Skip to content

Commit 6e1de2d

Browse files
committed
Merge branches 'develop' and 'version_3.0.2' of github.com:dronekit/dronekit-android into version_3.0.2
2 parents 9761835 + 372d0f0 commit 6e1de2d

File tree

5 files changed

+27
-13
lines changed

5 files changed

+27
-13
lines changed

ClientLib/src/main/java/org/droidplanner/services/android/impl/core/MAVLink/MavLinkStreamRates.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@
77

88
public class MavLinkStreamRates {
99

10-
public static void setupStreamRates(DataLinkProvider MAVClient, byte sysid, byte compid,
10+
public static void setupStreamRates(DataLinkProvider MAVClient, short sysid, short compid,
1111
int extendedStatus, int extra1, int extra2, int extra3, int position, int rcChannels,
1212
int rawSensors, int rawControler) {
1313
requestMavlinkDataStream(MAVClient, sysid, compid, MAV_DATA_STREAM.MAV_DATA_STREAM_EXTENDED_STATUS,
@@ -22,8 +22,8 @@ public static void setupStreamRates(DataLinkProvider MAVClient, byte sysid, byte
2222
requestMavlinkDataStream(MAVClient, sysid, compid, MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, rcChannels);
2323
}
2424

25-
private static void requestMavlinkDataStream(DataLinkProvider mAVClient, byte sysid,
26-
byte compid, int stream_id, int rate) {
25+
private static void requestMavlinkDataStream(DataLinkProvider mAVClient, short sysid,
26+
short compid, int stream_id, int rate) {
2727
msg_request_data_stream msg = new msg_request_data_stream();
2828
msg.target_system = sysid;
2929
msg.target_component = compid;

ClientLib/src/main/java/org/droidplanner/services/android/impl/core/drone/DroneVariable.java

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,10 @@
99
import timber.log.Timber;
1010

1111
public class DroneVariable<T extends MavLinkDrone> {
12+
13+
static int UNSIGNED_BYTE_MIN_VALUE = 0;
14+
static int UNSIGNED_BYTE_MAX_VALUE = 255;
15+
1216
protected T myDrone;
1317

1418
public DroneVariable(T myDrone) {
@@ -75,4 +79,13 @@ public void run() {
7579
});
7680
}
7781
}
82+
83+
public static short validateToUnsignedByteRange(int id){
84+
if(id < UNSIGNED_BYTE_MIN_VALUE || id > UNSIGNED_BYTE_MAX_VALUE){
85+
throw new IllegalArgumentException("Value is outside of the range of an sysid/compid byte: " + id);
86+
}
87+
return (short)id;
88+
}
89+
90+
7891
}

ClientLib/src/main/java/org/droidplanner/services/android/impl/core/drone/autopilot/MavLinkDrone.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,9 +27,9 @@ public interface MavLinkDrone extends Drone {
2727

2828
void onMavLinkMessageReceived(MAVLinkMessage message);
2929

30-
public byte getSysid();
30+
public short getSysid();
3131

32-
public byte getCompid();
32+
public short getCompid();
3333

3434
public State getState();
3535

ClientLib/src/main/java/org/droidplanner/services/android/impl/core/drone/autopilot/generic/GenericMavLinkDrone.java

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -237,12 +237,13 @@ public boolean isConnectionAlive() {
237237
}
238238

239239
@Override
240-
public byte getSysid() {
240+
public short getSysid() {
241+
241242
return heartbeat.getSysid();
242243
}
243244

244245
@Override
245-
public byte getCompid() {
246+
public short getCompid() {
246247
return heartbeat.getCompid();
247248
}
248249

ClientLib/src/main/java/org/droidplanner/services/android/impl/core/drone/variables/HeartBeat.java

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,8 @@ public class HeartBeat extends DroneVariable implements OnDroneListener<MavLinkD
2424
protected static final int NORMAL_HEARTBEAT = 2;
2525

2626
protected int heartbeatState = FIRST_HEARTBEAT;
27-
private byte sysid = 1;
28-
private byte compid = 1;
27+
private short sysid = 1;
28+
private short compid = 1;
2929

3030
/**
3131
* Stores the version of the mavlink protocol.
@@ -46,11 +46,11 @@ public HeartBeat(MavLinkDrone myDrone, Handler handler) {
4646
myDrone.addDroneListener(this);
4747
}
4848

49-
public byte getSysid() {
49+
public short getSysid() {
5050
return sysid;
5151
}
5252

53-
public byte getCompid() {
53+
public short getCompid() {
5454
return compid;
5555
}
5656

@@ -64,8 +64,8 @@ public short getMavlinkVersion() {
6464
public void onHeartbeat(MAVLinkMessage msg) {
6565
msg_heartbeat heartBeatMsg = msg instanceof msg_heartbeat ? (msg_heartbeat) msg : null;
6666
if(heartBeatMsg != null){
67-
sysid = (byte) msg.sysid;
68-
compid = (byte) msg.compid;
67+
sysid = validateToUnsignedByteRange(msg.sysid);
68+
compid = validateToUnsignedByteRange(msg.compid);
6969
mMavlinkVersion = heartBeatMsg.mavlink_version;
7070
}
7171

0 commit comments

Comments
 (0)