Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions ClientLib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@ apply plugin: 'com.getkeepsafe.dexcount'
ext {
VERSION_MAJOR = 3
VERSION_MINOR = 0
VERSION_PATCH = 1
VERSION_SUFFIX = "release"
VERSION_PATCH = 2
VERSION_SUFFIX = "beta1"

PUBLISH_ARTIFACT_ID = 'dronekit-android'
PUBLISH_VERSION = generateVersionName("", VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH, VERSION_SUFFIX)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

public class MavLinkStreamRates {

public static void setupStreamRates(DataLinkProvider MAVClient, byte sysid, byte compid,
public static void setupStreamRates(DataLinkProvider MAVClient, short sysid, short compid,
int extendedStatus, int extra1, int extra2, int extra3, int position, int rcChannels,
int rawSensors, int rawControler) {
requestMavlinkDataStream(MAVClient, sysid, compid, MAV_DATA_STREAM.MAV_DATA_STREAM_EXTENDED_STATUS,
Expand All @@ -22,8 +22,8 @@ public static void setupStreamRates(DataLinkProvider MAVClient, byte sysid, byte
requestMavlinkDataStream(MAVClient, sysid, compid, MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, rcChannels);
}

private static void requestMavlinkDataStream(DataLinkProvider mAVClient, byte sysid,
byte compid, int stream_id, int rate) {
private static void requestMavlinkDataStream(DataLinkProvider mAVClient, short sysid,
short compid, int stream_id, int rate) {
msg_request_data_stream msg = new msg_request_data_stream();
msg.target_system = sysid;
msg.target_component = compid;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,10 @@
import timber.log.Timber;

public class DroneVariable<T extends MavLinkDrone> {

static int UNSIGNED_BYTE_MIN_VALUE = 0;
static int UNSIGNED_BYTE_MAX_VALUE = 255;

protected T myDrone;

public DroneVariable(T myDrone) {
Expand Down Expand Up @@ -75,4 +79,13 @@ public void run() {
});
}
}

public static short validateToUnsignedByteRange(int id){
if(id < UNSIGNED_BYTE_MIN_VALUE || id > UNSIGNED_BYTE_MAX_VALUE){
throw new IllegalArgumentException("Value is outside of the range of an sysid/compid byte: " + id);
}
return (short)id;
}


}
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,9 @@ public interface MavLinkDrone extends Drone {

void onMavLinkMessageReceived(MAVLinkMessage message);

public byte getSysid();
public short getSysid();

public byte getCompid();
public short getCompid();

public State getState();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -237,12 +237,13 @@ public boolean isConnectionAlive() {
}

@Override
public byte getSysid() {
public short getSysid() {

return heartbeat.getSysid();
}

@Override
public byte getCompid() {
public short getCompid() {
return heartbeat.getCompid();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ public class HeartBeat extends DroneVariable implements OnDroneListener<MavLinkD
protected static final int NORMAL_HEARTBEAT = 2;

protected int heartbeatState = FIRST_HEARTBEAT;
private byte sysid = 1;
private byte compid = 1;
private short sysid = 1;
private short compid = 1;

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

public byte getSysid() {
public short getSysid() {
return sysid;
}

public byte getCompid() {
public short getCompid() {
return compid;
}

Expand All @@ -64,8 +64,8 @@ public short getMavlinkVersion() {
public void onHeartbeat(MAVLinkMessage msg) {
msg_heartbeat heartBeatMsg = msg instanceof msg_heartbeat ? (msg_heartbeat) msg : null;
if(heartBeatMsg != null){
sysid = (byte) msg.sysid;
compid = (byte) msg.compid;
sysid = validateToUnsignedByteRange(msg.sysid);
Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I added this check, so that an invalid conversion would break, but since this comes over the wire it would be safe to cast from int to short. I think where the java library goes wrong is that it uses int in the first place. if it used short these issue would have shown up, as there would be no need to cast and therefore mask the problem.

compid = validateToUnsignedByteRange(msg.compid);
mMavlinkVersion = heartBeatMsg.mavlink_version;
}

Expand Down