Commit a6619148 authored by Léo-Paul Géneau's avatar Léo-Paul Géneau 👾

Use doReposition and doOverride commands asynchronously

parent 903e38b3
......@@ -157,12 +157,16 @@ static int doReposition(float la, float lo, float radius, float y) {
return doMavlinkCommand(command, "Entering loiter mode failed");
}
static void doReposition_async(float la, float lo, float radius, float y) {
std::thread(doReposition, la, lo, radius, y).detach();
}
static void updateProjection(double current_lat, double current_lon) {
Coordinates position{ current_lat, current_lon };
projected_destination = getProjectionCoordinates(targeted_destination,
position);
return doReposition(
doReposition_async(
(float)projected_destination.latitude,
(float)projected_destination.longitude,
DEFAULT_RADIUS,
......@@ -175,7 +179,7 @@ static long long int getTimestamp() {
return std::chrono::duration_cast<std::chrono::milliseconds>(now.time_since_epoch()).count();
}
int updateLogAndProjection(void) {
void updateLogAndProjection(void) {
std::ostringstream oss;
Telemetry::Position position;
Telemetry::FixedwingMetrics metrics;
......@@ -192,11 +196,9 @@ int updateLogAndProjection(void) {
log(oss.str());
if (projected_destination.latitude != 0 || targeted_destination.latitude != 0) {
return updateProjection(position.latitude_deg, position.longitude_deg);
updateProjection(position.latitude_deg, position.longitude_deg);
}
}
return 0;
}
// Connexion management functions
......@@ -347,30 +349,37 @@ static int setAltitude(float altitude) {
return doOverride(altitude, last_override_speed, "Setting altitude failed");
}
int loiter(double la, double lo, float a, float radius) {
int result = doReposition((float)la, (float)lo, radius, 0);
result |= setAltitude(a);
return result;
static void setAltitude_async(float altitude) {
std::thread(setAltitude, altitude).detach();
}
void loiter(double la, double lo, float a, float radius) {
doReposition_async((float)la, (float)lo, radius, 0);
setAltitude_async(a);
}
int setAirSpeed(float airspeed) {
static int setAirSpeed(float airspeed) {
last_override_speed = airspeed;
return doOverride(last_override_altitude, airspeed,
"Setting airspeed failed");
}
int setTargetCoordinates(double la, double lo, float a) {
int result;
if (!mavsdk_started)
return -1;
void setAirSpeed_async(float airspeed) {
std::thread(setAirSpeed, airspeed).detach();
}
void setTargetCoordinates(double la, double lo, float a) {
if (!mavsdk_started) {
log_error("Mavsdk not started");
return;
}
Telemetry::Position position = telemetry->position();
targeted_destination.latitude = la;
targeted_destination.longitude = lo;
result = updateProjection(position.latitude_deg, position.longitude_deg);
result |= setAltitude(a);
return result;
updateProjection(position.latitude_deg, position.longitude_deg);
setAltitude_async(a);
}
// Information functions
......
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment