Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Q
qjs-wrapper
Project overview
Project overview
Details
Activity
Releases
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Analytics
Analytics
CI / CD
Repository
Value Stream
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
nexedi
qjs-wrapper
Commits
f616af35
Commit
f616af35
authored
Sep 08, 2022
by
Léo-Paul Géneau
👾
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
change doParachute into triggerParachute
parent
29fe3da7
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
16 additions
and
21 deletions
+16
-21
include/mavsdk_wrapper.h
include/mavsdk_wrapper.h
+1
-1
mavsdk_wrapper.cpp
mavsdk_wrapper.cpp
+12
-12
qjs_wrapper.c
qjs_wrapper.c
+3
-8
No files found.
include/mavsdk_wrapper.h
View file @
f616af35
...
@@ -12,11 +12,11 @@ int mavsdk_reboot(void);
...
@@ -12,11 +12,11 @@ int mavsdk_reboot(void);
// Flight state management functions
// Flight state management functions
int
mavsdk_arm
(
void
);
int
mavsdk_arm
(
void
);
int
mavsdk_doParachute
(
float
param
);
int
mavsdk_loiter
();
int
mavsdk_loiter
();
int
mavsdk_land
(
void
);
int
mavsdk_land
(
void
);
int
mavsdk_takeOff
(
void
);
int
mavsdk_takeOff
(
void
);
int
mavsdk_takeOffAndWait
(
void
);
int
mavsdk_takeOffAndWait
(
void
);
int
mavsdk_triggerParachute
(
void
);
// Flight management functions
// Flight management functions
int
mavsdk_doReposition
(
float
la
,
float
lo
,
float
a
,
float
y
);
int
mavsdk_doReposition
(
float
la
,
float
lo
,
float
a
,
float
y
);
...
...
mavsdk_wrapper.cpp
View file @
f616af35
...
@@ -214,18 +214,6 @@ int mavsdk_arm(void) {
...
@@ -214,18 +214,6 @@ int mavsdk_arm(void) {
return
doAction
(
&
Action
::
arm
,
"Arming failed"
);
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
)
{
int
mavsdk_land
(
void
)
{
log
(
"Landing..."
);
log
(
"Landing..."
);
if
(
doAction
(
&
Action
::
terminate
,
"Land failed"
))
{
if
(
doAction
(
&
Action
::
terminate
,
"Land failed"
))
{
...
@@ -280,6 +268,18 @@ int mavsdk_takeOffAndWait(void) {
...
@@ -280,6 +268,18 @@ int mavsdk_takeOffAndWait(void) {
return
0
;
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
// Flight management functions
int
mavsdk_doReposition
(
float
la
,
float
lo
,
float
a
,
float
y
)
{
int
mavsdk_doReposition
(
float
la
,
float
lo
,
float
a
,
float
y
)
{
...
...
qjs_wrapper.c
View file @
f616af35
...
@@ -463,15 +463,10 @@ static JSValue js_mavsdk_loiter(JSContext *ctx, JSValueConst this_val,
...
@@ -463,15 +463,10 @@ static JSValue js_mavsdk_loiter(JSContext *ctx, JSValueConst this_val,
return
JS_NewInt32
(
ctx
,
mavsdk_loiter
());
return
JS_NewInt32
(
ctx
,
mavsdk_loiter
());
}
}
static
JSValue
js_mavsdk_
do
Parachute
(
JSContext
*
ctx
,
JSValueConst
this_val
,
static
JSValue
js_mavsdk_
trigger
Parachute
(
JSContext
*
ctx
,
JSValueConst
this_val
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
double
param
;
return
JS_NewInt32
(
ctx
,
mavsdk_triggerParachute
());
if
(
JS_ToFloat64
(
ctx
,
&
param
,
argv
[
0
]))
return
JS_EXCEPTION
;
return
JS_NewInt32
(
ctx
,
mavsdk_doParachute
((
float
)
param
));
}
}
static
JSValue
js_mavsdk_takeOff
(
JSContext
*
ctx
,
JSValueConst
this_val
,
static
JSValue
js_mavsdk_takeOff
(
JSContext
*
ctx
,
JSValueConst
this_val
,
...
@@ -503,7 +498,7 @@ static const JSCFunctionListEntry js_mavsdk_funcs[] = {
...
@@ -503,7 +498,7 @@ static const JSCFunctionListEntry js_mavsdk_funcs[] = {
JS_CFUNC_DEF
(
"setAltitude"
,
1
,
js_mavsdk_setAltitude
),
JS_CFUNC_DEF
(
"setAltitude"
,
1
,
js_mavsdk_setAltitude
),
JS_CFUNC_DEF
(
"setAirspeed"
,
1
,
js_mavsdk_setAirspeed
),
JS_CFUNC_DEF
(
"setAirspeed"
,
1
,
js_mavsdk_setAirspeed
),
JS_CFUNC_DEF
(
"loiter"
,
0
,
js_mavsdk_loiter
),
JS_CFUNC_DEF
(
"loiter"
,
0
,
js_mavsdk_loiter
),
JS_CFUNC_DEF
(
"
doParachute"
,
1
,
js_mavsdk_do
Parachute
),
JS_CFUNC_DEF
(
"
triggerParachute"
,
0
,
js_mavsdk_trigger
Parachute
),
JS_CFUNC_DEF
(
"getYaw"
,
0
,
js_mavsdk_getYaw
),
JS_CFUNC_DEF
(
"getYaw"
,
0
,
js_mavsdk_getYaw
),
JS_CFUNC_DEF
(
"getInitialLatitude"
,
0
,
js_mavsdk_getInitialLatitude
),
JS_CFUNC_DEF
(
"getInitialLatitude"
,
0
,
js_mavsdk_getInitialLatitude
),
JS_CFUNC_DEF
(
"getLatitude"
,
0
,
js_mavsdk_getLatitude
),
JS_CFUNC_DEF
(
"getLatitude"
,
0
,
js_mavsdk_getLatitude
),
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment