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

change doParachute into triggerParachute

parent 29fe3da7
......@@ -12,11 +12,11 @@ int mavsdk_reboot(void);
// Flight state management functions
int mavsdk_arm(void);
int mavsdk_doParachute(float param);
int mavsdk_loiter();
int mavsdk_land(void);
int mavsdk_takeOff(void);
int mavsdk_takeOffAndWait(void);
int mavsdk_triggerParachute(void);
// Flight management functions
int mavsdk_doReposition(float la, float lo, float a, float y);
......
......@@ -214,18 +214,6 @@ int mavsdk_arm(void) {
return doAction(&Action::arm, "Arming failed");
}
int mavsdk_doParachute(float param) {
if(!mavsdk_started)
return -1;
MavlinkPassthrough::CommandLong command;
command.command = MAV_CMD_DO_PARACHUTE;
command.param1 = param; //see https://mavlink.io/en/messages/common.html#PARACHUTE_ACTION
command.target_sysid = mavlink_passthrough->get_target_sysid();
command.target_compid = mavlink_passthrough->get_target_compid();
return doMavlinkCommand(command, "Parachute failed");
}
int mavsdk_land(void) {
log("Landing...");
if(doAction(&Action::terminate, "Land failed")) {
......@@ -280,6 +268,18 @@ int mavsdk_takeOffAndWait(void) {
return 0;
}
int mavsdk_triggerParachute(void) {
if (!mavsdk_started)
return -1;
MavlinkPassthrough::CommandLong command;
command.command = MAV_CMD_DO_PARACHUTE;
command.param1 = 2; //see https://mavlink.io/en/messages/common.html#PARACHUTE_ACTION
command.target_sysid = mavlink_passthrough->get_target_sysid();
command.target_compid = mavlink_passthrough->get_target_compid();
return doMavlinkCommand(command, "Parachute release failed");
}
// Flight management functions
int mavsdk_doReposition(float la, float lo, float a, float y) {
......
......@@ -463,15 +463,10 @@ static JSValue js_mavsdk_loiter(JSContext *ctx, JSValueConst this_val,
return JS_NewInt32(ctx, mavsdk_loiter());
}
static JSValue js_mavsdk_doParachute(JSContext *ctx, JSValueConst this_val,
static JSValue js_mavsdk_triggerParachute(JSContext *ctx, JSValueConst this_val,
int argc, JSValueConst *argv)
{
double param;
if (JS_ToFloat64(ctx, &param, argv[0]))
return JS_EXCEPTION;
return JS_NewInt32(ctx, mavsdk_doParachute((float)param));
return JS_NewInt32(ctx, mavsdk_triggerParachute());
}
static JSValue js_mavsdk_takeOff(JSContext *ctx, JSValueConst this_val,
......@@ -503,7 +498,7 @@ static const JSCFunctionListEntry js_mavsdk_funcs[] = {
JS_CFUNC_DEF("setAltitude", 1, js_mavsdk_setAltitude ),
JS_CFUNC_DEF("setAirspeed", 1, js_mavsdk_setAirspeed ),
JS_CFUNC_DEF("loiter", 0, js_mavsdk_loiter ),
JS_CFUNC_DEF("doParachute", 1, js_mavsdk_doParachute ),
JS_CFUNC_DEF("triggerParachute", 0, js_mavsdk_triggerParachute ),
JS_CFUNC_DEF("getYaw", 0, js_mavsdk_getYaw ),
JS_CFUNC_DEF("getInitialLatitude", 0, js_mavsdk_getInitialLatitude ),
JS_CFUNC_DEF("getLatitude", 0, js_mavsdk_getLatitude ),
......
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