From 62bbc6de8cb45509b622257a96bbe5e8c5201679 Mon Sep 17 00:00:00 2001
From: Charles Rothbaum
<33434729+mynamecharlesrothbaum@users.noreply.github.com>
Date: Mon, 8 Apr 2024 20:43:55 -0600
Subject: [PATCH 1/4] force arm btn
---
.idea/compiler.xml | 2 +-
.idea/deploymentTargetDropDown.xml | 10 ++++++++++
.idea/gradle.xml | 5 ++---
.idea/migrations.xml | 10 ++++++++++
.idea/misc.xml | 2 +-
.../com/chobitsfan/minigcs/MainActivity.java | 2 ++
.../com/chobitsfan/minigcs/MyMavlinkWork.java | 18 ++++++++++++++++++
app/src/main/res/layout/activity_main.xml | 6 +++---
8 files changed, 47 insertions(+), 8 deletions(-)
create mode 100644 .idea/deploymentTargetDropDown.xml
create mode 100644 .idea/migrations.xml
diff --git a/.idea/compiler.xml b/.idea/compiler.xml
index fb7f4a8..b589d56 100644
--- a/.idea/compiler.xml
+++ b/.idea/compiler.xml
@@ -1,6 +1,6 @@
-
+
\ No newline at end of file
diff --git a/.idea/deploymentTargetDropDown.xml b/.idea/deploymentTargetDropDown.xml
new file mode 100644
index 0000000..0c0c338
--- /dev/null
+++ b/.idea/deploymentTargetDropDown.xml
@@ -0,0 +1,10 @@
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/.idea/gradle.xml b/.idea/gradle.xml
index a0de2a1..0897082 100644
--- a/.idea/gradle.xml
+++ b/.idea/gradle.xml
@@ -4,16 +4,15 @@
diff --git a/.idea/migrations.xml b/.idea/migrations.xml
new file mode 100644
index 0000000..f8051a6
--- /dev/null
+++ b/.idea/migrations.xml
@@ -0,0 +1,10 @@
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/.idea/misc.xml b/.idea/misc.xml
index 54d5acd..0ad17cb 100644
--- a/.idea/misc.xml
+++ b/.idea/misc.xml
@@ -1,7 +1,7 @@
-
+
diff --git a/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java b/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java
index 4655be5..300eb26 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java
@@ -123,6 +123,8 @@ public void onRTLBtn(View view) {
mav_work.setModeRTL();
}
+ public void onArmBtn(View view) {mav_work.forceArm();}
+
public void onRebootBtn(View view) {
long ts = SystemClock.elapsedRealtime();
if (ts - reboot_ts > 3000) {
diff --git a/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java b/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
index bd7ca2f..9547556 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
@@ -118,6 +118,24 @@ public void writeParam(String name, float val) {
}
}
+ public void forceArm() {
+ try {
+ // Create a CommandLong MAVLink message to arm the vehicle.
+ // param1 = 1 (to arm the vehicle),
+ // param2 = 21196 (magic number to bypass pre-arm checks and force arm)
+ CommandLong command = CommandLong.builder()
+ .command(MavCmd.MAV_CMD_COMPONENT_ARM_DISARM)
+ .param1(1)
+ .param2(21196)
+ .build();
+
+ // Send the command to the vehicle.
+ mav_conn.send1(255, 0, command);
+ } catch (IOException e) {
+ if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to send force arm command: " + e.getMessage());
+ }
+ }
+
public void rebootFC() {
try {
mav_conn.send1(255, 0, CommandLong.builder().command(MavCmd.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN).param1(1).build());
diff --git a/app/src/main/res/layout/activity_main.xml b/app/src/main/res/layout/activity_main.xml
index 7a15a75..2177d10 100644
--- a/app/src/main/res/layout/activity_main.xml
+++ b/app/src/main/res/layout/activity_main.xml
@@ -106,11 +106,11 @@
android:text="Land" />
+ android:onClick="onArmBtn"
+ android:text="Force Arm" />
Date: Mon, 15 Apr 2024 23:57:18 -0600
Subject: [PATCH 2/4] init
---
.idea/misc.xml | 1 -
.../com/chobitsfan/minigcs/ArduCopter.java | 9 ++-
.../com/chobitsfan/minigcs/ArduPlane.java | 33 ---------
.../com/chobitsfan/minigcs/MainActivity.java | 30 +++++++-
.../com/chobitsfan/minigcs/MyMavlinkWork.java | 70 ++++++++++++++++---
.../java/com/chobitsfan/minigcs/Vehicle.java | 11 +--
app/src/main/res/layout/activity_main.xml | 63 +++++++++++++++++
7 files changed, 158 insertions(+), 59 deletions(-)
delete mode 100644 app/src/main/java/com/chobitsfan/minigcs/ArduPlane.java
diff --git a/.idea/misc.xml b/.idea/misc.xml
index 0ad17cb..8978d23 100644
--- a/.idea/misc.xml
+++ b/.idea/misc.xml
@@ -1,4 +1,3 @@
-
diff --git a/app/src/main/java/com/chobitsfan/minigcs/ArduCopter.java b/app/src/main/java/com/chobitsfan/minigcs/ArduCopter.java
index 02c04f8..d402192 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/ArduCopter.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/ArduCopter.java
@@ -21,9 +21,12 @@ public Object Land() {
return SetMode.builder().baseMode(MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED).customMode(9).build();
}
- @Override
- public Object RTL() {
- return SetMode.builder().baseMode(MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED).customMode(6).build();
+ public Object Guided(){
+ return SetMode.builder().baseMode(MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED).customMode(4).build();
+ }
+
+ public Object Stabilize(){
+ return SetMode.builder().baseMode(MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED).customMode(0).build();
}
@Override
diff --git a/app/src/main/java/com/chobitsfan/minigcs/ArduPlane.java b/app/src/main/java/com/chobitsfan/minigcs/ArduPlane.java
deleted file mode 100644
index 70b6500..0000000
--- a/app/src/main/java/com/chobitsfan/minigcs/ArduPlane.java
+++ /dev/null
@@ -1,33 +0,0 @@
-package com.chobitsfan.minigcs;
-
-import io.dronefleet.mavlink.common.MavModeFlag;
-import io.dronefleet.mavlink.common.SetMode;
-
-public class ArduPlane extends Vehicle {
- String[] FLIGHT_MODE = {"MANUAL", "CIRCLE", "STABILIZE", "TRAINING", "ACRO", "FBWA", "FBWB", "CRUISE", "AUTOTUNE", "", "AUTO", "RTL", "LOITER", "TAKEOFF", "AVOID_ADSB", "GUIDED"};
- static ArduPlane instance = new ArduPlane();
-
- public static ArduPlane getInstance() {
- return instance;
- }
-
- @Override
- public String Mode(int customMode) {
- if (customMode >= FLIGHT_MODE.length) return "Mode " + customMode; else return FLIGHT_MODE[customMode];
- }
-
- @Override
- public Object Land() {
- return SetMode.builder().baseMode(MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED).customMode(11).build();
- }
-
- @Override
- public Object RTL() {
- return SetMode.builder().baseMode(MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED).customMode(11).build();
- }
-
- @Override
- public String Name() {
- return "ArduPlane";
- }
-}
diff --git a/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java b/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java
index 300eb26..631d2ed 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java
@@ -119,11 +119,17 @@ public void onLandBtn(View view) {
mav_work.setModeLand();
}
- public void onRTLBtn(View view) {
- mav_work.setModeRTL();
+ public void onArmBtn(View view) {
+ mav_work.forceArm();
}
- public void onArmBtn(View view) {mav_work.forceArm();}
+ public void onTakeoffBtn(View view){ mav_work.takeoff(); }
+
+ public void onGuidedBtn(View view){ mav_work.setModeGuided(); }
+
+ public void onStabilizeBtn(View view){ mav_work.setModeStabilize(); }
+
+ public void onSendLocalWaypoint(View view){ mav_work.sendLocalWaypoint(); }
public void onRebootBtn(View view) {
long ts = SystemClock.elapsedRealtime();
@@ -137,6 +143,23 @@ public void onRebootBtn(View view) {
}
}
+ private void onSubmitWaypoint(String waypointText) {
+ String[] parts = waypointText.split(",");
+ if(parts.length == 3) {
+ try {
+ float lat = Float.parseFloat(parts[0].trim());
+ float lon = Float.parseFloat(parts[1].trim());
+ float alt = Float.parseFloat(parts[2].trim());
+ mav_work.sendLocalWaypoint();
+ } catch(NumberFormatException e) {
+ Toast.makeText(MainActivity.this, "Invalid waypoint format", Toast.LENGTH_SHORT).show();
+ }
+ } else {
+ Toast.makeText(MainActivity.this, "Waypoint format should be lat,lon,alt", Toast.LENGTH_SHORT).show();
+ }
+ }
+
+
public void onReadParam(View view) {
TextView tv = (TextView)findViewById(R.id.param_name);
String param_name = tv.getText().toString();
@@ -195,6 +218,7 @@ protected void onCreate(Bundle savedInstanceState) {
Thread t2 = new Thread(serialListener);
t2.start();
+
detectMyDevice();
}
diff --git a/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java b/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
index 9547556..6523b7c 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
@@ -21,9 +21,11 @@
import io.dronefleet.mavlink.common.Heartbeat;
import io.dronefleet.mavlink.common.MavAutopilot;
import io.dronefleet.mavlink.common.MavCmd;
+import io.dronefleet.mavlink.common.MavFrame;
import io.dronefleet.mavlink.common.MavModeFlag;
import io.dronefleet.mavlink.common.MavParamType;
import io.dronefleet.mavlink.common.MavType;
+import io.dronefleet.mavlink.common.MissionItemInt;
import io.dronefleet.mavlink.common.MissionItemReached;
import io.dronefleet.mavlink.common.ParamRequestRead;
import io.dronefleet.mavlink.common.ParamSet;
@@ -84,17 +86,67 @@ public MyMavlinkWork(Handler handler, InputStream is, OutputStream os) {
t1.start();
}
- public void setModeLand() {
+ public void takeoff() {
try {
- mav_conn.send1(255,0, vehicle.Land());
+ CommandLong takeoffCommand = CommandLong.builder()
+ .command(MavCmd.MAV_CMD_NAV_TAKEOFF)
+ .param7(3) // set to desired altitude in meters
+ .build();
+
+ mav_conn.send1(255, 0, takeoffCommand);
} catch (IOException e) {
- if (MyAppConfig.DEBUG) Log.d("chobits", e.getMessage());
+ if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to send takeoff command: " + e.getMessage());
}
}
- public void setModeRTL() {
+ public void setModeGuided() {
try {
- mav_conn.send1(255,0, vehicle.RTL());
+ mav_conn.send1(255,0, vehicle.Guided());
+ } catch (IOException e) {
+ if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to set mode to Guided: " + e.getMessage());
+ }
+ }
+ public void setModeStabilize() {
+ try {
+ mav_conn.send1(255,0, vehicle.Stabilize());
+ } catch (IOException e) {
+ if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to set mode to Stabilize: " + e.getMessage());
+ }
+ }
+
+ public void sendLocalWaypoint() {
+ float lat = 2;
+ float lon = 2;
+ float alt = 4;
+ try {
+ MissionItemInt waypointCommand = MissionItemInt.builder()
+ .targetSystem(255) // System ID for the target system/vehicle
+ .targetComponent(0) // Component ID for the target component
+ .seq(0) // Sequence number of the waypoint
+ .frame(MavFrame.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) // Use relative altitude
+ .command(MavCmd.MAV_CMD_NAV_WAYPOINT) // Command to navigate to a waypoint
+ .current(1) // Set to 1 to indicate this is the current waypoint
+ .autocontinue(1) // Set to 1 to allow auto-continuing to the next waypoint
+ .param1(0) // Hold time in seconds (ignored for simple waypoint navigation)
+ .param2(0) // Acceptance radius in meters (if the vehicle is within this distance of the waypoint, consider it reached)
+ .param3(0) // Pass-through waypoint (0 to fly directly to the waypoint)
+ .param4(0) // Desired yaw angle at waypoint (ignored unless YAW_ANGLE is used)
+ .x((int) (lat * 1E7)) // Latitude in decimal degrees * 1E7
+ .y((int) (lon * 1E7)) // Longitude in decimal degrees * 1E7
+ .z(alt) // Altitude in meters
+ .build();
+
+ mav_conn.send1(255, 0, waypointCommand);
+ } catch (IOException e) {
+ if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to send local waypoint: " + e.getMessage());
+ }
+ }
+
+
+
+ public void setModeLand() {
+ try {
+ mav_conn.send1(255,0, vehicle.Land());
} catch (IOException e) {
if (MyAppConfig.DEBUG) Log.d("chobits", e.getMessage());
}
@@ -120,16 +172,12 @@ public void writeParam(String name, float val) {
public void forceArm() {
try {
- // Create a CommandLong MAVLink message to arm the vehicle.
- // param1 = 1 (to arm the vehicle),
- // param2 = 21196 (magic number to bypass pre-arm checks and force arm)
CommandLong command = CommandLong.builder()
.command(MavCmd.MAV_CMD_COMPONENT_ARM_DISARM)
- .param1(1)
- .param2(21196)
+ .param1(1) // param1 = 1 (to arm the vehicle),
+ .param2(21196) // param2 = 21196 (magic number to bypass pre-arm checks and force arm)
.build();
- // Send the command to the vehicle.
mav_conn.send1(255, 0, command);
} catch (IOException e) {
if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to send force arm command: " + e.getMessage());
diff --git a/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java b/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java
index 5f36f97..b081595 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java
@@ -6,13 +6,8 @@
public abstract class Vehicle {
public abstract String Mode(int customMode);
public abstract Object Land();
- public abstract Object RTL();
+ public abstract Object Guided();
+ public abstract Object Stabilize();
public abstract String Name();
- public static Vehicle getInstance(MavAutopilot autopilot, MavType type) {
- if (type == MavType.MAV_TYPE_FIXED_WING) {
- return ArduPlane.getInstance();
- } else {
- return ArduCopter.getInstance();
- }
- }
+ public static Vehicle getInstance(MavAutopilot autopilot, MavType type) {return ArduCopter.getInstance();}
}
diff --git a/app/src/main/res/layout/activity_main.xml b/app/src/main/res/layout/activity_main.xml
index 2177d10..756d866 100644
--- a/app/src/main/res/layout/activity_main.xml
+++ b/app/src/main/res/layout/activity_main.xml
@@ -112,6 +112,64 @@
android:onClick="onArmBtn"
android:text="Force Arm" />
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
From 2bd736e32ea2239329870694f21bb0f95853cea9 Mon Sep 17 00:00:00 2001
From: Charles Rothbaum
<33434729+mynamecharlesrothbaum@users.noreply.github.com>
Date: Thu, 18 Apr 2024 21:21:38 -0600
Subject: [PATCH 3/4] map and new layout
---
app/build.gradle | 6 +-
app/src/main/AndroidManifest.xml | 8 +
.../com/chobitsfan/minigcs/MainActivity.java | 203 +++++++++++++-----
.../com/chobitsfan/minigcs/MyMavlinkWork.java | 18 +-
app/src/main/res/layout/activity_main.xml | 195 +++++++----------
5 files changed, 245 insertions(+), 185 deletions(-)
diff --git a/app/build.gradle b/app/build.gradle
index cdccf77..970f0cb 100644
--- a/app/build.gradle
+++ b/app/build.gradle
@@ -4,12 +4,13 @@ plugins {
android {
namespace 'com.chobitsfan.minigcs'
- compileSdk 32
+ compileSdk 33
defaultConfig {
applicationId "com.chobitsfan.minigcs"
minSdk 26
- targetSdk 32
+ //noinspection EditedTargetSdkVersion
+ targetSdk 33
versionCode 10
versionName "2.0"
@@ -33,6 +34,7 @@ dependencies {
implementation 'androidx.appcompat:appcompat:1.4.1'
implementation 'com.google.android.material:material:1.5.0'
implementation 'androidx.constraintlayout:constraintlayout:2.1.3'
+ implementation 'org.osmdroid:osmdroid-android:6.1.14'
testImplementation 'junit:junit:4.13.2'
androidTestImplementation 'androidx.test.ext:junit:1.1.3'
androidTestImplementation 'androidx.test.espresso:espresso-core:3.4.0'
diff --git a/app/src/main/AndroidManifest.xml b/app/src/main/AndroidManifest.xml
index e9c99d2..880d8e1 100644
--- a/app/src/main/AndroidManifest.xml
+++ b/app/src/main/AndroidManifest.xml
@@ -2,7 +2,15 @@
+
+
+
+
+
+
+
Satellites
"+data.getInt("satellites")+"", Html.FROM_HTML_MODE_COMPACT));
break;
- case MyMavlinkWork.UI_PARAM_VAL:
- data = msg.getData();
- tv = (TextView)findViewById(R.id.param_val);
- if (((TextView)findViewById(R.id.param_name)).getText().toString().equalsIgnoreCase(data.getString("name"))) {
- if (data.getBoolean("is_float")) {
- tv.setText(Float.toString(data.getFloat("val")));
- } else {
- tv.setText(Integer.toString(data.getInt("val")));
- }
- } else if (data.getString("name").equals("chobits_param_rw_failed")) {
- tv.setHint("failed");
- this.postDelayed(new Runnable() {
- @Override
- public void run() {
- ((TextView)findViewById(R.id.param_val)).setHint("parameter value");
- }
- }, 3000);
- }
- break;
case MyMavlinkWork.UI_GLOBAL_POS:
tv = (TextView)findViewById(R.id.alt_status);
tv.setText(Html.fromHtml(String.format("Altitude
%.1fm", msg.arg2*0.001), Html.FROM_HTML_MODE_COMPACT));
@@ -105,6 +113,7 @@ public void run() {
}
}
};
+
View.OnFocusChangeListener myClearHint = new View.OnFocusChangeListener() {
@Override
public void onFocusChange(View view, boolean hasFocus) {
@@ -127,9 +136,10 @@ public void onArmBtn(View view) {
public void onGuidedBtn(View view){ mav_work.setModeGuided(); }
+ public void onDisarmBtn(View view){mav_work.disarm();}
+
public void onStabilizeBtn(View view){ mav_work.setModeStabilize(); }
- public void onSendLocalWaypoint(View view){ mav_work.sendLocalWaypoint(); }
public void onRebootBtn(View view) {
long ts = SystemClock.elapsedRealtime();
@@ -143,59 +153,46 @@ public void onRebootBtn(View view) {
}
}
- private void onSubmitWaypoint(String waypointText) {
- String[] parts = waypointText.split(",");
- if(parts.length == 3) {
- try {
- float lat = Float.parseFloat(parts[0].trim());
- float lon = Float.parseFloat(parts[1].trim());
- float alt = Float.parseFloat(parts[2].trim());
- mav_work.sendLocalWaypoint();
- } catch(NumberFormatException e) {
- Toast.makeText(MainActivity.this, "Invalid waypoint format", Toast.LENGTH_SHORT).show();
- }
- } else {
- Toast.makeText(MainActivity.this, "Waypoint format should be lat,lon,alt", Toast.LENGTH_SHORT).show();
- }
+ public void onSubmitWaypoint(View view) {
+ float lat = 0;
+ float lon = 0;
+ float alt = 0;
+ mav_work.sendLocalWaypoint(lat,lon,alt);
}
- public void onReadParam(View view) {
- TextView tv = (TextView)findViewById(R.id.param_name);
- String param_name = tv.getText().toString();
- if (!param_name.equals("")) {
- tv = (TextView)findViewById(R.id.param_val);
- tv.setText("");
- tv.setHint("reading...");
- mav_work.readParam(param_name);
- }
- }
- public void onWriteParam(View view) {
- TextView tv = (TextView)findViewById(R.id.param_name);
- String param_name = tv.getText().toString();
- if (param_name.equals("")) return;
- tv = (TextView)findViewById(R.id.param_val);
- float param_val;
- try {
- param_val = Float.parseFloat(tv.getText().toString());
- } catch (NumberFormatException e) {
- return;
- }
- tv.setText("");
- tv.setHint("writing...");
- mav_work.writeParam(param_name, param_val);
+ public void setupMapTileStorage() {
+ // Setting the user agent to avoid getting banned from the OSM servers
+ Configuration.getInstance().setUserAgentValue(BuildConfig.APPLICATION_ID);
+
+ // Getting the external storage directory
+ File osmdroidBasePath = new File(Environment.getExternalStorageDirectory(), "osmdroid");
+ File osmdroidTileCache = new File(osmdroidBasePath, "tile");
+ Configuration.getInstance().setOsmdroidBasePath(osmdroidBasePath);
+ Configuration.getInstance().setOsmdroidTileCache(osmdroidTileCache);
}
+
@Override
protected void onCreate(Bundle savedInstanceState) {
super.onCreate(savedInstanceState);
setContentView(R.layout.activity_main);
+ //get permission to use location and storage
+ if (ContextCompat.checkSelfPermission(this, Manifest.permission.WRITE_EXTERNAL_STORAGE) != PackageManager.PERMISSION_GRANTED ||
+ ContextCompat.checkSelfPermission(this, Manifest.permission.ACCESS_FINE_LOCATION) != PackageManager.PERMISSION_GRANTED) {
+
+ ActivityCompat.requestPermissions(this,
+ new String[]{Manifest.permission.WRITE_EXTERNAL_STORAGE, Manifest.permission.ACCESS_FINE_LOCATION},
+ 1); // 1 is requestCode, a unique identifier for this request
+ }
+
+
+
tts = new TextToSpeech(this, this);
((TextView)findViewById(R.id.status_txt)).setMovementMethod(new ScrollingMovementMethod());
- findViewById(R.id.param_val).setOnFocusChangeListener(myClearHint);
PipedInputStream mav_work_is = new PipedInputStream();
PipedOutputStream serial_os = new PipedOutputStream();
@@ -218,10 +215,98 @@ protected void onCreate(Bundle savedInstanceState) {
Thread t2 = new Thread(serialListener);
t2.start();
+ Context ctx = getApplicationContext();
+ Configuration.getInstance().load(ctx, PreferenceManager.getDefaultSharedPreferences(ctx));
+
+ MapView map = findViewById(R.id.osmmap);
+ map.setTileSource(TileSourceFactory.MAPNIK);
+ map.setMultiTouchControls(true);
+ map.setBuiltInZoomControls(false);
+
+ map.setOnTouchListener((v, event) -> {
+ if (event.getAction() == MotionEvent.ACTION_UP) {
+ Projection projection = map.getProjection();
+ GeoPoint geoPoint = (GeoPoint) projection.fromPixels((int) event.getX(), (int) event.getY());
+ handleGeoPoint(geoPoint);
+ return true;
+ }
+ return false;
+ });
+
+ IMapController mapController = map.getController();
+ mapController.setZoom(10);
+ GeoPoint startPoint = new GeoPoint(38.49480, -106.99539);
+ mapController.setCenter(startPoint);
+
+
+
+
+ //requestPermissions(arrayOf(
+ // if you need to show the current location, uncomment the line below
+ // Manifest.permission.ACCESS_FINE_LOCATION,
+ // WRITE_EXTERNAL_STORAGE is required in order to show the map
+ // Manifest.permission.WRITE_EXTERNAL_STORAGE
+ //));
+
+
detectMyDevice();
}
+ @Override
+ public void onRequestPermissionsResult(int requestCode, String[] permissions, int[] grantResults) {
+ super.onRequestPermissionsResult(requestCode, permissions, grantResults);
+ if (requestCode == 1) {
+ if (grantResults.length > 0 && grantResults[0] == PackageManager.PERMISSION_GRANTED) {
+ initializeMapAndDownloadTiles();
+ } else {
+ Toast.makeText(this, "Permissions denied, can't operate fully.", Toast.LENGTH_SHORT).show();
+ }
+ }
+ }
+
+ private void handleGeoPoint(GeoPoint geoPoint) {
+ Toast.makeText(this, "Lat: " + geoPoint.getLatitude() + ", Lon: " + geoPoint.getLongitude(), Toast.LENGTH_SHORT).show();
+ }
+ private void initializeMapAndDownloadTiles() {
+ MapView map = findViewById(R.id.osmmap);
+ map.setTileSource(TileSourceFactory.MAPNIK);
+ map.setBuiltInZoomControls(true);
+ map.setMultiTouchControls(true);
+
+ BoundingBox bbox = new BoundingBox(38.56, -106.89, 38.47, -106.97);
+ CacheManager cacheManager = new CacheManager(map);
+ cacheManager.downloadAreaAsync(this, bbox, 10, 19); // Assuming permissions are already granted
+ }
+
+
+ @Override
+ public void onPause() {
+ super.onPause();
+ //this will refresh the osmdroid configuration on resuming.
+ //if you make changes to the configuration, use
+ //SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(this);
+ //Configuration.getInstance().save(this, prefs);
+ map.onPause(); //needed for compass, my location overlays, v6.0.0 and up
+ }
+
+ private void requestPermissionsIfNecessary(String[] permissions) {
+ ArrayList permissionsToRequest = new ArrayList<>();
+ for (String permission : permissions) {
+ if (ContextCompat.checkSelfPermission(this, permission)
+ != PackageManager.PERMISSION_GRANTED) {
+ // Permission is not granted
+ permissionsToRequest.add(permission);
+ }
+ }
+ /* if (permissionsToRequest.size > 0) {
+ ActivityCompat.requestPermissions(
+ this,
+ permissionsToRequest.toArray(new String[0]),
+ REQUEST_PERMISSIONS_REQUEST_CODE);
+ }*/
+ }
+
@Override
protected void onDestroy() {
if (port != null) {
diff --git a/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java b/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
index 6523b7c..d0d3f75 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
@@ -114,10 +114,7 @@ public void setModeStabilize() {
}
}
- public void sendLocalWaypoint() {
- float lat = 2;
- float lon = 2;
- float alt = 4;
+ public void sendLocalWaypoint(float lat, float lon, float alt) {
try {
MissionItemInt waypointCommand = MissionItemInt.builder()
.targetSystem(255) // System ID for the target system/vehicle
@@ -183,6 +180,19 @@ public void forceArm() {
if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to send force arm command: " + e.getMessage());
}
}
+ public void disarm(){
+ try{
+ CommandLong command = CommandLong.builder()
+ .command(MavCmd.MAV_CMD_COMPONENT_ARM_DISARM)
+ .param1(0) // param1 = 1 (to arm the vehicle),
+ .param2(0)
+ .build();
+
+ mav_conn.send1(255, 0, command);
+ } catch (IOException e) {
+ if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to disarm: " + e.getMessage());
+ }
+ }
public void rebootFC() {
try {
diff --git a/app/src/main/res/layout/activity_main.xml b/app/src/main/res/layout/activity_main.xml
index 756d866..e6a9cee 100644
--- a/app/src/main/res/layout/activity_main.xml
+++ b/app/src/main/res/layout/activity_main.xml
@@ -6,14 +6,16 @@
android:layout_height="match_parent"
tools:context=".MainActivity">
+
+ app:layout_constraintTop_toTopOf="parent">
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
-
-
-
+ android:layout_height="match_parent"
+ android:orientation="vertical">
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
-
-
-
-
-
-
-
Date: Wed, 24 Apr 2024 14:01:06 -0600
Subject: [PATCH 4/4] map update with position and waypoint commands
---
.idea/appInsightsSettings.xml | 6 +
.../com/chobitsfan/minigcs/ArduCopter.java | 4 +
.../com/chobitsfan/minigcs/MainActivity.java | 73 +++++++++---
.../com/chobitsfan/minigcs/MyMavlinkWork.java | 106 +++++++++++++++---
.../java/com/chobitsfan/minigcs/Vehicle.java | 1 +
.../res/drawable/baseline_push_pin_24.xml | 6 +
app/src/main/res/drawable/uav.xml | 20 ++++
app/src/main/res/layout/activity_main.xml | 59 ++++------
app/src/main/res/values/refs.xml | 4 +
9 files changed, 207 insertions(+), 72 deletions(-)
create mode 100644 .idea/appInsightsSettings.xml
create mode 100644 app/src/main/res/drawable/baseline_push_pin_24.xml
create mode 100644 app/src/main/res/drawable/uav.xml
create mode 100644 app/src/main/res/values/refs.xml
diff --git a/.idea/appInsightsSettings.xml b/.idea/appInsightsSettings.xml
new file mode 100644
index 0000000..6bbe2ae
--- /dev/null
+++ b/.idea/appInsightsSettings.xml
@@ -0,0 +1,6 @@
+
+
+
+
+
+
\ No newline at end of file
diff --git a/app/src/main/java/com/chobitsfan/minigcs/ArduCopter.java b/app/src/main/java/com/chobitsfan/minigcs/ArduCopter.java
index d402192..9089e99 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/ArduCopter.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/ArduCopter.java
@@ -25,6 +25,10 @@ public Object Guided(){
return SetMode.builder().baseMode(MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED).customMode(4).build();
}
+ public Object Auto(){
+ return SetMode.builder().baseMode(MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED).customMode(3).build();
+ }
+
public Object Stabilize(){
return SetMode.builder().baseMode(MavModeFlag.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED).customMode(0).build();
}
diff --git a/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java b/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java
index 85838a0..f3360c0 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java
@@ -6,6 +6,7 @@
import android.app.PendingIntent;
import android.content.Context;
import android.content.Intent;
+import android.graphics.drawable.Drawable;
import android.hardware.usb.UsbDeviceConnection;
import android.hardware.usb.UsbManager;
import android.os.Bundle;
@@ -18,6 +19,7 @@
import android.text.Html;
import android.text.method.ScrollingMovementMethod;
import android.util.Log;
+import android.view.GestureDetector;
import android.view.MotionEvent;
import android.view.View;
import android.widget.EditText;
@@ -42,6 +44,8 @@
import org.osmdroid.util.GeoPoint;
import org.osmdroid.views.MapView;
import org.osmdroid.views.Projection;
+import org.osmdroid.views.overlay.Marker;
+import org.osmdroid.views.overlay.Overlay;
import java.io.File;
import java.util.ArrayList;
@@ -56,17 +60,20 @@
import java.io.IOException;
import java.io.PipedInputStream;
import java.io.PipedOutputStream;
+import java.util.Iterator;
import java.util.List;
import java.util.Locale;
public class MainActivity extends AppCompatActivity implements TextToSpeech.OnInitListener {
- private MapView map = null;
+ MapView map = null;
UsbSerialPort port = null;
SerialInputOutputManager usbIoManager;
MyMavlinkWork mav_work;
MyUSBSerialListener serialListener;
long reboot_ts = 0;
TextToSpeech tts;
+ private Marker lastMarker = null;
+
Handler ui_handler = new Handler(Looper.myLooper()) {
@Override
@@ -101,11 +108,28 @@ public void handleMessage(Message msg) {
tv.setText(Html.fromHtml("Satellites
"+data.getInt("satellites")+"", Html.FROM_HTML_MODE_COMPACT));
break;
case MyMavlinkWork.UI_GLOBAL_POS:
- tv = (TextView)findViewById(R.id.alt_status);
- tv.setText(Html.fromHtml(String.format("Altitude
%.1fm", msg.arg2*0.001), Html.FROM_HTML_MODE_COMPACT));
- tv = (TextView)findViewById(R.id.alt_msl_status);
- tv.setText(Html.fromHtml(String.format("Altitude MSL
%.1fm", msg.arg1*0.001), Html.FROM_HTML_MODE_COMPACT));
+ if (map != null) {
+ if (lastMarker != null) {
+ map.getOverlays().remove(lastMarker);
+ }
+
+ Drawable icon = getResources().getDrawable(R.drawable.uav);
+ Marker startMarker = new Marker(map);
+ GeoPoint currentPosition = new GeoPoint(msg.arg1 / 1E7, msg.arg2 / 1E7);
+
+ startMarker.setPosition(currentPosition);
+ startMarker.setIcon(icon);
+ startMarker.setTitle("Marker Title");
+
+ // Add the new marker to the map
+ map.getOverlays().add(startMarker);
+ map.invalidate(); // Refresh the map
+
+ // Update the lastMarker reference to the new marker
+ lastMarker = startMarker;
+ }
break;
+
case MyMavlinkWork.UI_AP_NAME:
tv = (TextView)findViewById(R.id.ap_name);
tv.setText((String)msg.obj);
@@ -138,7 +162,14 @@ public void onArmBtn(View view) {
public void onDisarmBtn(View view){mav_work.disarm();}
- public void onStabilizeBtn(View view){ mav_work.setModeStabilize(); }
+ public void onStabilizeBtn(View view){ mav_work.setModeAuto(); }
+
+ public void onSendWaypoint(View view){
+ mav_work.setGPSOrigin();
+ MyMavlinkWork.sendGlobalWaypoint1(38.54, -106.92, 2);
+ Toast.makeText(this, "sending GLOBAL waypoint", Toast.LENGTH_SHORT).show();
+ }
+
public void onRebootBtn(View view) {
@@ -157,7 +188,7 @@ public void onSubmitWaypoint(View view) {
float lat = 0;
float lon = 0;
float alt = 0;
- mav_work.sendLocalWaypoint(lat,lon,alt);
+ mav_work.sendLocalWaypoint();
}
@@ -174,6 +205,7 @@ public void setupMapTileStorage() {
}
+ @SuppressLint("ClickableViewAccessibility")
@Override
protected void onCreate(Bundle savedInstanceState) {
super.onCreate(savedInstanceState);
@@ -218,11 +250,12 @@ protected void onCreate(Bundle savedInstanceState) {
Context ctx = getApplicationContext();
Configuration.getInstance().load(ctx, PreferenceManager.getDefaultSharedPreferences(ctx));
- MapView map = findViewById(R.id.osmmap);
+ map = findViewById(R.id.osmmap);
map.setTileSource(TileSourceFactory.MAPNIK);
map.setMultiTouchControls(true);
map.setBuiltInZoomControls(false);
+
map.setOnTouchListener((v, event) -> {
if (event.getAction() == MotionEvent.ACTION_UP) {
Projection projection = map.getProjection();
@@ -234,7 +267,7 @@ protected void onCreate(Bundle savedInstanceState) {
});
IMapController mapController = map.getController();
- mapController.setZoom(10);
+ mapController.setZoom(13);
GeoPoint startPoint = new GeoPoint(38.49480, -106.99539);
mapController.setCenter(startPoint);
@@ -267,9 +300,11 @@ public void onRequestPermissionsResult(int requestCode, String[] permissions, in
private void handleGeoPoint(GeoPoint geoPoint) {
Toast.makeText(this, "Lat: " + geoPoint.getLatitude() + ", Lon: " + geoPoint.getLongitude(), Toast.LENGTH_SHORT).show();
+ MyMavlinkWork.sendGlobalWaypoint(geoPoint.getLatitude(), geoPoint.getLongitude(), 3);
}
private void initializeMapAndDownloadTiles() {
MapView map = findViewById(R.id.osmmap);
+ setupMapTileStorage();
map.setTileSource(TileSourceFactory.MAPNIK);
map.setBuiltInZoomControls(true);
map.setMultiTouchControls(true);
@@ -279,17 +314,23 @@ private void initializeMapAndDownloadTiles() {
cacheManager.downloadAreaAsync(this, bbox, 10, 19); // Assuming permissions are already granted
}
-
@Override
- public void onPause() {
+ protected void onPause() {
super.onPause();
- //this will refresh the osmdroid configuration on resuming.
- //if you make changes to the configuration, use
- //SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(this);
- //Configuration.getInstance().save(this, prefs);
- map.onPause(); //needed for compass, my location overlays, v6.0.0 and up
+ if (map != null) {
+ map.onPause(); // pause the map view properly
+ }
}
+ @Override
+ protected void onResume() {
+ super.onResume();
+ if (map != null) {
+ map.onResume(); // resume the map view
+ }
+ }
+
+
private void requestPermissionsIfNecessary(String[] permissions) {
ArrayList permissionsToRequest = new ArrayList<>();
for (String permission : permissions) {
diff --git a/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java b/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
index d0d3f75..de0f3d6 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/MyMavlinkWork.java
@@ -4,6 +4,7 @@
import android.os.Handler;
import android.os.Message;
import android.os.SystemClock;
+import android.provider.Contacts;
import android.provider.Settings;
import android.util.Log;
@@ -15,6 +16,7 @@
import io.dronefleet.mavlink.MavlinkConnection;
import io.dronefleet.mavlink.MavlinkMessage;
+import io.dronefleet.mavlink.common.CommandInt;
import io.dronefleet.mavlink.common.CommandLong;
import io.dronefleet.mavlink.common.GlobalPositionInt;
import io.dronefleet.mavlink.common.GpsRawInt;
@@ -30,12 +32,16 @@
import io.dronefleet.mavlink.common.ParamRequestRead;
import io.dronefleet.mavlink.common.ParamSet;
import io.dronefleet.mavlink.common.ParamValue;
+import io.dronefleet.mavlink.common.PositionTargetTypemask;
import io.dronefleet.mavlink.common.SetMode;
import io.dronefleet.mavlink.common.Statustext;
import io.dronefleet.mavlink.common.SysStatus;
+import io.dronefleet.mavlink.common.SetPositionTargetGlobalInt;
+import io.dronefleet.mavlink.util.EnumValue;
+
public class MyMavlinkWork implements Runnable {
- MavlinkConnection mav_conn;
+ static MavlinkConnection mav_conn;
Handler ui_handler;
Vehicle vehicle = Vehicle.getInstance(MavAutopilot.MAV_AUTOPILOT_ARDUPILOTMEGA, MavType.MAV_TYPE_QUADROTOR);
static String[] GPS_FIX_TYPE = {"No GPS", "No Fix", "2D Fix", "3D Fix", "DGPS", "RTK Float", "RTK Fix"};
@@ -86,6 +92,42 @@ public MyMavlinkWork(Handler handler, InputStream is, OutputStream os) {
t1.start();
}
+ public static void sendGlobalWaypoint(double latitude, double longitude, int alt) {
+ try {
+ CommandLong sendWaypointCommand = CommandLong.builder()
+ .command(MavCmd.MAV_CMD_NAV_WAYPOINT)
+ .param1(3)
+ .param2(0)
+ .param3(0)
+ .param4(0)
+ .param5((float)latitude*1000)
+ .param6((float)longitude*1000)
+ .param7(0)
+ .build();
+
+ mav_conn.send1(255, 0, sendWaypointCommand);
+ } catch (IOException e) {
+ if (MyAppConfig.DEBUG) Log.e("chobits", "Failed to send global waypoint: " + e.getMessage());
+ }
+ }
+
+ public static void sendGlobalWaypoint1(double latitude, double longitude, int alt) {
+ try {
+ SetPositionTargetGlobalInt positionTarget = new SetPositionTargetGlobalInt.Builder()
+ .timeBootMs(0)
+ .coordinateFrame(MavFrame.MAV_FRAME_GLOBAL_INT)
+ .typeMask() // Specify what fields are ignored
+ .latInt(345678901) // Example latitude
+ .lonInt(-987654321) // Example longitude
+ .alt(500.5f) // Altitude in meters
+ .build();
+
+ mav_conn.send1(255, 0, positionTarget);
+ } catch (IOException e) {
+ if (MyAppConfig.DEBUG) Log.e("chobits", "Failed to send global waypoint: " + e.getMessage());
+ }
+ }
+
public void takeoff() {
try {
CommandLong takeoffCommand = CommandLong.builder()
@@ -106,6 +148,13 @@ public void setModeGuided() {
if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to set mode to Guided: " + e.getMessage());
}
}
+ public void setModeAuto() {
+ try {
+ mav_conn.send1(255,0, vehicle.Auto());
+ } catch (IOException e) {
+ if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to set mode to Guided: " + e.getMessage());
+ }
+ }
public void setModeStabilize() {
try {
mav_conn.send1(255,0, vehicle.Stabilize());
@@ -114,28 +163,34 @@ public void setModeStabilize() {
}
}
- public void sendLocalWaypoint(float lat, float lon, float alt) {
+ public void sendLocalWaypoint() {
+ float latitude = 38;
+ float longitude = -106;
+ float altitude = 3;
try {
+ // Construct a waypoint command using global coordinates but intended for relative movement or specific local handling
MissionItemInt waypointCommand = MissionItemInt.builder()
- .targetSystem(255) // System ID for the target system/vehicle
- .targetComponent(0) // Component ID for the target component
+ .targetSystem(255) // System ID for the target system/vehicle; often 1 in practical scenarios
+ .targetComponent(0) // Component ID for the main flight controller
.seq(0) // Sequence number of the waypoint
- .frame(MavFrame.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) // Use relative altitude
+ .frame(MavFrame.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) // Use global position but with altitude relative to home
.command(MavCmd.MAV_CMD_NAV_WAYPOINT) // Command to navigate to a waypoint
- .current(1) // Set to 1 to indicate this is the current waypoint
- .autocontinue(1) // Set to 1 to allow auto-continuing to the next waypoint
- .param1(0) // Hold time in seconds (ignored for simple waypoint navigation)
- .param2(0) // Acceptance radius in meters (if the vehicle is within this distance of the waypoint, consider it reached)
- .param3(0) // Pass-through waypoint (0 to fly directly to the waypoint)
- .param4(0) // Desired yaw angle at waypoint (ignored unless YAW_ANGLE is used)
- .x((int) (lat * 1E7)) // Latitude in decimal degrees * 1E7
- .y((int) (lon * 1E7)) // Longitude in decimal degrees * 1E7
- .z(alt) // Altitude in meters
+ .current(1) // Set this waypoint as active
+ .autocontinue(1) // Allow auto-continuing to subsequent waypoints if any
+ .param1(0) // Hold time at waypoint
+ .param2(0) // Acceptance radius in meters; if zero, default is used
+ .param3(0) // Pass-through waypoint; no loiter around the waypoint
+ .param4(0) // Yaw angle; ignored unless specified
+ .x((int) (latitude * 1E7)) // Latitude in decimal degrees, multiplied by 1E7 for MAVLink protocol
+ .y((int) (longitude * 1E7)) // Longitude in decimal degrees, multiplied by 1E7
+ .z(altitude) // Altitude in meters
.build();
+ // Send the waypoint command to the vehicle
mav_conn.send1(255, 0, waypointCommand);
} catch (IOException e) {
- if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to send local waypoint: " + e.getMessage());
+ // Log any errors for debugging purposes
+ if (MyAppConfig.DEBUG) Log.e("chobits", "Failed to send local waypoint: " + e.getMessage());
}
}
@@ -149,6 +204,23 @@ public void setModeLand() {
}
}
+ public void setGPSOrigin(){
+ try {
+ CommandInt setOriginCommand = CommandInt.builder()
+ .targetSystem(255) // System ID for the target system/vehicle
+ .targetComponent(0)
+ .frame(MavFrame.MAV_FRAME_GLOBAL)
+ .command(MavCmd.MAV_CMD_DO_SET_HOME)
+ .param1(0)
+ .build();
+
+ mav_conn.send1(255, 0, setOriginCommand);
+
+ } catch (IOException e) {
+ if (MyAppConfig.DEBUG) Log.d("chobits", e.getMessage());
+ }
+ }
+
public void readParam(String name) {
param_rw_sent_ts = SystemClock.elapsedRealtime();
try {
@@ -296,8 +368,8 @@ public void run() {
} else if (msg_payload instanceof GlobalPositionInt) {
last_global_pos_ts = SystemClock.elapsedRealtime();
GlobalPositionInt global_pos = (GlobalPositionInt)msg_payload;
- Message ui_msg = ui_handler.obtainMessage(UI_GLOBAL_POS, global_pos.alt(), global_pos.relativeAlt());
- ui_handler.sendMessage(ui_msg);
+ Message loc_msg = ui_handler.obtainMessage(UI_GLOBAL_POS, global_pos.lat(), global_pos.lon());
+ ui_handler.sendMessage(loc_msg);
} else if (msg_payload instanceof ParamValue) {
ParamValue p_val = (ParamValue)msg_payload;
if (MyAppConfig.DEBUG) Log.d("chobits", "param val " + p_val.paramId() + ":" + p_val.paramValue());
diff --git a/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java b/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java
index b081595..beda96b 100644
--- a/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java
+++ b/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java
@@ -7,6 +7,7 @@ public abstract class Vehicle {
public abstract String Mode(int customMode);
public abstract Object Land();
public abstract Object Guided();
+ public abstract Object Auto();
public abstract Object Stabilize();
public abstract String Name();
public static Vehicle getInstance(MavAutopilot autopilot, MavType type) {return ArduCopter.getInstance();}
diff --git a/app/src/main/res/drawable/baseline_push_pin_24.xml b/app/src/main/res/drawable/baseline_push_pin_24.xml
new file mode 100644
index 0000000..4f4089e
--- /dev/null
+++ b/app/src/main/res/drawable/baseline_push_pin_24.xml
@@ -0,0 +1,6 @@
+
+
+
diff --git a/app/src/main/res/drawable/uav.xml b/app/src/main/res/drawable/uav.xml
new file mode 100644
index 0000000..670594d
--- /dev/null
+++ b/app/src/main/res/drawable/uav.xml
@@ -0,0 +1,20 @@
+
+
+
+
+
+
+
diff --git a/app/src/main/res/layout/activity_main.xml b/app/src/main/res/layout/activity_main.xml
index e6a9cee..9808d0c 100644
--- a/app/src/main/res/layout/activity_main.xml
+++ b/app/src/main/res/layout/activity_main.xml
@@ -47,34 +47,12 @@
-
-
-
-
-
-
-
+
+
+
+
@@ -185,21 +181,6 @@
-
-
+
+
+
\ No newline at end of file