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

Comply with autopilot's firmware update

Included changes are required to use the autopilot's version complatible with
mavlink 2
parent 27ae36e4
......@@ -21,7 +21,7 @@ extern "C" {
#include <stdint.h>
// Connexion management functions
int mavsdk_start(const char * ip, int port, const char * log_file, int timeout);
int mavsdk_stop(void);
int mavsdk_stop(bool shutdown);
int mavsdk_reboot(void);
// Flight state management functions
......@@ -50,7 +50,6 @@ float mavsdk_getYaw(void);
float mavsdk_getSpeed(void);
float mavsdk_getClimbRate(void);
int mavsdk_healthAllOk(void);
int mavsdk_landed(void);
#ifdef __cplusplus
}
#endif
......
......@@ -172,22 +172,23 @@ int mavsdk_start(const char * ip, int port, const char * log_file, int timeout)
return 0;
}
int mavsdk_stop() {
int mavsdk_stop(bool shutdown) {
if (!mavsdk_started)
return -1;
if (!mavsdk_landed()) {
log_error("You must land first !");
return -1;
}
if (shutdown) {
while (telemetry->armed())
sleep_for(seconds(1));
if (doAction(&Action::shutdown, "Shutdown failed"))
return -1;
}
// Delete pointers
delete action;
delete mavlink_passthrough;
delete telemetry;
log_file_fd << std::flush;
log_file_fd.close();
return 0;
......@@ -227,7 +228,8 @@ int mavsdk_takeOffAndWait(void) {
sleep_for(seconds(1));
while (telemetry->flight_mode() == Telemetry::FlightMode::Takeoff)
sleep_for(seconds(1));
return 0;
return doAction(&Action::transition_to_fixedwing, "Transition to fixedwing failed");
}
int mavsdk_triggerParachute(void) {
......@@ -236,26 +238,11 @@ int mavsdk_triggerParachute(void) {
log("Landing...");
MavlinkPassthrough::CommandLong command;
command.command = MAV_CMD_DO_PARACHUTE;
command.param1 = 2; //see https://mavlink.io/en/messages/common.html#PARACHUTE_ACTION
command.command = MAV_CMD_DO_FLIGHTTERMINATION;
command.param1 = 1; //see https://mavlink.io/en/messages/common.html#MAV_CMD_DO_FLIGHTTERMINATION
command.target_sysid = mavlink_passthrough->get_target_sysid();
command.target_compid = mavlink_passthrough->get_target_compid();
if (doMavlinkCommand(command, "Parachute release failed"))
return -1;
// Check if vehicule is still in air
while (telemetry->in_air()) {
log("Vehicle is landing...");
sleep_for(seconds(1));
}
log("Landed!");
while (telemetry->armed())
sleep_for(seconds(1));
log("Finished...");
log_file_fd << std::flush;
return 0;
return doMavlinkCommand(command, "Parachute release failed");
}
// Flight management functions
......@@ -435,7 +422,3 @@ float mavsdk_getClimbRate(void) {
int mavsdk_healthAllOk(void) {
return telemetry->health_all_ok();
}
int mavsdk_landed(void) {
return !telemetry->in_air();
}
......@@ -428,7 +428,7 @@ static JSValue js_mavsdk_start(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_stop(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewInt32(ctx, mavsdk_stop());
return JS_NewInt32(ctx, mavsdk_stop(JS_ToBool(ctx, argv[0])));
}
static JSValue js_mavsdk_reboot(JSContext *ctx, JSValueConst thisVal,
......@@ -584,18 +584,12 @@ static JSValue js_mavsdk_healthAllOk(JSContext *ctx, JSValueConst this_val,
return JS_NewBool(ctx, mavsdk_healthAllOk());
}
static JSValue js_mavsdk_landed(JSContext *ctx, JSValueConst this_val,
int argc, JSValueConst *argv)
{
return JS_NewBool(ctx, mavsdk_landed());
}
static const JSCFunctionListEntry js_mavsdk_funcs[] = {
JS_CFUNC_DEF("setMessage", 1, js_drone_set_message ),
JS_CFUNC_DEF("runPubsub", 6, js_run_pubsub ),
JS_CFUNC_DEF("stopPubsub", 0, js_stop_pubsub ),
JS_CFUNC_DEF("start", 4, js_mavsdk_start ),
JS_CFUNC_DEF("stop", 0, js_mavsdk_stop ),
JS_CFUNC_DEF("stop", 1, js_mavsdk_stop ),
JS_CFUNC_DEF("reboot", 0, js_mavsdk_reboot ),
JS_CFUNC_DEF("arm", 0, js_mavsdk_arm ),
JS_CFUNC_DEF("takeOff", 0, js_mavsdk_takeOff ),
......@@ -616,7 +610,6 @@ static const JSCFunctionListEntry js_mavsdk_funcs[] = {
JS_CFUNC_DEF("getAirspeed", 0, js_mavsdk_getSpeed ),
JS_CFUNC_DEF("getClimbRate", 0, js_mavsdk_getClimbRate ),
JS_CFUNC_DEF("healthAllOk", 0, js_mavsdk_healthAllOk ),
JS_CFUNC_DEF("landed", 0, js_mavsdk_landed ),
JS_CFUNC_DEF("initPubsub", 1, js_init_pubsub ),
};
......
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