Skip to content
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
2 changes: 1 addition & 1 deletion other-modules/comm/sensorhub-comm-mavlink2/build.gradle
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
description = 'MAVLink Connection'
description = 'Unmanned System'
ext.details = 'MAVLink adapter'

dependencies{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,7 @@ private void registerModule() {
unmannedConfig.name = "Unmanned System";
unmannedConfig.autoStart = true;
unmannedConfig.moduleClass = UnmannedSystem.class.getCanonicalName();
unmannedConfig.serialNumber = UUID.randomUUID().toString();

try {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,11 @@

import org.sensorhub.api.config.DisplayInfo;
import org.sensorhub.api.sensor.SensorConfig;
import org.sensorhub.impl.comm.mavlink2.config.MissionConfig;

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

/**
* Configuration settings for the {@link UnmannedSystem} driver exposed via the OpenSensorHub Admin panel.
Expand All @@ -33,5 +38,11 @@ public class UnmannedConfig extends SensorConfig {
*/
@DisplayInfo.Required
@DisplayInfo(desc = "Serial number or unique identifier")
public String serialNumber = "sensor001";
public String serialNumber = UUID.randomUUID().toString();;

public List<MissionConfig> missions;

public String SDKAddress = "127.0.0.1";
public int SDKPort = 50051;
public String systemId;
}
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ Developer are Copyright (C) 2025 the Initial Developer. All Rights Reserved.
package org.sensorhub.impl.comm.mavlink2;

import io.mavsdk.action.Action;
import io.reactivex.Completable;
import net.opengis.swe.v20.*;
import org.sensorhub.api.command.CommandException;
import org.sensorhub.impl.sensor.AbstractSensorControl;
Expand Down Expand Up @@ -63,7 +64,7 @@ public class UnmannedControlLocation extends AbstractSensorControl<UnmannedSyste

private io.mavsdk.System system = null;

static double deltaSuccess = 0.000003; //distance from lat/lon to determine success
static double deltaSuccess = 0.000005; //distance from lat/lon to determine success

public UnmannedControlLocation( UnmannedSystem parentSensor) {
super("mavControl", parentSensor);
Expand Down Expand Up @@ -121,7 +122,8 @@ protected boolean execCommand(DataBlock command) throws CommandException {
System.out.println("Command received - Lat: " + latitude + " Lon: " + longitude + " Alt: " + altitude );

if ( system != null ) {
sendToLocation( latitude, longitude, altitude, returnToStart, hoverSeconds );
sendToLocation( latitude, longitude, altitude, returnToStart, hoverSeconds )
.subscribe();
} else {
throw new CommandException("Unmanned System not initialized");
}
Expand All @@ -130,37 +132,32 @@ protected boolean execCommand(DataBlock command) throws CommandException {
}


private void sendToLocation( double latitudeParam,
public Completable sendToLocation( double latitudeParam,
double longitudeParam,
double altAglParam,
boolean returnHomeParam,
long hoverSecondsParam ) {

System.out.println("Preparing to send to location...");

float absoluteMsl = system.getTelemetry().getPosition().blockingFirst().getAbsoluteAltitudeM();
System.out.println("absolute MSL (m): " + absoluteMsl);
float altMsl = getAltMsl((float) altAglParam);
System.out.println("setting altitude MSL to: " + altMsl);

float relativeAltitude = system.getTelemetry().getPosition().blockingFirst().getRelativeAltitudeM();
System.out.println("current Relative MSL (m): " + relativeAltitude);
double homeLat = system.getTelemetry().getPosition().blockingFirst().getLatitudeDeg();
double homeLon = system.getTelemetry().getPosition().blockingFirst().getLongitudeDeg();

float terrainOffset = absoluteMsl - relativeAltitude;
System.out.println("terrain offset: " + terrainOffset);
return goLocation(latitudeParam, longitudeParam, returnHomeParam, hoverSecondsParam, altMsl, homeLat, homeLon);
}

// We can use the last
// known relative altitude to set an approximate MSL. This will sometimes not be adequate as the
// terrain will change. For now it's good for a quick demo, but we'll want to eventually
// constantly adjust based on terrain altitude.
float altMsl = (float)altAglParam + terrainOffset;
System.out.println("setting altitude MSL to: " + altMsl);

system.getAction().gotoLocation(latitudeParam, longitudeParam, altMsl, 45.0F)
.doOnComplete( () -> {
public Completable goLocation( double latitudeParam, double longitudeParam, boolean returnHomeParam, long hoverSecondsParam, float altMsl, double homeLat, double homeLon ) {
return system.getAction().gotoLocation(latitudeParam, longitudeParam, altMsl, 45.0F)
.doOnComplete(() -> {

System.out.println("Moving to target location");

})
.doOnError( throwable -> {
.doOnError(throwable -> {

System.out.println("Failed to go to target: " + ((Action.ActionException) throwable).getCode());

Expand All @@ -169,11 +166,41 @@ private void sendToLocation( double latitudeParam,
.filter(pos -> (abs(pos.getLatitudeDeg() - latitudeParam) <= deltaSuccess && abs(pos.getLongitudeDeg() - longitudeParam) <= deltaSuccess))
.firstElement()
.ignoreElement()
)
.subscribe(() -> {
.delay(hoverSecondsParam, TimeUnit.SECONDS) //hover if the value is marked
.andThen(Completable.fromAction(() -> {

//return home if the value is checked
if (returnHomeParam) {
system.getAction().gotoLocation(homeLat, homeLon, altMsl, 45.0F)
.doOnComplete(() -> {
System.out.println("Moving back to home");
})
.doOnError(throwable -> {
System.out.println("Failed to go home: " + ((Action.ActionException) throwable).getCode());
})
.subscribe();
}
}))
);
}

});

public float getAltMsl( float altAglParam ) {
float absoluteMsl = system.getTelemetry().getPosition().blockingFirst().getAbsoluteAltitudeM();
System.out.println("absolute MSL (m): " + absoluteMsl);

float relativeAltitude = system.getTelemetry().getPosition().blockingFirst().getRelativeAltitudeM();
System.out.println("current Relative MSL (m): " + relativeAltitude);

float terrainOffset = absoluteMsl - relativeAltitude;
System.out.println("terrain offset: " + terrainOffset);

// We can use the last
// known relative altitude to set an approximate MSL. This will sometimes not be adequate as the
// terrain will change. For now it's good for a quick demo, but we'll want to eventually
// constantly adjust based on terrain altitude.
float altMsl = altAglParam + terrainOffset;
return altMsl;
}


Expand Down
Loading