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

Remove autopilot's API specific related code

parent 1fd9dd91
CFLAGS=-std=c99 -D_POSIX_C_SOURCE=200809L -pipe -Wall -Wextra -Wpedantic -Werror -Wno-overlength-strings -Wno-unused-parameter -Wc++-compat -Wformat -Wformat-security -Wformat-nonliteral -Wmissing-prototypes -Wstrict-prototypes -Wredundant-decls -Wuninitialized -Winit-self -Wcast-qual -Wstrict-overflow -Wnested-externs -Wmultichar -Wundef -fno-strict-aliasing -fexceptions -fPIC -fstack-protector-strong -fstack-clash-protection -ffunction-sections -fdata-sections -fno-unwind-tables -fno-asynchronous-unwind-tables -fno-math-errno -O3 -flto -fno-fat-lto-objects -Wshadow -Wconversion -fvisibility=hidden -fPIC CFLAGS=-std=c99 -D_POSIX_C_SOURCE=200809L -pipe -Wall -Wextra -Wpedantic -Werror -Wno-overlength-strings -Wno-unused-parameter -Wc++-compat -Wformat -Wformat-security -Wformat-nonliteral -Wmissing-prototypes -Wstrict-prototypes -Wredundant-decls -Wuninitialized -Winit-self -Wcast-qual -Wstrict-overflow -Wnested-externs -Wmultichar -Wundef -fno-strict-aliasing -fexceptions -fstack-protector-strong -fstack-clash-protection -ffunction-sections -fdata-sections -fno-unwind-tables -fno-asynchronous-unwind-tables -fno-math-errno -O3 -flto -fno-fat-lto-objects -Wshadow -Wconversion -fvisibility=hidden -fPIC
CXXFLAGS=-pipe -Wall -Wextra -Wpedantic -Werror -Wno-overlength-strings -Wno-unused-parameter -Wformat -Wformat-security -Wformat-nonliteral -Wredundant-decls -Wuninitialized -Winit-self -Wcast-qual -Wstrict-overflow -Wmultichar -Wundef -fno-strict-aliasing -fexceptions -fPIC -fstack-protector-strong -fstack-clash-protection -ffunction-sections -fdata-sections -fno-unwind-tables -fno-asynchronous-unwind-tables -fno-math-errno -O3 -flto -fno-fat-lto-objects -Wshadow -Wconversion -fvisibility=hidden -fPIC LIBS=-lautopilotwrapper -lopen62541
LDFLAGS+= -std=c99 -D_POSIX_C_SOURCE=200809L -pipe -Wall -Wextra -Wpedantic -Werror -Wno-static-in-inline -Wno-overlength-strings -Wno-unused-parameter -Wc++-compat -Wformat -Wformat-security -Wformat-nonliteral -Wmissing-prototypes -Wstrict-prototypes -Wredundant-decls -Wuninitialized -Winit-self -Wcast-qual -Wstrict-overflow -Wnested-externs -Wmultichar -Wundef -fno-strict-aliasing -fexceptions -fPIC -fstack-protector-strong -fstack-clash-protection -ffunction-sections -fdata-sections -fno-unwind-tables -fno-asynchronous-unwind-tables -fno-math-errno -O3 -flto -fno-fat-lto-objects -Wshadow -Wconversion -fvisibility=hidden -fPIC
LIBS=-lstdc++ -lmavsdk -lmavsdk_action -lmavsdk_mavlink_passthrough -lmavsdk_telemetry -lopen62541
LIB_NAME := libqjswrapper.so LIB_NAME := libqjswrapper.so
SRCS := mavsdk_wrapper.cpp pubsub.c qjs_wrapper.c SRCS := pubsub.c qjs_wrapper.c
OBJS := mavsdk_wrapper.o pubsub.o qjs_wrapper.o OBJS := pubsub.o qjs_wrapper.o
all: $(LIB_NAME) all: $(LIB_NAME)
......
This project is holding the source code for QuickJS component that will wrap the functions from MAVSDK and open62541. # qjs-wrapper
This project is holding the source code for QuickJS component that will wrap the functions from open62541 and a drone
autopilot's API (MAVSDK by default).
...@@ -2,7 +2,7 @@ ...@@ -2,7 +2,7 @@
#define __DRONEDGE_H__ #define __DRONEDGE_H__
#include <open62541/server.h> #include <open62541/server.h>
#include "mavsdk_wrapper.h" #include "autopilot_wrapper.h"
#include "pubsub.h" #include "pubsub.h"
struct messageNode { struct messageNode {
...@@ -36,7 +36,7 @@ VariableData droneVariableArray[] = { ...@@ -36,7 +36,7 @@ VariableData droneVariableArray[] = {
.valueRank = UA_VALUERANK_ONE_DIMENSION, .valueRank = UA_VALUERANK_ONE_DIMENSION,
.arrayDimensionsSize = 1, .arrayDimensionsSize = 1,
.arrayDimensions = positionArrayDims, .arrayDimensions = positionArrayDims,
.getter.getArray = mavsdk_getPositionArray, .getter.getArray = getPositionArray,
}, },
{ {
.name = "speedArray", .name = "speedArray",
...@@ -48,7 +48,7 @@ VariableData droneVariableArray[] = { ...@@ -48,7 +48,7 @@ VariableData droneVariableArray[] = {
.valueRank = UA_VALUERANK_ONE_DIMENSION, .valueRank = UA_VALUERANK_ONE_DIMENSION,
.arrayDimensionsSize = 1, .arrayDimensionsSize = 1,
.arrayDimensions = speedArrayDims, .arrayDimensions = speedArrayDims,
.getter.getArray = mavsdk_getSpeedArray, .getter.getArray = getSpeedArray,
}, },
{ {
.name = "message", .name = "message",
......
#ifndef __MAVSDK_H__
#define __MAVSDK_H__
/*
* 0. latitude (double, degrees)
* 1. longitude (double, degrees)
* 2. absolute altitude (double, meters)
* 3. relative altitude (double, meters)
*/
#define POSITION_ARRAY_SIZE 4
/*
* 0. yaw angle (float, degrees)
* 1. air speed (float, m/s)
* 2. climb rate (float, m/s)
*/
#define SPEED_ARRAY_SIZE 3
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
// Connexion management functions
int mavsdk_start(const char * ip, int port, const char * log_file, int timeout);
int mavsdk_stop(bool shutdown);
int mavsdk_reboot(void);
// Flight state management functions
int mavsdk_arm(void);
int mavsdk_takeOff(void);
int mavsdk_takeOffAndWait(void);
int mavsdk_triggerParachute(void);
// Flight management functions
int mavsdk_loiter(float radius);
int mavsdk_setAirspeed(float airspeed);
int mavsdk_setTargetCoordinates(double la, double lo, float a);
// Information functions
float mavsdk_getAltitude(void);
float mavsdk_getAltitudeRel(void);
float mavsdk_getInitialAltitude(void);
double mavsdk_getInitialLatitude(void);
double mavsdk_getInitialLongitude(void);
double mavsdk_getLatitude(void);
double mavsdk_getLongitude(void);
double *mavsdk_getPositionArray(void);
float *mavsdk_getSpeedArray(void);
double mavsdk_getTakeOffAltitude(void);
float mavsdk_getYaw(void);
float mavsdk_getSpeed(void);
float mavsdk_getClimbRate(void);
int mavsdk_healthAllOk(void);
#ifdef __cplusplus
}
#endif
#endif /* __MAVSDK_H__ */
...@@ -6,7 +6,9 @@ ...@@ -6,7 +6,9 @@
#include <quickjs/quickjs.h> #include <quickjs/quickjs.h>
#ifndef DLL_PUBLIC
#define DLL_PUBLIC __attribute__ ((visibility ("default"))) #define DLL_PUBLIC __attribute__ ((visibility ("default")))
#endif
#define countof(x) (sizeof(x) / sizeof((x)[0])) #define countof(x) (sizeof(x) / sizeof((x)[0]))
......
#include <chrono>
#include <cmath>
#include <cstdint>
#include <mavsdk/mavsdk.h>
#include <mavsdk/plugins/action/action.h>
#include <mavsdk/plugins/mavlink_passthrough/mavlink_passthrough.h>
#include <mavsdk/plugins/telemetry/telemetry.h>
#include <iostream>
#include <fstream>
#include <functional>
#include <future>
#include <memory>
#include <thread>
#include "mavsdk_wrapper.h"
using namespace mavsdk;
using std::chrono::seconds;
using std::this_thread::sleep_for;
#define ERROR_CONSOLE_TEXT "\033[31m" // Turn text on console red
#define NORMAL_CONSOLE_TEXT "\033[0m" // Restore normal console colour
static std::ofstream log_file_fd;
static Mavsdk _mavsdk;
static Telemetry * telemetry;
static Action * action;
static MavlinkPassthrough * mavlink_passthrough;
static std::shared_ptr<System> msystem;
static auto prom = std::promise<std::shared_ptr<System>>{};
static std::future<std::shared_ptr<System>> fut;
static const float DEFAULT_RADIUS = 100;
static const float EARTH_RADIUS = 6371000;
static bool takingOff = false;
static int mavsdk_started = 0;
static uint64_t init_timestamp;
static Telemetry::Position origin;
// Logs functions
static void log(std::string message) {
log_file_fd << message << std::endl;
}
static void log_error(std::string message) {
log(ERROR_CONSOLE_TEXT + message + NORMAL_CONSOLE_TEXT);
}
template <class Enumeration>
static void log_error_from_result(std::string message, Enumeration result) {
std::ostringstream oss;
oss << message << ": " << result;
log_error(oss.str());
}
// Action functions
static int doAction(Action::Result (Action::*toDo)(void) const, std::string failure_message) {
if(!mavsdk_started) {
log_error("Mavsdk not started");
return -1;
}
const Action::Result result = (action->*toDo)();
if(result != Action::Result::Success) {
log_error_from_result(failure_message, result);
return -1;
}
return 0;
}
static int doMavlinkCommand(MavlinkPassthrough::CommandLong command, std::string failure_message) {
const MavlinkPassthrough::Result result = mavlink_passthrough->send_command_long(command);
if(result != MavlinkPassthrough::Result::Success) {
log_error_from_result(failure_message, result);
return -1;
}
return 0;
}
// Connexion management functions
static double toRad(double angle) {
return M_PI * angle / 180;
}
static double toDeg(double angle) {
return 180 * angle / M_PI;
}
int mavsdk_start(const char * ip, int port, const char * log_file, int timeout) {
char url[32];
sprintf(url, "udp://%s:%d", ip , port);
std::string connection_url(url);
ConnectionResult connection_result;
float abs_altitude;
log_file_fd.open(log_file);
connection_result = _mavsdk.add_any_connection(connection_url);
if (connection_result != ConnectionResult::Success) {
log_error_from_result("Connection failed", connection_result);
return -1;
}
log("Waiting to discover msystem...");
fut = prom.get_future();
_mavsdk.subscribe_on_new_system([]() {
auto msystem_tmp = _mavsdk.systems().back();
if (msystem_tmp->has_autopilot()) {
log("Discovered autopilot");
// Unsubscribe again as we only want to find one system.
_mavsdk.subscribe_on_new_system(nullptr);
prom.set_value(msystem_tmp);
}
});
if (fut.wait_for(seconds(timeout)) == std::future_status::timeout) {
log_error("No autopilot found, exiting.");
return -1;
}
msystem = fut.get();
telemetry = new Telemetry(msystem);
action = new Action(msystem);
mavlink_passthrough = new MavlinkPassthrough(msystem);
telemetry->subscribe_flight_mode([](Telemetry::FlightMode flight_mode) {
if (takingOff && flight_mode != Telemetry::FlightMode::Takeoff) {
log("Subscribing to raw GPS...");
telemetry->subscribe_raw_gps([](Telemetry::RawGps gps) {
std::ostringstream oss;
oss << (gps.timestamp_us - init_timestamp) / 1000 << ";"
<< gps.latitude_deg << ";" << gps.longitude_deg << ";"
<< gps.absolute_altitude_m << ";" << telemetry->position().relative_altitude_m << ";"
<< telemetry->attitude_euler().yaw_deg << ";"
<< gps.velocity_m_s << ";" << telemetry->fixedwing_metrics().climb_rate_m_s;
log(oss.str());
});
}
switch(flight_mode) {
case Telemetry::FlightMode::Takeoff:
takingOff = true;
log("Taking off...");
break;
default:
if (takingOff) {
takingOff = false;
init_timestamp = telemetry->raw_gps().timestamp_us;
}
}
});
do {
log("Waiting for first telemetry");
sleep_for(seconds(1));
abs_altitude = mavsdk_getAltitude();
} while(isnan(abs_altitude) || abs_altitude == 0);
origin = telemetry->position();
log("MAVSDK started...");
mavsdk_started = 1;
log("timestamp (ms);latitude (°);longitude (°);AMSL (m);rel altitude (m);yaw (°);ground speed (m/s);climb rate (m/s)");
return 0;
}
int mavsdk_stop(bool shutdown) {
if (!mavsdk_started)
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;
}
int mavsdk_reboot() {
return doAction(&Action::reboot, "Rebooting failed");
}
// Flight state management functions
int mavsdk_arm(void) {
if(!mavsdk_started)
return -1;
while(!telemetry->health().is_home_position_ok) {
log("Waiting for home position to be set");
sleep_for(seconds(1));
}
log("Arming...");
return doAction(&Action::arm, "Arming failed");
}
int mavsdk_takeOff(void) {
if (doAction(&Action::takeoff, "Takeoff failed"))
return -1;
return 0;
}
int mavsdk_takeOffAndWait(void) {
if (mavsdk_takeOff() < 0)
return -1;
while (!takingOff)
sleep_for(seconds(1));
while (telemetry->flight_mode() == Telemetry::FlightMode::Takeoff)
sleep_for(seconds(1));
return doAction(&Action::transition_to_fixedwing, "Transition to fixedwing failed");
}
int mavsdk_triggerParachute(void) {
if (!mavsdk_started)
return -1;
log("Landing...");
MavlinkPassthrough::CommandLong command;
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();
return doMavlinkCommand(command, "Parachute release failed");
}
// Flight management functions
static int doReposition(float la, float lo, float radius, float y) {
if (!mavsdk_started)
return -1;
MavlinkPassthrough::CommandLong command;
command.command = MAV_CMD_DO_REPOSITION;
command.param1 = -1; // Ground speed, -1 for default
command.param2 = MAV_DO_REPOSITION_FLAGS_CHANGE_MODE; //will go to navigate mode
command.param3 = radius; // loiter radius
command.param4 = y; // loiter direction, 0: clockwise 1: counter clockwise
command.param5 = la;
command.param6 = lo;
command.target_sysid = mavlink_passthrough->get_target_sysid();
command.target_compid = mavlink_passthrough->get_target_compid();
return doMavlinkCommand(command, "Entering loiter mode failed");
}
int mavsdk_loiter(float radius) {
Telemetry::Position position = telemetry->position();
return doReposition(
(float)position.latitude_deg,
(float)position.longitude_deg,
radius,
0
);
}
int mavsdk_setAirspeed(float airspeed) {
if (!mavsdk_started)
return -1;
MavlinkPassthrough::CommandLong command;
command.command = MAV_CMD_DO_OVERRIDE;
command.param1 = 1 | 2 | 4 | 8;
command.param2 = 2 | 4 | 8;
command.param4 = airspeed;
command.target_sysid = mavlink_passthrough->get_target_sysid();
command.target_compid = mavlink_passthrough->get_target_compid();
return doMavlinkCommand(command, "Setting airspeed failed");
}
static int mavsdk_setAltitude(float altitude) {
if (!mavsdk_started)
return -1;
MavlinkPassthrough::CommandLong command;
command.command = MAV_CMD_DO_OVERRIDE;
command.param1 = 1 | 2 | 4 | 8;
command.param2 = 1 | 2 | 8;
command.param3 = altitude;
command.target_sysid = mavlink_passthrough->get_target_sysid();
command.target_compid = mavlink_passthrough->get_target_compid();
return doMavlinkCommand(command, "Setting altitude failed");
}
/*
* compute the bearing angle between point 1 and point 2
* the bearing angle is the direction to take to go from point 1 to point 2
* values are in [-π; π] where 0 is North
*/
static double bearing(double lat1, double lon1, double lat2, double lon2) {
double lat1_rad = toRad(lat1);
double lat2_rad = toRad(lat2);
double dL = toRad(lon2 - lon1);
double x = cos(lat2_rad) * sin(dL);
double y = cos(lat1_rad) * sin(lat2_rad) - sin(lat1_rad) * cos(lat2_rad) * cos(dL);
return atan2(x, y);
}
int mavsdk_setTargetCoordinates(double la, double lo, float a) {
double b, laRad = toRad(la), loRad = toRad(lo), newLa, newLo;
int result;
float addedDistance = (2 * DEFAULT_RADIUS) / EARTH_RADIUS;
Telemetry::Position position = telemetry->position();
if (!mavsdk_started)
return -1;
b = bearing(position.latitude_deg, position.longitude_deg, la, lo);
newLa = asin(
sin(laRad) * cos(addedDistance)
+ cos(laRad) * sin(addedDistance) * cos(b)
);
newLo = loRad + atan2(
sin(b) * sin(addedDistance) * cos(laRad),
cos(addedDistance) - sin(laRad) * sin(newLa)
);
result = doReposition(
(float)toDeg(newLa),
(float)toDeg(newLo),
DEFAULT_RADIUS,
0
);
result |= mavsdk_setAltitude(a);
return result;
}
// Information functions
float mavsdk_getAltitude(void) {
return telemetry->position().absolute_altitude_m;
}
float mavsdk_getAltitudeRel(void) {
return telemetry->position().relative_altitude_m;
}
float mavsdk_getInitialAltitude(void) {
return origin.absolute_altitude_m;
}
double mavsdk_getInitialLatitude(void) {
return origin.latitude_deg;
}
double mavsdk_getInitialLongitude(void) {
return origin.longitude_deg;
}
double mavsdk_getLatitude(void) {
return telemetry->position().latitude_deg;
}
double mavsdk_getLongitude(void) {
return telemetry->position().longitude_deg;
}
double *mavsdk_getPositionArray(void) {
Telemetry::Position position = telemetry->position();
double *positionArray = (double*) malloc(POSITION_ARRAY_SIZE * sizeof(double));
positionArray[0] = position.latitude_deg;
positionArray[1] = position.longitude_deg;
positionArray[2] = (double) position.absolute_altitude_m;
positionArray[3] = (double) position.relative_altitude_m;
return positionArray;
}
float *mavsdk_getSpeedArray(void) {
Telemetry::FixedwingMetrics metrics = telemetry->fixedwing_metrics();
float *speedArray = (float*) malloc(SPEED_ARRAY_SIZE * sizeof(float));
speedArray[0] = mavsdk_getYaw();
speedArray[1] = metrics.airspeed_m_s;
speedArray[2] = metrics.climb_rate_m_s;
return speedArray;
}
double mavsdk_getTakeOffAltitude(void) {
const std::pair<Action::Result, float> response = action->get_takeoff_altitude();
if (response.first != Action::Result::Success) {
log_error_from_result("Get takeoff altitude failed", response.first);
return -1;
}
return response.second;
}
float mavsdk_getYaw(void) {
return telemetry->attitude_euler().yaw_deg;
}
float mavsdk_getSpeed(void) {
return telemetry->fixedwing_metrics().airspeed_m_s;
}
float mavsdk_getClimbRate(void) {
return telemetry->fixedwing_metrics().climb_rate_m_s;
}
int mavsdk_healthAllOk(void) {
return telemetry->health_all_ok();
}
...@@ -402,7 +402,7 @@ static JSValue js_stop_pubsub(JSContext *ctx, JSValueConst thisVal, ...@@ -402,7 +402,7 @@ static JSValue js_stop_pubsub(JSContext *ctx, JSValueConst thisVal,
// Connexion management functions // Connexion management functions
static JSValue js_mavsdk_start(JSContext *ctx, JSValueConst thisVal, static JSValue js_start(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
const char *ip; const char *ip;
...@@ -418,77 +418,77 @@ static JSValue js_mavsdk_start(JSContext *ctx, JSValueConst thisVal, ...@@ -418,77 +418,77 @@ static JSValue js_mavsdk_start(JSContext *ctx, JSValueConst thisVal,
if (JS_ToInt32(ctx, &timeout, argv[3])) if (JS_ToInt32(ctx, &timeout, argv[3]))
return JS_EXCEPTION; return JS_EXCEPTION;
res = mavsdk_start(ip, port, log_file, timeout); res = start(ip, port, log_file, timeout);
JS_FreeCString(ctx, ip); JS_FreeCString(ctx, ip);
JS_FreeCString(ctx, log_file); JS_FreeCString(ctx, log_file);
return JS_NewInt32(ctx, res); return JS_NewInt32(ctx, res);
} }
static JSValue js_mavsdk_stop(JSContext *ctx, JSValueConst thisVal, static JSValue js_stop(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewInt32(ctx, mavsdk_stop(JS_ToBool(ctx, argv[0]))); return JS_NewInt32(ctx, stop(JS_ToBool(ctx, argv[0])));
} }
static JSValue js_mavsdk_reboot(JSContext *ctx, JSValueConst thisVal, static JSValue js_reboot(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewInt32(ctx, mavsdk_reboot()); return JS_NewInt32(ctx, reboot());
} }
// Flight state management functions // Flight state management functions
static JSValue js_mavsdk_arm(JSContext *ctx, JSValueConst this_val, static JSValue js_arm(JSContext *ctx, JSValueConst this_val,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewInt32(ctx, mavsdk_arm()); return JS_NewInt32(ctx, arm());
} }
static JSValue js_mavsdk_takeOff(JSContext *ctx, JSValueConst thisVal, static JSValue js_takeOff(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewInt32(ctx, mavsdk_takeOff()); return JS_NewInt32(ctx, takeOff());
} }
static JSValue js_mavsdk_takeOffAndWait(JSContext *ctx, JSValueConst thisVal, static JSValue js_takeOffAndWait(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewInt32(ctx, mavsdk_takeOffAndWait()); return JS_NewInt32(ctx, takeOffAndWait());
} }
static JSValue js_mavsdk_triggerParachute(JSContext *ctx, JSValueConst thisVal, static JSValue js_triggerParachute(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewInt32(ctx, mavsdk_triggerParachute()); return JS_NewInt32(ctx, triggerParachute());
} }
// Flight management functions // Flight management functions
static JSValue js_mavsdk_loiter(JSContext *ctx, JSValueConst thisVal, static JSValue js_loiter(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
double radius; double radius;
if (JS_ToFloat64(ctx, &radius, argv[0])) if (JS_ToFloat64(ctx, &radius, argv[0]))
return JS_EXCEPTION; return JS_EXCEPTION;
return JS_NewInt32(ctx, mavsdk_loiter((float)radius)); return JS_NewInt32(ctx, loiter((float)radius));
} }
static JSValue js_mavsdk_setAirspeed(JSContext *ctx, JSValueConst thisVal, static JSValue js_setAirspeed(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
double altitude; double altitude;
if (JS_ToFloat64(ctx, &altitude, argv[0])) if (JS_ToFloat64(ctx, &altitude, argv[0]))
return JS_EXCEPTION; return JS_EXCEPTION;
return JS_NewInt32(ctx, mavsdk_setAirspeed((float)altitude)); return JS_NewInt32(ctx, setAirspeed((float)altitude));
} }
static JSValue js_mavsdk_setTargetCoordinates(JSContext *ctx, static JSValue js_setTargetCoordinates(JSContext *ctx,
JSValueConst thisVal, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
double la_arg_double; double la_arg_double;
double lo_arg_double; double lo_arg_double;
...@@ -501,119 +501,119 @@ static JSValue js_mavsdk_setTargetCoordinates(JSContext *ctx, ...@@ -501,119 +501,119 @@ static JSValue js_mavsdk_setTargetCoordinates(JSContext *ctx,
if (JS_ToFloat64(ctx, &a_arg_double, argv[2])) if (JS_ToFloat64(ctx, &a_arg_double, argv[2]))
return JS_EXCEPTION; return JS_EXCEPTION;
return JS_NewInt32(ctx, mavsdk_setTargetCoordinates(la_arg_double, return JS_NewInt32(ctx, setTargetCoordinates(la_arg_double,
lo_arg_double, lo_arg_double,
(float)a_arg_double)); (float)a_arg_double));
} }
// Information functions // Information functions
static JSValue js_mavsdk_getAltitude(JSContext *ctx, JSValueConst thisVal, static JSValue js_getAltitude(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getAltitude()); return JS_NewFloat64(ctx, getAltitude());
} }
static JSValue js_mavsdk_getAltitudeRel(JSContext *ctx, JSValueConst thisVal, static JSValue js_getAltitudeRel(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getAltitudeRel()); return JS_NewFloat64(ctx, getAltitudeRel());
} }
static JSValue js_mavsdk_getInitialAltitude(JSContext *ctx, static JSValue js_getInitialAltitude(JSContext *ctx,
JSValueConst thisVal, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getInitialAltitude()); return JS_NewFloat64(ctx, getInitialAltitude());
} }
static JSValue js_mavsdk_getInitialLatitude(JSContext *ctx, static JSValue js_getInitialLatitude(JSContext *ctx,
JSValueConst thisVal, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getInitialLatitude()); return JS_NewFloat64(ctx, getInitialLatitude());
} }
static JSValue js_mavsdk_getInitialLongitude(JSContext *ctx, static JSValue js_getInitialLongitude(JSContext *ctx,
JSValueConst thisVal, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getInitialLongitude()); return JS_NewFloat64(ctx, getInitialLongitude());
} }
static JSValue js_mavsdk_getLatitude(JSContext *ctx, JSValueConst thisVal, static JSValue js_getLatitude(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getLatitude()); return JS_NewFloat64(ctx, getLatitude());
} }
static JSValue js_mavsdk_getLongitude(JSContext *ctx, JSValueConst thisVal, static JSValue js_getLongitude(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getLongitude()); return JS_NewFloat64(ctx, getLongitude());
} }
static JSValue js_mavsdk_getTakeOffAltitude(JSContext *ctx, static JSValue js_getTakeOffAltitude(JSContext *ctx,
JSValueConst thisVal, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getTakeOffAltitude()); return JS_NewFloat64(ctx, getTakeOffAltitude());
} }
static JSValue js_mavsdk_getYaw(JSContext *ctx, JSValueConst thisVal, static JSValue js_getYaw(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getYaw()); return JS_NewFloat64(ctx, getYaw());
} }
static JSValue js_mavsdk_getSpeed(JSContext *ctx, JSValueConst thisVal, static JSValue js_getSpeed(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getSpeed()); return JS_NewFloat64(ctx, getSpeed());
} }
static JSValue js_mavsdk_getClimbRate(JSContext *ctx, JSValueConst thisVal, static JSValue js_getClimbRate(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewFloat64(ctx, mavsdk_getClimbRate()); return JS_NewFloat64(ctx, getClimbRate());
} }
static JSValue js_mavsdk_healthAllOk(JSContext *ctx, JSValueConst this_val, static JSValue js_healthAllOk(JSContext *ctx, JSValueConst this_val,
int argc, JSValueConst *argv) int argc, JSValueConst *argv)
{ {
return JS_NewBool(ctx, mavsdk_healthAllOk()); return JS_NewBool(ctx, healthAllOk());
} }
static const JSCFunctionListEntry js_mavsdk_funcs[] = { static const JSCFunctionListEntry js_funcs[] = {
JS_CFUNC_DEF("setMessage", 1, js_drone_set_message ), JS_CFUNC_DEF("setMessage", 1, js_drone_set_message ),
JS_CFUNC_DEF("runPubsub", 6, js_run_pubsub ), JS_CFUNC_DEF("runPubsub", 6, js_run_pubsub ),
JS_CFUNC_DEF("stopPubsub", 0, js_stop_pubsub ), JS_CFUNC_DEF("stopPubsub", 0, js_stop_pubsub ),
JS_CFUNC_DEF("start", 4, js_mavsdk_start ), JS_CFUNC_DEF("start", 4, js_start ),
JS_CFUNC_DEF("stop", 1, js_mavsdk_stop ), JS_CFUNC_DEF("stop", 1, js_stop ),
JS_CFUNC_DEF("reboot", 0, js_mavsdk_reboot ), JS_CFUNC_DEF("reboot", 0, js_reboot ),
JS_CFUNC_DEF("arm", 0, js_mavsdk_arm ), JS_CFUNC_DEF("arm", 0, js_arm ),
JS_CFUNC_DEF("takeOff", 0, js_mavsdk_takeOff ), JS_CFUNC_DEF("takeOff", 0, js_takeOff ),
JS_CFUNC_DEF("takeOffAndWait", 0, js_mavsdk_takeOffAndWait ), JS_CFUNC_DEF("takeOffAndWait", 0, js_takeOffAndWait ),
JS_CFUNC_DEF("triggerParachute", 0, js_mavsdk_triggerParachute ), JS_CFUNC_DEF("triggerParachute", 0, js_triggerParachute ),
JS_CFUNC_DEF("loiter", 1, js_mavsdk_loiter ), JS_CFUNC_DEF("loiter", 1, js_loiter ),
JS_CFUNC_DEF("setAirspeed", 1, js_mavsdk_setAirspeed ), JS_CFUNC_DEF("setAirspeed", 1, js_setAirspeed ),
JS_CFUNC_DEF("setTargetCoordinates", 3, js_mavsdk_setTargetCoordinates ), JS_CFUNC_DEF("setTargetCoordinates", 3, js_setTargetCoordinates ),
JS_CFUNC_DEF("getAltitude", 0, js_mavsdk_getAltitude ), JS_CFUNC_DEF("getAltitude", 0, js_getAltitude ),
JS_CFUNC_DEF("getAltitudeRel", 0, js_mavsdk_getAltitudeRel ), JS_CFUNC_DEF("getAltitudeRel", 0, js_getAltitudeRel ),
JS_CFUNC_DEF("getInitialAltitude", 0, js_mavsdk_getInitialAltitude ), JS_CFUNC_DEF("getInitialAltitude", 0, js_getInitialAltitude ),
JS_CFUNC_DEF("getInitialLatitude", 0, js_mavsdk_getInitialLatitude ), JS_CFUNC_DEF("getInitialLatitude", 0, js_getInitialLatitude ),
JS_CFUNC_DEF("getInitialLongitude", 0, js_mavsdk_getInitialLongitude ), JS_CFUNC_DEF("getInitialLongitude", 0, js_getInitialLongitude ),
JS_CFUNC_DEF("getLatitude", 0, js_mavsdk_getLatitude ), JS_CFUNC_DEF("getLatitude", 0, js_getLatitude ),
JS_CFUNC_DEF("getLongitude", 0, js_mavsdk_getLongitude ), JS_CFUNC_DEF("getLongitude", 0, js_getLongitude ),
JS_CFUNC_DEF("getTakeOffAltitude", 0, js_mavsdk_getTakeOffAltitude ), JS_CFUNC_DEF("getTakeOffAltitude", 0, js_getTakeOffAltitude ),
JS_CFUNC_DEF("getYaw", 0, js_mavsdk_getYaw ), JS_CFUNC_DEF("getYaw", 0, js_getYaw ),
JS_CFUNC_DEF("getAirspeed", 0, js_mavsdk_getSpeed ), JS_CFUNC_DEF("getAirspeed", 0, js_getSpeed ),
JS_CFUNC_DEF("getClimbRate", 0, js_mavsdk_getClimbRate ), JS_CFUNC_DEF("getClimbRate", 0, js_getClimbRate ),
JS_CFUNC_DEF("healthAllOk", 0, js_mavsdk_healthAllOk ), JS_CFUNC_DEF("healthAllOk", 0, js_healthAllOk ),
JS_CFUNC_DEF("initPubsub", 1, js_init_pubsub ), JS_CFUNC_DEF("initPubsub", 1, js_init_pubsub ),
}; };
static int js_mavsdk_init(JSContext *ctx, JSModuleDef *m) static int js_init(JSContext *ctx, JSModuleDef *m)
{ {
JSValue droneProto, droneClass; JSValue droneProto, droneClass;
...@@ -631,17 +631,17 @@ static int js_mavsdk_init(JSContext *ctx, JSModuleDef *m) ...@@ -631,17 +631,17 @@ static int js_mavsdk_init(JSContext *ctx, JSModuleDef *m)
JS_SetModuleExport(ctx, m, "Drone", droneClass); JS_SetModuleExport(ctx, m, "Drone", droneClass);
return JS_SetModuleExportList(ctx, m, js_mavsdk_funcs, return JS_SetModuleExportList(ctx, m, js_funcs,
countof(js_mavsdk_funcs)); countof(js_funcs));
} }
JSModuleDef *js_init_module(JSContext *ctx, const char *module_name) JSModuleDef *js_init_module(JSContext *ctx, const char *module_name)
{ {
JSModuleDef *m; JSModuleDef *m;
m = JS_NewCModule(ctx, module_name, js_mavsdk_init); m = JS_NewCModule(ctx, module_name, js_init);
if (!m) if (!m)
return NULL; return NULL;
JS_AddModuleExportList(ctx, m, js_mavsdk_funcs, countof(js_mavsdk_funcs)); JS_AddModuleExportList(ctx, m, js_funcs, countof(js_funcs));
JS_AddModuleExport(ctx, m, "Drone"); JS_AddModuleExport(ctx, m, "Drone");
return m; return m;
} }
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