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

sort qjs_wrapper functions

parent 66755185
......@@ -314,7 +314,6 @@ static int startAltitudeControl(void) {
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);
......
......@@ -16,6 +16,8 @@ UA_String currentMessage;
pthread_mutex_t mutex;
pthread_cond_t threadCond;
// Drone class functions
static void js_drone_finalizer(JSRuntime *rt, JSValue val)
{
JSDroneData *s = (JSDroneData *) JS_GetOpaque(val, jsDroneClassId);
......@@ -169,6 +171,8 @@ static const JSCFunctionListEntry js_drone_proto_funcs[] = {
JS_CFUNC_DEF("init", 1, js_drone_init),
};
// pubsub functions
UA_UInt16 get_drone_id(UA_UInt32 nb) {
JSDroneData *s = (JSDroneData *) JS_GetOpaque(droneObjectIdList[nb], jsDroneClassId);
return s->id;
......@@ -384,6 +388,8 @@ static JSValue js_stop_pubsub(JSContext *ctx, JSValueConst thisVal,
return JS_NewInt32(ctx, 0);
}
// Connexion management functions
static JSValue js_mavsdk_start(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
......@@ -416,58 +422,53 @@ static JSValue js_mavsdk_reboot(JSContext *ctx, JSValueConst thisVal,
return JS_NewInt32(ctx, mavsdk_reboot());
}
static JSValue js_mavsdk_healthAllOk(JSContext *ctx, JSValueConst this_val,
// Flight state management functions
static JSValue js_mavsdk_arm(JSContext *ctx, JSValueConst this_val,
int argc, JSValueConst *argv)
{
return JS_NewBool(ctx, mavsdk_healthAllOk());
return JS_NewInt32(ctx, mavsdk_arm());
}
static JSValue js_mavsdk_landed(JSContext *ctx, JSValueConst this_val,
static JSValue js_mavsdk_land(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewBool(ctx, mavsdk_landed());
return JS_NewInt32(ctx, mavsdk_land());
}
static JSValue js_mavsdk_isInManualMode(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_takeOff(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewBool(ctx, mavsdk_isInManualMode());
return JS_NewInt32(ctx, mavsdk_takeOff());
}
static JSValue js_mavsdk_arm(JSContext *ctx, JSValueConst this_val,
static JSValue js_mavsdk_takeOffAndWait(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewInt32(ctx, mavsdk_arm());
return JS_NewInt32(ctx, mavsdk_takeOffAndWait());
}
static JSValue js_mavsdk_setTargetCoordinates(JSContext *ctx,
JSValueConst thisVal,
static JSValue js_mavsdk_triggerParachute(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
double la_arg_double;
double lo_arg_double;
double a_arg_double;
if (JS_ToFloat64(ctx, &la_arg_double, argv[0]))
return JS_EXCEPTION;
if (JS_ToFloat64(ctx, &lo_arg_double, argv[1]))
return JS_EXCEPTION;
if (JS_ToFloat64(ctx, &a_arg_double, argv[2]))
return JS_EXCEPTION;
return JS_NewInt32(ctx, mavsdk_setTargetCoordinates(la_arg_double,
lo_arg_double,
(float)a_arg_double));
return JS_NewInt32(ctx, mavsdk_triggerParachute());
}
static JSValue js_mavsdk_setManualControlInput(JSContext *ctx,
JSValueConst thisVal,
// Flight management functions
static JSValue js_mavsdk_loiter(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewInt32(ctx, mavsdk_setManualControlInput());
double radius = 100;
if (argc > 0) {
if (JS_ToFloat64(ctx, &radius, argv[0]))
return JS_EXCEPTION;
}
return JS_NewInt32(ctx, mavsdk_loiter((float)radius));
}
static JSValue js_mavsdk_setAltitude(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_setAirspeed(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
double altitude;
......@@ -475,10 +476,10 @@ static JSValue js_mavsdk_setAltitude(JSContext *ctx, JSValueConst thisVal,
if (JS_ToFloat64(ctx, &altitude, argv[0]))
return JS_EXCEPTION;
return JS_NewInt32(ctx, mavsdk_setAltitude((float)altitude));
return JS_NewInt32(ctx, mavsdk_setAirspeed((float)altitude));
}
static JSValue js_mavsdk_setAirspeed(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_setAltitude(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
double altitude;
......@@ -486,133 +487,144 @@ static JSValue js_mavsdk_setAirspeed(JSContext *ctx, JSValueConst thisVal,
if (JS_ToFloat64(ctx, &altitude, argv[0]))
return JS_EXCEPTION;
return JS_NewInt32(ctx, mavsdk_setAirspeed((float)altitude));
return JS_NewInt32(ctx, mavsdk_setAltitude((float)altitude));
}
static JSValue js_mavsdk_getYaw(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_setTargetCoordinates(JSContext *ctx,
JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewFloat64(ctx, mavsdk_getYaw());
double la_arg_double;
double lo_arg_double;
double a_arg_double;
if (JS_ToFloat64(ctx, &la_arg_double, argv[0]))
return JS_EXCEPTION;
if (JS_ToFloat64(ctx, &lo_arg_double, argv[1]))
return JS_EXCEPTION;
if (JS_ToFloat64(ctx, &a_arg_double, argv[2]))
return JS_EXCEPTION;
return JS_NewInt32(ctx, mavsdk_setTargetCoordinates(la_arg_double,
lo_arg_double,
(float)a_arg_double));
}
static JSValue js_mavsdk_getInitialLatitude(JSContext *ctx,
static JSValue js_mavsdk_setManualControlInput(JSContext *ctx,
JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewFloat64(ctx, mavsdk_getInitialLatitude());
return JS_NewInt32(ctx, mavsdk_setManualControlInput());
}
static JSValue js_mavsdk_getLatitude(JSContext *ctx, JSValueConst thisVal,
// Information functions
static JSValue js_mavsdk_getAltitude(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewFloat64(ctx, mavsdk_getLatitude());
return JS_NewFloat64(ctx, mavsdk_getAltitude());
}
static JSValue js_mavsdk_getInitialLongitude(JSContext *ctx,
JSValueConst thisVal,
static JSValue js_mavsdk_getAltitudeRel(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewFloat64(ctx, mavsdk_getInitialLongitude());
return JS_NewFloat64(ctx, mavsdk_getAltitudeRel());
}
static JSValue js_mavsdk_getLongitude(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_getInitialAltitude(JSContext *ctx,
JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewFloat64(ctx, mavsdk_getLongitude());
return JS_NewFloat64(ctx, mavsdk_getInitialAltitude());
}
static JSValue js_mavsdk_getTakeOffAltitude(JSContext *ctx,
static JSValue js_mavsdk_getInitialLatitude(JSContext *ctx,
JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewFloat64(ctx, mavsdk_getTakeOffAltitude());
return JS_NewFloat64(ctx, mavsdk_getInitialLatitude());
}
static JSValue js_mavsdk_getInitialAltitude(JSContext *ctx,
static JSValue js_mavsdk_getInitialLongitude(JSContext *ctx,
JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewFloat64(ctx, mavsdk_getInitialAltitude());
return JS_NewFloat64(ctx, mavsdk_getInitialLongitude());
}
static JSValue js_mavsdk_getAltitude(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_getLatitude(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewFloat64(ctx, mavsdk_getAltitude());
return JS_NewFloat64(ctx, mavsdk_getLatitude());
}
static JSValue js_mavsdk_getAltitudeRel(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_getLongitude(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewFloat64(ctx, mavsdk_getAltitudeRel());
return JS_NewFloat64(ctx, mavsdk_getLongitude());
}
static JSValue js_mavsdk_loiter(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_getTakeOffAltitude(JSContext *ctx,
JSValueConst thisVal,
int argc, JSValueConst *argv)
{
double radius = 100;
if (argc > 0) {
if (JS_ToFloat64(ctx, &radius, argv[0]))
return JS_EXCEPTION;
}
return JS_NewInt32(ctx, mavsdk_loiter((float)radius));
return JS_NewFloat64(ctx, mavsdk_getTakeOffAltitude());
}
static JSValue js_mavsdk_triggerParachute(JSContext *ctx, JSValueConst this_val,
static JSValue js_mavsdk_getYaw(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewInt32(ctx, mavsdk_triggerParachute());
return JS_NewFloat64(ctx, mavsdk_getYaw());
}
static JSValue js_mavsdk_takeOff(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_healthAllOk(JSContext *ctx, JSValueConst this_val,
int argc, JSValueConst *argv)
{
return JS_NewInt32(ctx, mavsdk_takeOff());
return JS_NewBool(ctx, mavsdk_healthAllOk());
}
static JSValue js_mavsdk_takeOffAndWait(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_isInManualMode(JSContext *ctx, JSValueConst thisVal,
int argc, JSValueConst *argv)
{
return JS_NewInt32(ctx, mavsdk_takeOffAndWait());
return JS_NewBool(ctx, mavsdk_isInManualMode());
}
static JSValue js_mavsdk_land(JSContext *ctx, JSValueConst thisVal,
static JSValue js_mavsdk_landed(JSContext *ctx, JSValueConst this_val,
int argc, JSValueConst *argv)
{
return JS_NewInt32(ctx, mavsdk_land());
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", 3, js_mavsdk_start ),
JS_CFUNC_DEF("stop", 0, js_mavsdk_stop ),
JS_CFUNC_DEF("reboot", 0, js_mavsdk_reboot ),
JS_CFUNC_DEF("healthAllOk", 0, js_mavsdk_healthAllOk ),
JS_CFUNC_DEF("landed", 0, js_mavsdk_landed ),
JS_CFUNC_DEF("isInManualMode", 0, js_mavsdk_isInManualMode ),
JS_CFUNC_DEF("arm", 0, js_mavsdk_arm ),
JS_CFUNC_DEF("land", 0, js_mavsdk_land ),
JS_CFUNC_DEF("takeOff", 0, js_mavsdk_takeOff ),
JS_CFUNC_DEF("takeOffAndWait", 0, js_mavsdk_takeOffAndWait ),
JS_CFUNC_DEF("triggerParachute", 0, js_mavsdk_triggerParachute ),
JS_CFUNC_DEF("loiter", 0, js_mavsdk_loiter ),
JS_CFUNC_DEF("setAirspeed", 1, js_mavsdk_setAirspeed ),
JS_CFUNC_DEF("setAltitude", 1, js_mavsdk_setAltitude ),
JS_CFUNC_DEF("setTargetCoordinates", 3, js_mavsdk_setTargetCoordinates ),
JS_CFUNC_DEF("setManualControlInput", 0, js_mavsdk_setManualControlInput ),
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("triggerParachute", 0, js_mavsdk_triggerParachute ),
JS_CFUNC_DEF("getYaw", 0, js_mavsdk_getYaw ),
JS_CFUNC_DEF("getAltitude", 0, js_mavsdk_getAltitude ),
JS_CFUNC_DEF("getAltitudeRel", 0, js_mavsdk_getAltitudeRel ),
JS_CFUNC_DEF("getInitialAltitude", 0, js_mavsdk_getInitialAltitude ),
JS_CFUNC_DEF("getInitialLatitude", 0, js_mavsdk_getInitialLatitude ),
JS_CFUNC_DEF("getLatitude", 0, js_mavsdk_getLatitude ),
JS_CFUNC_DEF("getInitialLongitude", 0, js_mavsdk_getInitialLongitude ),
JS_CFUNC_DEF("getLatitude", 0, js_mavsdk_getLatitude ),
JS_CFUNC_DEF("getLongitude", 0, js_mavsdk_getLongitude ),
JS_CFUNC_DEF("getTakeOffAltitude", 0, js_mavsdk_getTakeOffAltitude ),
JS_CFUNC_DEF("getInitialAltitude", 0, js_mavsdk_getInitialAltitude ),
JS_CFUNC_DEF("getAltitude", 0, js_mavsdk_getAltitude ),
JS_CFUNC_DEF("getAltitudeRel", 0, js_mavsdk_getAltitudeRel ),
JS_CFUNC_DEF("takeOff", 0, js_mavsdk_takeOff ),
JS_CFUNC_DEF("takeOffAndWait", 0, js_mavsdk_takeOffAndWait ),
JS_CFUNC_DEF("land", 0, js_mavsdk_land ),
JS_CFUNC_DEF("getYaw", 0, js_mavsdk_getYaw ),
JS_CFUNC_DEF("isInManualMode", 0, js_mavsdk_isInManualMode ),
JS_CFUNC_DEF("healthAllOk", 0, js_mavsdk_healthAllOk ),
JS_CFUNC_DEF("landed", 0, js_mavsdk_landed ),
JS_CFUNC_DEF("initPubsub", 1, js_init_pubsub ),
JS_CFUNC_DEF("runPubsub", 6, js_run_pubsub ),
JS_CFUNC_DEF("setMessage", 1, js_drone_set_message ),
JS_CFUNC_DEF("stopPubsub", 0, js_stop_pubsub ),
};
static int js_mavsdk_init(JSContext *ctx, JSModuleDef *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