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
3 changes: 2 additions & 1 deletion ClientLib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ apply plugin: 'com.getkeepsafe.dexcount'
ext {
VERSION_MAJOR = 3
VERSION_MINOR = 0
VERSION_PATCH = 1
VERSION_PATCH = 2
VERSION_SUFFIX = "release"

PUBLISH_ARTIFACT_ID = 'dronekit-android'
Expand Down Expand Up @@ -94,6 +94,7 @@ android {
testOptions {
unitTests.returnDefaultValues = true
}
buildToolsVersion '24.0.1'
}

dependencies {
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 @@ -385,6 +385,12 @@ protected boolean performTakeoff(Bundle data, ICommandListener listener) {

@Override
public void onMavLinkMessageReceived(MAVLinkMessage message) {

if (message.sysid != this.getSysid()) {
// Reject Messages that are not for the system id
return;
}

int compId = message.compid;
if (compId != AUTOPILOT_COMPONENT_ID
&& compId != ARTOO_COMPONENT_ID
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 Expand Up @@ -574,6 +575,11 @@ private void onHeartbeat(MAVLinkMessage msg) {
@Override
public void onMavLinkMessageReceived(MAVLinkMessage message) {

if (message.sysid != this.getSysid()) {
// Reject Messages that are not for the system id
return;
}

onHeartbeat(message);

switch (message.msgid) {
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);
compid = validateToUnsignedByteRange(msg.compid);
mMavlinkVersion = heartBeatMsg.mavlink_version;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

import com.MAVLink.common.msg_mission_item;
import com.MAVLink.enums.MAV_CMD;
import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;

import org.droidplanner.services.android.impl.core.helpers.geoTools.GeoTools;
import org.droidplanner.services.android.impl.core.mission.MissionImpl;
Expand All @@ -12,15 +14,13 @@
import org.droidplanner.services.android.impl.core.survey.CameraInfo;
import org.droidplanner.services.android.impl.core.survey.SurveyData;
import org.droidplanner.services.android.impl.core.survey.grid.GridBuilder;
import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;

import java.util.ArrayList;
import java.util.List;

public class StructureScannerImpl extends SpatialCoordItem {
private double radius = (10.0);
private double heightStep = (5);
private double radius = 10.0;
private double heightStep = 5;
private int numberOfSteps = 2;
private boolean crossHatch = false;
SurveyData survey = new SurveyData();
Expand Down Expand Up @@ -50,10 +50,12 @@ private void packROI(List<msg_mission_item> list) {
}

private void packCircles(List<msg_mission_item> list) {
for (double altitude = coordinate.getAltitude(); altitude <= getTopHeight(); altitude += heightStep) {
CircleImpl circleImpl = new CircleImpl(missionImpl, new LatLongAlt(coordinate, (altitude)));
double altitude = coordinate.getAltitude();
for (int iSteps = 0; iSteps < numberOfSteps; iSteps++) {
CircleImpl circleImpl = new CircleImpl(missionImpl, new LatLongAlt(coordinate, altitude));
circleImpl.setRadius(radius);
list.addAll(circleImpl.packMissionItem());
altitude+= heightStep;
}
}

Expand Down
2 changes: 1 addition & 1 deletion ClientLib/src/main/res/values/version.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<?xml version="1.0" encoding="utf-8"?>
<resources>
<integer name="core_lib_version">30000</integer>
<integer name="core_lib_version">30200</integer>
</resources>
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ DroneKit-Android helps you create powerful Android apps for UAVs.

[DroneKit-Android](http://android.dronekit.io/) is the implementation of [DroneKit](http://dronekit.io/) on Android.

The API provides interfaces that apps can use to control copters, planes, and ground vehicles. It is compatible with vehicles that communicate using the MAVLink protocol (including most vehicles made by 3DR and other members of the DroneCode foundation), and is validated against the open-source [ArduPilot flight control platform](ardupilot.com).
The API provides interfaces that apps can use to control copters, planes, and ground vehicles. It is compatible with vehicles that communicate using the MAVLink protocol (including most vehicles made by 3DR and other members of the DroneCode foundation), and is validated against the open-source [ArduPilot flight control platform](http://ardupilot.com).

This project implements the [DroneKit-Android Client library](http://android.dronekit.io) which allows developers to leverage the DroneKit API.

Expand Down
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ buildscript {
}

dependencies {
classpath 'com.android.tools.build:gradle:1.5.0'
classpath 'com.android.tools.build:gradle:2.2.0'

//Dexcount gradle plugin
classpath 'com.getkeepsafe.dexcount:dexcount-gradle-plugin:0.4.4'
Expand Down
2 changes: 2 additions & 0 deletions dependencyLibs/Mavlink/build.gradle
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
apply plugin: 'java'
sourceCompatibility = JavaVersion.VERSION_1_7
targetCompatibility = JavaVersion.VERSION_1_7

sourceSets {
main {
Expand Down
4 changes: 2 additions & 2 deletions gradle/wrapper/gradle-wrapper.properties
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#Sun Nov 30 09:39:49 PST 2014
#Sun Oct 09 17:42:15 PDT 2016
distributionBase=GRADLE_USER_HOME
distributionPath=wrapper/dists
zipStoreBase=GRADLE_USER_HOME
zipStorePath=wrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-2.10-all.zip
distributionUrl=https\://services.gradle.org/distributions/gradle-2.14.1-all.zip
6 changes: 6 additions & 0 deletions samples/StarterApp/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,12 @@ android {
abortOnError false
}

compileOptions {
sourceCompatibility JavaVersion.VERSION_1_7
targetCompatibility JavaVersion.VERSION_1_7
}

buildToolsVersion '24.0.1'
}

dependencies {
Expand Down