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/.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..8978d23 100644 --- a/.idea/misc.xml +++ b/.idea/misc.xml @@ -1,7 +1,6 @@ - - + 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 @@ + + + + + + + = 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 4655be5..f3360c0 100644 --- a/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java +++ b/app/src/main/java/com/chobitsfan/minigcs/MainActivity.java @@ -2,12 +2,15 @@ import androidx.appcompat.app.AppCompatActivity; +import android.annotation.SuppressLint; 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; +import android.os.Environment; import android.os.Handler; import android.os.Looper; import android.os.Message; @@ -16,11 +19,37 @@ 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; import android.widget.TextView; import android.widget.Toast; +import android.Manifest; +import android.content.Context; +import android.content.pm.PackageManager; +import android.os.Bundle; +import android.preference.PreferenceManager; + +import androidx.appcompat.app.AppCompatActivity; +import androidx.core.app.ActivityCompat; +import androidx.core.content.ContextCompat; + +import org.osmdroid.api.IMapController; +import org.osmdroid.config.Configuration; +import org.osmdroid.tileprovider.cachemanager.CacheManager; +import org.osmdroid.tileprovider.tilesource.TileSourceFactory; +import org.osmdroid.util.BoundingBox; +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; + import com.hoho.android.usbserial.driver.CdcAcmSerialDriver; import com.hoho.android.usbserial.driver.ProbeTable; import com.hoho.android.usbserial.driver.UsbSerialDriver; @@ -31,16 +60,21 @@ 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 { + 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 public void handleMessage(Message msg) { @@ -73,31 +107,29 @@ public void handleMessage(Message msg) { tv = (TextView)findViewById(R.id.gps_satellites); tv.setText(Html.fromHtml("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"))); + case MyMavlinkWork.UI_GLOBAL_POS: + if (map != null) { + if (lastMarker != null) { + map.getOverlays().remove(lastMarker); } - } 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); + + 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_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)); - break; + case MyMavlinkWork.UI_AP_NAME: tv = (TextView)findViewById(R.id.ap_name); tv.setText((String)msg.obj); @@ -105,6 +137,7 @@ public void run() { } } }; + View.OnFocusChangeListener myClearHint = new View.OnFocusChangeListener() { @Override public void onFocusChange(View view, boolean hasFocus) { @@ -119,10 +152,26 @@ 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 onTakeoffBtn(View view){ mav_work.takeoff(); } + + public void onGuidedBtn(View view){ mav_work.setModeGuided(); } + + public void onDisarmBtn(View view){mav_work.disarm();} + + 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) { long ts = SystemClock.elapsedRealtime(); if (ts - reboot_ts > 3000) { @@ -135,42 +184,47 @@ public void onRebootBtn(View view) { } } - 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 onSubmitWaypoint(View view) { + float lat = 0; + float lon = 0; + float alt = 0; + mav_work.sendLocalWaypoint(); } - 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); } + + @SuppressLint("ClickableViewAccessibility") @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(); @@ -193,9 +247,107 @@ protected void onCreate(Bundle savedInstanceState) { Thread t2 = new Thread(serialListener); t2.start(); + Context ctx = getApplicationContext(); + Configuration.getInstance().load(ctx, PreferenceManager.getDefaultSharedPreferences(ctx)); + + 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(13); + 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(); + 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); + + 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 + protected void onPause() { + super.onPause(); + 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) { + 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 bd7ca2f..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,25 +16,32 @@ 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; 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; 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"}; @@ -84,6 +92,110 @@ 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() + .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", "Failed to send takeoff command: " + e.getMessage()); + } + } + + public void setModeGuided() { + try { + 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 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()); + } catch (IOException e) { + if (MyAppConfig.DEBUG) Log.d("chobits", "Failed to set mode to Stabilize: " + e.getMessage()); + } + } + + 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; 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 global position but with altitude relative to home + .command(MavCmd.MAV_CMD_NAV_WAYPOINT) // Command to navigate to a waypoint + .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) { + // Log any errors for debugging purposes + if (MyAppConfig.DEBUG) Log.e("chobits", "Failed to send local waypoint: " + e.getMessage()); + } + } + + + public void setModeLand() { try { mav_conn.send1(255,0, vehicle.Land()); @@ -92,9 +204,18 @@ public void setModeLand() { } } - public void setModeRTL() { + public void setGPSOrigin(){ try { - mav_conn.send1(255,0, vehicle.RTL()); + 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()); } @@ -118,6 +239,33 @@ public void writeParam(String name, float val) { } } + public void forceArm() { + try { + CommandLong command = CommandLong.builder() + .command(MavCmd.MAV_CMD_COMPONENT_ARM_DISARM) + .param1(1) // param1 = 1 (to arm the vehicle), + .param2(21196) // param2 = 21196 (magic number to bypass pre-arm checks and force arm) + .build(); + + 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 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 { mav_conn.send1(255, 0, CommandLong.builder().command(MavCmd.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN).param1(1).build()); @@ -220,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 5f36f97..beda96b 100644 --- a/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java +++ b/app/src/main/java/com/chobitsfan/minigcs/Vehicle.java @@ -6,13 +6,9 @@ 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 Auto(); + 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/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 7a15a75..9808d0c 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"> + - - - - - - - -