Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

WIP: Adding Alt Frames (ie. Terrain) to API #460

Open
wants to merge 6 commits into
base: develop
Choose a base branch
from
Open
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
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package com.o3dr.services.android.lib.util;

import com.o3dr.services.android.lib.coordinate.Frame;
import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;

Expand Down Expand Up @@ -44,7 +45,8 @@ public class MathUtilsTest extends TestCase {

public void testGetDistance3D() throws Exception {
//Test get distance altitude only.
double distance = MathUtils.getDistance3D(new LatLongAlt(0.0, 0.0, 50.0), new LatLongAlt(0.0, 0.0, 100.0));
double distance = MathUtils.getDistance3D(new LatLongAlt(0.0, 0.0, 50.0, Frame.GLOBAL_RELATIVE),
new LatLongAlt(0.0, 0.0, 100.0, Frame.GLOBAL_RELATIVE));
assertEquals(distance, 50.0, MARGIN_OF_ERROR);
}

Expand Down Expand Up @@ -80,7 +82,8 @@ public void testGetDistance() throws Exception {
toLongitude = randDouble(rand, MIN_LONGITUDE, MAX_LONGITUDE);

//3D Distance equation
distance1 = MathUtils.getDistance3D(new LatLongAlt(fromLatitude, fromLongitude, 0.0), new LatLongAlt(toLatitude, toLongitude, 0.0));
distance1 = MathUtils.getDistance3D(new LatLongAlt(fromLatitude, fromLongitude, 0.0, Frame.GLOBAL_RELATIVE),
new LatLongAlt(toLatitude, toLongitude, 0.0, Frame.GLOBAL_RELATIVE));
//2D Distance equation
distance2 = MathUtils.getDistance2D(new LatLong(fromLatitude, fromLongitude), new LatLong(toLatitude, toLongitude));

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package org.droidplanner.services.android.impl.core.helpers.coordinates;

import com.o3dr.services.android.lib.coordinate.Frame;
import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;

Expand All @@ -9,7 +10,7 @@ public class Coord3DTest extends TestCase {

public void testConstructor() {
double alt = (50.0);
LatLongAlt point = new LatLongAlt(10, -5.6, alt);
LatLongAlt point = new LatLongAlt(10, -5.6, alt, Frame.GLOBAL_RELATIVE);
assertEquals(10.0, point.getLatitude());
assertEquals(-5.6, point.getLongitude());
assertEquals(alt, point.getAltitude());
Expand All @@ -18,7 +19,7 @@ public void testConstructor() {
public void testConstFrom2dCoord() {
double alt = (5.0);
LatLong point2d = new LatLong(1, -0.6);
LatLongAlt point = new LatLongAlt(point2d, alt);
LatLongAlt point = new LatLongAlt(point2d, alt, Frame.GLOBAL_RELATIVE);

assertEquals(1.0, point.getLatitude());
assertEquals(-0.6, point.getLongitude());
Expand All @@ -27,7 +28,7 @@ public void testConstFrom2dCoord() {

public void testSet() {
double alt = (50.0);
LatLongAlt point = new LatLongAlt(10, -5.6, alt);
LatLongAlt point = new LatLongAlt(10, -5.6, alt, Frame.GLOBAL_RELATIVE);
point.setLatitude(0);
point.setLongitude(0);
point.setAltitude(alt);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package org.droidplanner.services.android.impl.core.helpers.geoTools;

import com.o3dr.services.android.lib.coordinate.Frame;
import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;

Expand All @@ -10,8 +11,8 @@

public class GeoToolsTest extends TestCase {

LatLongAlt p1 = new LatLongAlt(37.85363485683941, -122.4204097390123, (250.0));
LatLongAlt p2 = new LatLongAlt(37.85130335221235, -122.4142645673542, (0.0));
LatLongAlt p1 = new LatLongAlt(37.85363485683941, -122.4204097390123, (250.0), Frame.GLOBAL_RELATIVE);
LatLongAlt p2 = new LatLongAlt(37.85130335221235, -122.4142645673542, (0.0), Frame.GLOBAL_RELATIVE);
double polygonArea = 502915;
double dist2DP1toP2 = 599.26;
double dist3DP1toP2 = 649.32;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import com.MAVLink.common.msg_mission_item;
import com.MAVLink.enums.MAV_FRAME;
import com.o3dr.services.android.lib.coordinate.Frame;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;

import junit.framework.TestCase;
Expand All @@ -12,7 +13,7 @@ public class SpatialCoordItemTest extends TestCase {

public void testPackMissionItem() {
MissionImpl missionImpl = new MissionImpl(null);
WaypointImpl item = new WaypointImpl(missionImpl, new LatLongAlt(0.1, 1, (2)));
WaypointImpl item = new WaypointImpl(missionImpl, new LatLongAlt(0.1, 1, (2), Frame.GLOBAL_RELATIVE));

msg_mission_item mavMsg = item.packMissionItem().get(0);

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

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

import junit.framework.TestCase;
Expand All @@ -14,7 +15,7 @@ public class WaypointImplTest extends TestCase {

public void testPackMissionItem() {
MissionImpl missionImpl = new MissionImpl(null);
WaypointImpl item = new WaypointImpl(missionImpl, new LatLongAlt(0, 1, (2)));
WaypointImpl item = new WaypointImpl(missionImpl, new LatLongAlt(0, 1, (2), Frame.GLOBAL_RELATIVE));

List<msg_mission_item> listOfMsg = item.packMissionItem();
assertEquals(1, listOfMsg.size());
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
package com.o3dr.services.android.lib.coordinate;

import com.MAVLink.enums.MAV_FRAME;

/** TODO This is the start of using a more generic location/frame class
* The frame for LatLongAlt would only ever be GLOBAL and not LOCAL.
*/

public enum Frame {
GLOBAL_ABS ("Absolute" , "Abs", 0 ), // Absolute means Above Mean Sea Level AMSL
LOCAL_NED ("Local NED", "NED", 1 ),
MISSION ("Mission" , "MIS", 2 ),
GLOBAL_RELATIVE ("Relative" , "Rel", 3 ), // Relative to HOME location
LOCAL_ENU ("Local ENU", "ENU", 4 ),
GLOBAL_TERRAIN ("Terrain" , "Ter", 10); // Relative to Terrain Level. (Either measured or from STRM)

private final int frame;
private final String name;
private final String abbreviation;
Copy link
Member

Choose a reason for hiding this comment

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

@billbonney I'd advocate for the removal of the frame field since it can be substitute by the enum itself.


Frame(String name, String abbreviation, int frame ) {
this.name = name;
this.abbreviation = abbreviation;
this.frame = frame;
}

public String getName() {
return name;
}

public String getAbbreviation() {
return abbreviation;
}

public int asInt() {
return frame;
}

public static Frame getFrame(int mavFrame) {

switch (mavFrame) {
case MAV_FRAME.MAV_FRAME_GLOBAL:
case MAV_FRAME.MAV_FRAME_GLOBAL_INT:
return Frame.GLOBAL_ABS;

case MAV_FRAME.MAV_FRAME_MISSION:
return Frame.MISSION;

case MAV_FRAME.MAV_FRAME_LOCAL_NED:
return Frame.LOCAL_NED;

case MAV_FRAME.MAV_FRAME_LOCAL_ENU:
return Frame.LOCAL_NED;

case MAV_FRAME.MAV_FRAME_GLOBAL_TERRAIN_ALT:
case MAV_FRAME.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
return Frame.GLOBAL_TERRAIN;

case MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
default:
return Frame.GLOBAL_RELATIVE;
}

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,11 @@ public class LatLong implements Parcelable, Serializable {
private double latitude;
private double longitude;

public LatLong(){
Copy link
Member

Choose a reason for hiding this comment

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

@billbonney I don't agree with having a default constructor. This is usually the cause of subtle and hard to find bugs. In which scenario would having a default constructor be helpful?

this.latitude = -100.0; // TODO: Should we set this to invalid ie -100.0 ?
this.longitude = -190.0;// TODO: Should we set this to invalid ie -190.0 ?
}

public LatLong(double latitude, double longitude){
this.latitude = latitude;
this.longitude = longitude;
Expand All @@ -32,6 +37,23 @@ public void set(LatLong update){
this.longitude = update.longitude;
}

/**
* @return if this is a valid LatLong global point
*/
public boolean isValid() {

if ( this.longitude > 180.0 || this.latitude > 90.0
|| this.longitude < -180.0 || this.latitude < -90.0 ) {
return false; // Not a valid location

} if (Double.compare(this.longitude, 0.0) == 0 && Double.compare(this.latitude, 0.0) == 0) {
return false; // Rarely in 0.0,0.0 a valid location, so reject.

} else {
return true;
}
}

/**
* @return the latitude in degrees
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
/**
* Stores latitude, longitude, and altitude information for a coordinate.
*/

public class LatLongAlt extends LatLong {

private static final long serialVersionUID =-4771550293045623743L;
Expand All @@ -14,24 +15,34 @@ public class LatLongAlt extends LatLong {
* Stores the altitude in meters.
*/
private double mAltitude;
private Frame mFrame;

public LatLongAlt() {
Copy link
Member

Choose a reason for hiding this comment

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

@billbonney Same comment as with LatLong. I fail to see the utility of a default constructor.

Copy link
Collaborator Author

@billbonney billbonney Nov 15, 2016

Choose a reason for hiding this comment

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

I can refactor this. It was a 'quick fix'. To resolve some npe I was having.

LATER: The issue is this in BaseSpatial. And that it constructed without a point.

public LatLongAlt getCoordinate() {
        if (coordinate == null)
            coordinate = new LatLongAlt();
        return coordinate;
    }

Which means it's partially created object. And then set to call here

public void addSpatialWaypoint(BaseSpatialItem spatialItem, LatLong point) {
        double alt = getLastAltitude();
        spatialItem.getCoordinate().set(point);
        spatialItem.getCoordinate().setAltitude(alt);
        addMissionItem(spatialItem);
    }

The fix was to have getCoordinate to create a LatLngAlt when none existed. I can add the parameter list there.

The real fix is to refactor BaseSpatial on construction to take a point so it's not null in the first place (but that may break getNewItem for other mission items (i'll need to think about that)

@Override
    public void onMapClick(LatLong point) {
        if (missionProxy == null) return;

        // If an mission item is selected, unselect it.
        missionProxy.selection.clearSelection();

        if (selectedType == null)
            return;

        BaseSpatialItem spatialItem = (BaseSpatialItem) selectedType.getNewItem();
        missionProxy.addSpatialWaypoint(spatialItem, point);
    }

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

it looks like the above is related with change b343b8c

super();
mAltitude = 0.0;
mFrame = Frame.GLOBAL_RELATIVE;
}

public LatLongAlt(double latitude, double longitude, double altitude) {
public LatLongAlt(double latitude, double longitude, double altitude, Frame frame) {
Copy link
Member

Choose a reason for hiding this comment

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

@billbonney Given that Frame.GLOBAL_RELATIVE is the default frame, you could include an additional constructor that omit the frame parameter and sets mFrame to Frame.GLOBAL_RELATIVE.
This removes the need to update all the files where the constructor is invoked.

Copy link
Collaborator Author

@billbonney billbonney Nov 15, 2016

Choose a reason for hiding this comment

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

I did that for a reason in that it exposes the parts in the code that sets the frame. I.e you can see explicitly what frame is being assumed. You don't want to accidentally put abs alt into relative. It would seem like a flyaway.

(LATER: Ironically, this is similar thought why default constructors are bad, it hides assumptions)

super(latitude, longitude);
mAltitude = altitude;
mFrame = frame;
}

public LatLongAlt(LatLong location, double altitude){
public LatLongAlt(LatLong location, double altitude, Frame frame){
super(location);
mAltitude = altitude;
mFrame = frame;
}

public LatLongAlt(LatLongAlt copy) {
this(copy.getLatitude(), copy.getLongitude(), copy.getAltitude());
this(copy.getLatitude(), copy.getLongitude(), copy.getAltitude(), copy.getFrame());
}

public void set(LatLongAlt source){
public void set(LatLongAlt source){ // TODO: this looks wrong
Copy link
Member

Choose a reason for hiding this comment

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

@billbonney How so?

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

It's like a shallow copy, i'm not sure when set is called and why? why is using set different from
latLgAlt1 = latLgAlt2

super.set(source);
this.mAltitude = source.mAltitude;
this.mFrame = source.mFrame;
}

/**
Expand All @@ -45,6 +56,18 @@ public void setAltitude(double altitude) {
this.mAltitude = altitude;
}

public Frame getFrame() {
return mFrame;
}

public boolean setFrame(Frame frame) {
if (mFrame != frame) {
mFrame = frame;
return true;
}
return false;
}

@Override
public boolean equals(Object o) {
if (this == o) return true;
Expand All @@ -53,7 +76,9 @@ public boolean equals(Object o) {

LatLongAlt that = (LatLongAlt) o;

if (Double.compare(that.mAltitude, mAltitude) != 0) return false;
if ((Double.compare(that.mAltitude, mAltitude) != 0)
&& (that.mFrame.asInt() != mFrame.asInt()) )
Copy link
Member

Choose a reason for hiding this comment

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

@billbonney Since mFrame is an enum, you can just compare it using that.mFrame != mFrame.

Copy link
Member

Choose a reason for hiding this comment

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

In addition, the equals(), hashCode() and toString() methods were generated automatically via Android Studio: Code => Generate.

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Ok, good tip... I'll check that.

return false;

return true;
}
Expand All @@ -63,7 +88,7 @@ public int hashCode() {
int result = super.hashCode();
long temp;
temp = Double.doubleToLongBits(mAltitude);
result = 31 * result + (int) (temp ^ (temp >>> 32));
result = 31 * result + (int) (temp ^ (temp >>> 32)); // TODO Check this hash is OK with frame
return result;
}

Expand All @@ -73,6 +98,7 @@ public String toString() {
return "LatLongAlt{" +
superToString +
", mAltitude=" + mAltitude +
", mFrame=" + mFrame.getAbbreviation() +
'}';
}

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

import android.os.Parcel;

import com.o3dr.services.android.lib.coordinate.Frame;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;

import java.nio.ByteBuffer;
Expand All @@ -26,7 +27,7 @@ public class SoloCableCamWaypoint extends TLVPacket {

public SoloCableCamWaypoint(double latitude, double longitude, float altitude, float degreesYaw, float pitch) {
super(TLVMessageTypes.TYPE_SOLO_CABLE_CAM_WAYPOINT, 28);
this.coordinate = new LatLongAlt(latitude, longitude, altitude);
this.coordinate = new LatLongAlt(latitude, longitude, altitude, Frame.GLOBAL_RELATIVE);
this.degreesYaw = degreesYaw;
this.pitch = pitch;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import android.os.Parcel;

import com.o3dr.services.android.lib.coordinate.Frame;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;

import java.nio.ByteBuffer;
Expand All @@ -15,7 +16,7 @@ public class SoloMessageLocation extends TLVPacket {

public SoloMessageLocation(double latitude, double longitude, float altitudeInMeters) {
super(TLVMessageTypes.TYPE_SOLO_MESSAGE_LOCATION, 20);
this.coordinate = new LatLongAlt(latitude, longitude, altitudeInMeters);
this.coordinate = new LatLongAlt(latitude, longitude, altitudeInMeters, Frame.GLOBAL_RELATIVE);
}

public SoloMessageLocation(LatLongAlt coordinate){
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import android.os.Parcel;

import com.o3dr.services.android.lib.coordinate.Frame;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;

import java.nio.ByteBuffer;
Expand All @@ -19,7 +20,7 @@ public class SoloReturnHomeLocationMessage extends TLVPacket {

public SoloReturnHomeLocationMessage(double latitude, double longitude, float altitudeInMeters) {
super(TLVMessageTypes.TYPE_RTL_HOME_POINT, 20);
this.coordinate = new LatLongAlt(latitude, longitude, altitudeInMeters);
this.coordinate = new LatLongAlt(latitude, longitude, altitudeInMeters, Frame.GLOBAL_RELATIVE);
}

public SoloReturnHomeLocationMessage(LatLongAlt coordinate){
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import android.os.Parcel;

import com.o3dr.services.android.lib.coordinate.Frame;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;
import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVMessageTypes;
import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket;
Expand Down Expand Up @@ -100,7 +101,10 @@ public SoloSplinePoint(ByteBuffer dataBuffer){
this(dataBuffer.getShort(),
dataBuffer.getFloat(),
dataBuffer.getInt(),
new LatLongAlt(dataBuffer.getDouble(), dataBuffer.getDouble(), dataBuffer.getFloat()),
new LatLongAlt(dataBuffer.getDouble(),
dataBuffer.getDouble(),
dataBuffer.getFloat(),
Frame.GLOBAL_RELATIVE),
dataBuffer.getFloat(),
dataBuffer.getFloat(),
dataBuffer.getFloat(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -277,7 +277,7 @@ public static ConnectionParameter newSoloConnection(String ssid, @Nullable Strin
eventsDispatchingPeriod);
}

private ConnectionParameter(@ConnectionType.Type int connectionType, Bundle paramsBundle){
public ConnectionParameter(@ConnectionType.Type int connectionType, Bundle paramsBundle){
Copy link
Member

Choose a reason for hiding this comment

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

@billbonney Why make this public?

Copy link
Collaborator Author

@billbonney billbonney Nov 15, 2016

Choose a reason for hiding this comment

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

I was having a build issue with this being private. I haven't investigated, and had not meant for it to be checked in. I should put a TODO on it, and come back and investigate.

Choose a reason for hiding this comment

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

As far as I remember class BasicTest complains about the access to this constructor while compilation:
https://github.com/dronekit/dronekit-android/blob/develop/ClientLib/src/androidTest/java/org/droidplanner/services/android/impl/BasicTest.java#L60

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

@mariansoban Thanks. I can revert this change for now and we can look at fixing the test cases

this(connectionType, paramsBundle, null);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ public String toString() {

@Override
public LatLongAlt getCoordinate() {
if (coordinate == null)
coordinate = new LatLongAlt();
return coordinate;
}

Expand Down
Loading