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
66755185
Commit
66755185
authored
Aug 11, 2022
by
Léo-Paul Géneau
👾
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
pubsub: use message instead of checkpoint
parent
a2430d79
Changes
4
Show whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
217 additions
and
121 deletions
+217
-121
include/dronedge.h
include/dronedge.h
+19
-7
include/pubsub.h
include/pubsub.h
+11
-10
pubsub.c
pubsub.c
+14
-12
qjs_wrapper.c
qjs_wrapper.c
+173
-92
No files found.
include/dronedge.h
View file @
66755185
...
@@ -5,11 +5,23 @@
...
@@ -5,11 +5,23 @@
#include "mavsdk_wrapper.h"
#include "mavsdk_wrapper.h"
#include "pubsub.h"
#include "pubsub.h"
struct
messageNode
{
char
*
message
;
struct
messageNode
*
next
;
};
typedef
struct
{
struct
messageNode
*
head
;
struct
messageNode
*
tail
;
}
MessageQueue
;
UA_Double
latitude
=
0
;
UA_Double
latitude
=
0
;
UA_Double
longitude
=
0
;
UA_Double
longitude
=
0
;
UA_Float
altitude_abs
=
0
;
UA_Float
altitude_abs
=
0
;
UA_Float
altitude_rel
=
0
;
UA_Float
altitude_rel
=
0
;
UA_UInt32
last_checkpoint
=
0
;
UA_String
message
=
{
.
length
=
0
,
.
data
=
NULL
,
};
VariableData
droneVariableArray
[]
=
{
VariableData
droneVariableArray
[]
=
{
{
{
...
@@ -45,12 +57,12 @@ VariableData droneVariableArray[] = {
...
@@ -45,12 +57,12 @@ VariableData droneVariableArray[] = {
.
getter
.
getFloat
=
mavsdk_getAltitudeRel
,
.
getter
.
getFloat
=
mavsdk_getAltitudeRel
,
},
},
{
{
.
name
=
"
last_checkpoint
"
,
.
name
=
"
message
"
,
.
description
=
"
Last checkpoint flown over
"
,
.
description
=
"
Message to send to the other drones
"
,
.
value
=
&
last_checkpoint
,
.
value
=
&
message
,
.
type
=
UA_TYPES_
UINT32
,
.
type
=
UA_TYPES_
STRING
,
.
builtInType
=
UA_NS0ID_
UINT32
,
.
builtInType
=
UA_NS0ID_
STRING
,
.
getter
.
get
Uint32
=
getLastCheckpoint
.
getter
.
get
String
=
get_message
},
},
};
};
...
...
include/pubsub.h
View file @
66755185
...
@@ -13,6 +13,8 @@
...
@@ -13,6 +13,8 @@
#define DATA_SET_WRITER_ID 1
#define DATA_SET_WRITER_ID 1
#define WRITER_GROUP_ID 1
#define WRITER_GROUP_ID 1
#define MAX_MESSAGE_SIZE 1024
typedef
struct
{
typedef
struct
{
UA_UInt16
id
;
UA_UInt16
id
;
UA_Double
latitude
;
UA_Double
latitude
;
...
@@ -23,8 +25,8 @@ typedef struct {
...
@@ -23,8 +25,8 @@ typedef struct {
UA_UInt32
altitudeAbsId
;
UA_UInt32
altitudeAbsId
;
UA_Float
altitudeRel
;
UA_Float
altitudeRel
;
UA_UInt32
altitudeRelId
;
UA_UInt32
altitudeRelId
;
UA_UInt32
lastCheckpoint
;
char
message
[
MAX_MESSAGE_SIZE
]
;
UA_UInt32
lastCheckpoint
Id
;
UA_UInt32
message
Id
;
}
JSDroneData
;
}
JSDroneData
;
typedef
struct
{
typedef
struct
{
...
@@ -34,10 +36,11 @@ typedef struct {
...
@@ -34,10 +36,11 @@ typedef struct {
int
type
;
int
type
;
UA_Byte
builtInType
;
UA_Byte
builtInType
;
union
{
union
{
UA_UInt32
(
*
getUint32
)(
void
);
UA_Float
(
*
getFloat
)(
void
);
UA_Double
(
*
getDouble
)(
void
);
UA_DateTime
(
*
getTimestamp
)(
void
);
UA_DateTime
(
*
getTimestamp
)(
void
);
UA_Double
(
*
getDouble
)(
void
);
UA_Float
(
*
getFloat
)(
void
);
UA_String
(
*
getString
)(
void
);
UA_UInt32
(
*
getUint32
)(
void
);
}
getter
;
}
getter
;
}
VariableData
;
}
VariableData
;
...
@@ -45,7 +48,7 @@ typedef struct {
...
@@ -45,7 +48,7 @@ typedef struct {
int
subscribeOnly
(
UA_String
*
transportProfile
,
int
subscribeOnly
(
UA_String
*
transportProfile
,
UA_NetworkAddressUrlDataType
*
networkAddressUrl
,
UA_NetworkAddressUrlDataType
*
networkAddressUrl
,
VariableData
*
variableArray
,
size_t
nbVariable
,
VariableData
*
variableArray
,
size_t
nbVariable
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_Duration
interval
,
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
void
(
*
update
)(
UA_UInt32
id
,
const
UA_DataValue
*
),
void
(
*
update
)(
UA_UInt32
id
,
const
UA_DataValue
*
),
...
@@ -54,14 +57,14 @@ int subscribeOnly(UA_String *transportProfile,
...
@@ -54,14 +57,14 @@ int subscribeOnly(UA_String *transportProfile,
int
runPubsub
(
UA_String
*
transportProfile
,
int
runPubsub
(
UA_String
*
transportProfile
,
UA_NetworkAddressUrlDataType
*
networkAddressUrl
,
UA_NetworkAddressUrlDataType
*
networkAddressUrl
,
VariableData
*
variableArray
,
size_t
nbVariable
,
VariableData
*
variableArray
,
size_t
nbVariable
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_Duration
interval
,
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
VariableData
(
*
get_value
)(
UA_String
identifier
),
VariableData
(
*
get_value
)(
UA_String
identifier
),
void
(
*
update
)(
UA_UInt32
id
,
const
UA_DataValue
*
),
void
(
*
update
)(
UA_UInt32
id
,
const
UA_DataValue
*
),
UA_Boolean
*
running
);
UA_Boolean
*
running
);
UA_
UInt32
getLastCheckpoint
(
void
);
UA_
String
get_message
(
void
);
UA_UInt16
get_drone_id
(
UA_UInt32
nb
);
UA_UInt16
get_drone_id
(
UA_UInt32
nb
);
...
@@ -73,8 +76,6 @@ void pubsub_print_coordinates(UA_UInt32 id, const UA_DataValue *var);
...
@@ -73,8 +76,6 @@ void pubsub_print_coordinates(UA_UInt32 id, const UA_DataValue *var);
VariableData
pubsub_get_value
(
UA_String
identifier
);
VariableData
pubsub_get_value
(
UA_String
identifier
);
void
stop_pubsub
(
void
);
DLL_PUBLIC
JSModuleDef
*
js_init_module
(
JSContext
*
ctx
,
const
char
*
module_name
);
DLL_PUBLIC
JSModuleDef
*
js_init_module
(
JSContext
*
ctx
,
const
char
*
module_name
);
#endif
/* __PUBSUB_H__ */
#endif
/* __PUBSUB_H__ */
pubsub.c
View file @
66755185
...
@@ -135,13 +135,13 @@ addDataSetField(UA_Server *server, VariableData varDetails) {
...
@@ -135,13 +135,13 @@ addDataSetField(UA_Server *server, VariableData varDetails) {
* The WriterGroup (WG) is part of the connection and contains the primary
* The WriterGroup (WG) is part of the connection and contains the primary
* configuration parameters for the message creation. */
* configuration parameters for the message creation. */
static
void
static
void
addWriterGroup
(
UA_Server
*
server
)
{
addWriterGroup
(
UA_Server
*
server
,
UA_Duration
publishingInterval
)
{
/* Now we create a new WriterGroupConfig and add the group to the existing
/* Now we create a new WriterGroupConfig and add the group to the existing
* PubSubConnection. */
* PubSubConnection. */
UA_WriterGroupConfig
writerGroupConfig
;
UA_WriterGroupConfig
writerGroupConfig
;
memset
(
&
writerGroupConfig
,
0
,
sizeof
(
UA_WriterGroupConfig
));
memset
(
&
writerGroupConfig
,
0
,
sizeof
(
UA_WriterGroupConfig
));
writerGroupConfig
.
name
=
UA_STRING
(
"Demo WriterGroup"
);
writerGroupConfig
.
name
=
UA_STRING
(
"Demo WriterGroup"
);
writerGroupConfig
.
publishingInterval
=
100
;
writerGroupConfig
.
publishingInterval
=
publishingInterval
;
writerGroupConfig
.
enabled
=
UA_FALSE
;
writerGroupConfig
.
enabled
=
UA_FALSE
;
writerGroupConfig
.
writerGroupId
=
WRITER_GROUP_ID
;
writerGroupConfig
.
writerGroupId
=
WRITER_GROUP_ID
;
writerGroupConfig
.
encodingMimeType
=
UA_PUBSUB_ENCODING_UADP
;
writerGroupConfig
.
encodingMimeType
=
UA_PUBSUB_ENCODING_UADP
;
...
@@ -245,7 +245,8 @@ dataChangeNotificationCallback(UA_Server *server, UA_UInt32 monitoredItemId,
...
@@ -245,7 +245,8 @@ dataChangeNotificationCallback(UA_Server *server, UA_UInt32 monitoredItemId,
* Set SubscribedDataSet type to TargetVariables data type.
* Set SubscribedDataSet type to TargetVariables data type.
* Add subscribedvariables to the DataSetReader */
* Add subscribedvariables to the DataSetReader */
static
UA_StatusCode
static
UA_StatusCode
addSubscribedVariables
(
UA_Server
*
server
,
UA_NodeId
dataSetReaderId
,
UA_UInt32
nb
,
addSubscribedVariables
(
UA_Server
*
server
,
UA_NodeId
dataSetReaderId
,
UA_UInt32
nb
,
UA_Duration
samplingInterval
,
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
))
{
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
))
{
if
(
server
==
NULL
)
if
(
server
==
NULL
)
return
UA_STATUSCODE_BADINTERNALERROR
;
return
UA_STATUSCODE_BADINTERNALERROR
;
...
@@ -302,6 +303,7 @@ addSubscribedVariables(UA_Server *server, UA_NodeId dataSetReaderId, UA_UInt32 n
...
@@ -302,6 +303,7 @@ addSubscribedVariables(UA_Server *server, UA_NodeId dataSetReaderId, UA_UInt32 n
/*monitor variable*/
/*monitor variable*/
UA_MonitoredItemCreateRequest
monRequest
=
UA_MonitoredItemCreateRequest_default
(
newNode
);
UA_MonitoredItemCreateRequest
monRequest
=
UA_MonitoredItemCreateRequest_default
(
newNode
);
init_node_id
(
newNode
.
identifier
.
numeric
,
nb
,
i
);
init_node_id
(
newNode
.
identifier
.
numeric
,
nb
,
i
);
monRequest
.
requestedParameters
.
samplingInterval
=
samplingInterval
;
UA_Server_createDataChangeMonitoredItem
(
server
,
UA_TIMESTAMPSTORETURN_SOURCE
,
UA_Server_createDataChangeMonitoredItem
(
server
,
UA_TIMESTAMPSTORETURN_SOURCE
,
monRequest
,
NULL
,
dataChangeNotificationCallback
);
monRequest
,
NULL
,
dataChangeNotificationCallback
);
...
@@ -375,7 +377,7 @@ setServer(UA_String *transportProfile,
...
@@ -375,7 +377,7 @@ setServer(UA_String *transportProfile,
static
UA_StatusCode
static
UA_StatusCode
subscribe
(
UA_Server
*
server
,
subscribe
(
UA_Server
*
server
,
VariableData
*
variableArray
,
size_t
nbVariable
,
VariableData
*
variableArray
,
size_t
nbVariable
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_Duration
interval
,
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
void
(
*
update
)(
UA_UInt32
id
,
const
UA_DataValue
*
))
{
void
(
*
update
)(
UA_UInt32
id
,
const
UA_DataValue
*
))
{
...
@@ -405,7 +407,7 @@ subscribe(UA_Server *server,
...
@@ -405,7 +407,7 @@ subscribe(UA_Server *server,
return
EXIT_FAILURE
;
return
EXIT_FAILURE
;
/* Add SubscribedVariables to the created DataSetReader */
/* Add SubscribedVariables to the created DataSetReader */
retval
=
addSubscribedVariables
(
server
,
readerIdent
,
i
,
init_node_id
);
retval
=
addSubscribedVariables
(
server
,
readerIdent
,
i
,
in
terval
,
in
it_node_id
);
if
(
retval
!=
UA_STATUSCODE_GOOD
)
if
(
retval
!=
UA_STATUSCODE_GOOD
)
return
EXIT_FAILURE
;
return
EXIT_FAILURE
;
}
}
...
@@ -416,7 +418,7 @@ subscribe(UA_Server *server,
...
@@ -416,7 +418,7 @@ subscribe(UA_Server *server,
int
subscribeOnly
(
UA_String
*
transportProfile
,
int
subscribeOnly
(
UA_String
*
transportProfile
,
UA_NetworkAddressUrlDataType
*
networkAddressUrl
,
UA_NetworkAddressUrlDataType
*
networkAddressUrl
,
VariableData
*
variableArray
,
size_t
nbVariable
,
VariableData
*
variableArray
,
size_t
nbVariable
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_Duration
interval
,
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
void
(
*
update
)(
UA_UInt32
id
,
const
UA_DataValue
*
),
void
(
*
update
)(
UA_UInt32
id
,
const
UA_DataValue
*
),
...
@@ -426,8 +428,8 @@ int subscribeOnly(UA_String *transportProfile,
...
@@ -426,8 +428,8 @@ int subscribeOnly(UA_String *transportProfile,
server
=
setServer
(
transportProfile
,
networkAddressUrl
,
id
);
server
=
setServer
(
transportProfile
,
networkAddressUrl
,
id
);
subscribe
(
server
,
variableArray
,
nbVariable
,
id
,
nbReader
,
in
it_node_id
,
subscribe
(
server
,
variableArray
,
nbVariable
,
id
,
nbReader
,
in
terval
,
get_reader_id
,
update
);
init_node_id
,
get_reader_id
,
update
);
retval
=
UA_Server_run
(
server
,
running
);
retval
=
UA_Server_run
(
server
,
running
);
UA_Server_delete
(
server
);
UA_Server_delete
(
server
);
...
@@ -437,7 +439,7 @@ int subscribeOnly(UA_String *transportProfile,
...
@@ -437,7 +439,7 @@ int subscribeOnly(UA_String *transportProfile,
int
runPubsub
(
UA_String
*
transportProfile
,
int
runPubsub
(
UA_String
*
transportProfile
,
UA_NetworkAddressUrlDataType
*
networkAddressUrl
,
UA_NetworkAddressUrlDataType
*
networkAddressUrl
,
VariableData
*
variableArray
,
size_t
nbVariable
,
VariableData
*
variableArray
,
size_t
nbVariable
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_UInt32
id
,
UA_UInt32
nbReader
,
UA_Duration
interval
,
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
void
(
*
init_node_id
)(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
UA_UInt16
(
*
get_reader_id
)(
UA_UInt32
nb
),
VariableData
(
*
get_value
)(
UA_String
identifier
),
VariableData
(
*
get_value
)(
UA_String
identifier
),
...
@@ -460,15 +462,15 @@ int runPubsub(UA_String *transportProfile,
...
@@ -460,15 +462,15 @@ int runPubsub(UA_String *transportProfile,
addDataSetField
(
server
,
variableArray
[
i
]);
addDataSetField
(
server
,
variableArray
[
i
]);
}
}
addWriterGroup
(
server
);
addWriterGroup
(
server
,
interval
);
retval
=
addDataSetWriter
(
server
);
retval
=
addDataSetWriter
(
server
);
if
(
retval
!=
UA_STATUSCODE_GOOD
)
if
(
retval
!=
UA_STATUSCODE_GOOD
)
return
EXIT_FAILURE
;
return
EXIT_FAILURE
;
/* Subscribing */
/* Subscribing */
subscribe
(
server
,
variableArray
,
nbVariable
,
id
,
nbReader
,
in
it_node_id
,
subscribe
(
server
,
variableArray
,
nbVariable
,
id
,
nbReader
,
in
terval
,
get_reader_id
,
update
);
init_node_id
,
get_reader_id
,
update
);
retval
=
UA_Server_run
(
server
,
running
);
retval
=
UA_Server_run
(
server
,
running
);
UA_Server_delete
(
server
);
UA_Server_delete
(
server
);
...
...
qjs_wrapper.c
View file @
66755185
#include <pthread.h>
#include "dronedge.h"
#include "dronedge.h"
static
JSClassID
js
_drone_class_i
d
;
static
JSClassID
js
DroneClassI
d
;
static
UA_Boolean
pubsub
_r
unning
=
true
;
static
UA_Boolean
pubsub
R
unning
=
true
;
static
UA_UInt32
nbDrone
;
static
UA_UInt32
nbDrone
;
static
JSValueConst
*
drone_object_id_list
;
static
JSValueConst
*
droneObjectIdList
;
static
MessageQueue
messageQueue
=
{
.
head
=
NULL
,
.
tail
=
NULL
,
};
UA_String
currentMessage
;
static
UA_UInt32
lastCheckpoint
=
0
;
pthread_mutex_t
mutex
;
pthread_cond_t
threadCond
;
static
void
js_drone_finalizer
(
JSRuntime
*
rt
,
JSValue
val
)
static
void
js_drone_finalizer
(
JSRuntime
*
rt
,
JSValue
val
)
{
{
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
val
,
js
_drone_class_i
d
);
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
val
,
js
DroneClassI
d
);
js_free_rt
(
rt
,
s
);
js_free_rt
(
rt
,
s
);
}
}
static
JSValue
js_drone_ctor
(
JSContext
*
ctx
,
JSValueConst
new
_t
arget
,
static
JSValue
js_drone_ctor
(
JSContext
*
ctx
,
JSValueConst
new
T
arget
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
JSDroneData
*
s
;
JSDroneData
*
s
;
...
@@ -30,10 +37,10 @@ static JSValue js_drone_ctor(JSContext *ctx, JSValueConst new_target,
...
@@ -30,10 +37,10 @@ static JSValue js_drone_ctor(JSContext *ctx, JSValueConst new_target,
goto
fail
;
goto
fail
;
s
->
id
=
(
uint16_t
)
uint32
;
s
->
id
=
(
uint16_t
)
uint32
;
proto
=
JS_GetPropertyStr
(
ctx
,
new
_t
arget
,
"prototype"
);
proto
=
JS_GetPropertyStr
(
ctx
,
new
T
arget
,
"prototype"
);
if
(
JS_IsException
(
proto
))
if
(
JS_IsException
(
proto
))
goto
fail
;
goto
fail
;
obj
=
JS_NewObjectProtoClass
(
ctx
,
proto
,
js
_drone_class_i
d
);
obj
=
JS_NewObjectProtoClass
(
ctx
,
proto
,
js
DroneClassI
d
);
JS_FreeValue
(
ctx
,
proto
);
JS_FreeValue
(
ctx
,
proto
);
if
(
JS_IsException
(
obj
))
if
(
JS_IsException
(
obj
))
goto
fail
;
goto
fail
;
...
@@ -45,22 +52,23 @@ static JSValue js_drone_ctor(JSContext *ctx, JSValueConst new_target,
...
@@ -45,22 +52,23 @@ static JSValue js_drone_ctor(JSContext *ctx, JSValueConst new_target,
return
JS_EXCEPTION
;
return
JS_EXCEPTION
;
}
}
static
JSValue
js_drone_init
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_drone_init
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
int
nb
;
int
nb
;
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque2
(
ctx
,
this
_val
,
js_drone_class_i
d
);
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque2
(
ctx
,
this
Val
,
jsDroneClassI
d
);
if
(
!
s
)
if
(
!
s
)
return
JS_EXCEPTION
;
return
JS_EXCEPTION
;
if
(
JS_ToInt32
(
ctx
,
&
nb
,
argv
[
0
]))
if
(
JS_ToInt32
(
ctx
,
&
nb
,
argv
[
0
]))
return
JS_EXCEPTION
;
return
JS_EXCEPTION
;
drone
_object_id_list
[
nb
]
=
this_v
al
;
drone
ObjectIdList
[
nb
]
=
thisV
al
;
return
JS_UNDEFINED
;
return
JS_UNDEFINED
;
}
}
static
JSValue
js_drone_get
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
int
magic
)
static
JSValue
js_drone_get
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
magic
)
{
{
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque2
(
ctx
,
this_val
,
js_drone_class_id
);
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque2
(
ctx
,
thisVal
,
jsDroneClassId
);
JSValue
res
;
if
(
!
s
)
if
(
!
s
)
return
JS_EXCEPTION
;
return
JS_EXCEPTION
;
switch
(
magic
)
{
switch
(
magic
)
{
...
@@ -75,28 +83,78 @@ static JSValue js_drone_get(JSContext *ctx, JSValueConst this_val, int magic)
...
@@ -75,28 +83,78 @@ static JSValue js_drone_get(JSContext *ctx, JSValueConst this_val, int magic)
case
4
:
case
4
:
return
JS_NewFloat64
(
ctx
,
s
->
altitudeRel
);
return
JS_NewFloat64
(
ctx
,
s
->
altitudeRel
);
case
5
:
case
5
:
return
JS_NewUint32
(
ctx
,
s
->
lastCheckpoint
);
pthread_mutex_lock
(
&
mutex
);
res
=
JS_NewString
(
ctx
,
s
->
message
);
strcpy
(
s
->
message
,
""
);
pthread_cond_signal
(
&
threadCond
);
pthread_mutex_unlock
(
&
mutex
);
return
res
;
default:
default:
return
JS_EXCEPTION
;
return
JS_EXCEPTION
;
}
}
}
}
static
JSValue
js_drone_set_
checkpoint
(
JSContext
*
ctx
,
JSValueConst
this_v
al
,
static
JSValue
js_drone_set_
message
(
JSContext
*
ctx
,
JSValueConst
thisV
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
uint32_t
uint32
;
struct
messageNode
*
newNode
;
if
(
JS_ToUint32
(
ctx
,
&
uint32
,
argv
[
0
]))
const
char
*
message
;
message
=
JS_ToCString
(
ctx
,
argv
[
0
]);
if
(
strlen
(
message
)
>
MAX_MESSAGE_SIZE
)
{
UA_LOG_ERROR
(
UA_Log_Stdout
,
UA_LOGCATEGORY_SERVER
,
"Message too long"
);
return
JS_EXCEPTION
;
return
JS_EXCEPTION
;
lastCheckpoint
=
(
uint16_t
)
uint32
;
}
newNode
=
(
struct
messageNode
*
)
malloc
(
sizeof
(
struct
messageNode
));
newNode
->
message
=
strdup
(
message
);
newNode
->
next
=
NULL
;
if
(
messageQueue
.
tail
==
NULL
)
{
messageQueue
.
head
=
messageQueue
.
tail
=
newNode
;
}
else
{
messageQueue
.
tail
->
next
=
newNode
;
messageQueue
.
tail
=
newNode
;
}
JS_FreeCString
(
ctx
,
message
);
return
JS_UNDEFINED
;
return
JS_UNDEFINED
;
}
}
UA_UInt32
getLastCheckpoint
(
void
)
static
void
delete_message_node
(
struct
messageNode
*
node
)
{
free
(
node
->
message
);
free
(
node
);
}
static
UA_Boolean
UA_String_isEmpty
(
const
UA_String
*
s
)
{
return
(
s
->
length
==
0
||
s
->
data
==
NULL
);
}
static
void
clear_message
(
UA_String
message
)
{
if
(
!
UA_String_isEmpty
(
&
message
))
UA_String_clear
(
&
message
);
}
UA_String
get_message
(
void
)
{
{
return
lastCheckpoint
;
struct
messageNode
*
current
;
current
=
messageQueue
.
head
;
if
(
current
==
NULL
)
{
if
(
!
UA_String_isEmpty
(
&
currentMessage
))
{
UA_String_clear
(
&
currentMessage
);
currentMessage
=
UA_STRING
(
""
);
}
}
else
{
clear_message
(
currentMessage
);
currentMessage
=
UA_STRING_ALLOC
(
current
->
message
);
messageQueue
.
head
=
current
->
next
==
NULL
?
(
messageQueue
.
tail
=
NULL
)
:
current
->
next
;
delete_message_node
(
current
);
}
return
currentMessage
;
}
}
static
JSClassDef
js
_drone_c
lass
=
{
static
JSClassDef
js
DroneC
lass
=
{
"Drone"
,
"Drone"
,
.
finalizer
=
js_drone_finalizer
,
.
finalizer
=
js_drone_finalizer
,
};
};
...
@@ -107,20 +165,15 @@ static const JSCFunctionListEntry js_drone_proto_funcs[] = {
...
@@ -107,20 +165,15 @@ static const JSCFunctionListEntry js_drone_proto_funcs[] = {
JS_CGETSET_MAGIC_DEF
(
"longitude"
,
js_drone_get
,
NULL
,
2
),
JS_CGETSET_MAGIC_DEF
(
"longitude"
,
js_drone_get
,
NULL
,
2
),
JS_CGETSET_MAGIC_DEF
(
"altitudeAbs"
,
js_drone_get
,
NULL
,
3
),
JS_CGETSET_MAGIC_DEF
(
"altitudeAbs"
,
js_drone_get
,
NULL
,
3
),
JS_CGETSET_MAGIC_DEF
(
"altitudeRel"
,
js_drone_get
,
NULL
,
4
),
JS_CGETSET_MAGIC_DEF
(
"altitudeRel"
,
js_drone_get
,
NULL
,
4
),
JS_CGETSET_MAGIC_DEF
(
"
lastCheckpoint
"
,
js_drone_get
,
NULL
,
5
),
JS_CGETSET_MAGIC_DEF
(
"
message
"
,
js_drone_get
,
NULL
,
5
),
JS_CFUNC_DEF
(
"init"
,
1
,
js_drone_init
),
JS_CFUNC_DEF
(
"init"
,
1
,
js_drone_init
),
};
};
UA_UInt16
get_drone_id
(
UA_UInt32
nb
)
{
UA_UInt16
get_drone_id
(
UA_UInt32
nb
)
{
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
drone
_object_id_list
[
nb
],
js_drone_class_i
d
);
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
drone
ObjectIdList
[
nb
],
jsDroneClassI
d
);
return
s
->
id
;
return
s
->
id
;
}
}
void
stop_pubsub
(
void
)
{
pubsub_running
=
false
;
free
(
drone_object_id_list
);
}
VariableData
pubsub_get_value
(
UA_String
identifier
)
{
VariableData
pubsub_get_value
(
UA_String
identifier
)
{
VariableData
var_details
;
VariableData
var_details
;
UA_String
name
;
UA_String
name
;
...
@@ -143,6 +196,9 @@ VariableData pubsub_get_value(UA_String identifier) {
...
@@ -143,6 +196,9 @@ VariableData pubsub_get_value(UA_String identifier) {
case
UA_TYPES_DATETIME
:
case
UA_TYPES_DATETIME
:
*
(
UA_DateTime
*
)
var_details
.
value
=
droneVariableArray
[
i
].
getter
.
getTimestamp
();
*
(
UA_DateTime
*
)
var_details
.
value
=
droneVariableArray
[
i
].
getter
.
getTimestamp
();
break
;
break
;
case
UA_TYPES_STRING
:
*
(
UA_String
*
)
var_details
.
value
=
droneVariableArray
[
i
].
getter
.
getString
();
break
;
default:
default:
UA_LOG_ERROR
(
UA_Log_Stdout
,
UA_LOGCATEGORY_SERVER
,
"UA_TYPE not handled"
);
UA_LOG_ERROR
(
UA_Log_Stdout
,
UA_LOGCATEGORY_SERVER
,
"UA_TYPE not handled"
);
break
;
break
;
...
@@ -155,7 +211,7 @@ VariableData pubsub_get_value(UA_String identifier) {
...
@@ -155,7 +211,7 @@ VariableData pubsub_get_value(UA_String identifier) {
}
}
void
init_node_id
(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
)
{
void
init_node_id
(
UA_UInt32
id
,
UA_UInt32
nb
,
UA_UInt32
magic
)
{
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
drone
_object_id_list
[
nb
],
js_drone_class_i
d
);
JSDroneData
*
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
drone
ObjectIdList
[
nb
],
jsDroneClassI
d
);
switch
(
magic
)
{
switch
(
magic
)
{
case
0
:
case
0
:
s
->
latitudeId
=
id
;
s
->
latitudeId
=
id
;
...
@@ -170,7 +226,7 @@ void init_node_id(UA_UInt32 id, UA_UInt32 nb, UA_UInt32 magic) {
...
@@ -170,7 +226,7 @@ void init_node_id(UA_UInt32 id, UA_UInt32 nb, UA_UInt32 magic) {
s
->
altitudeRelId
=
id
;
s
->
altitudeRelId
=
id
;
break
;
break
;
case
4
:
case
4
:
s
->
lastCheckpoint
Id
=
id
;
s
->
message
Id
=
id
;
break
;
break
;
default:
default:
break
;
break
;
...
@@ -180,8 +236,9 @@ void init_node_id(UA_UInt32 id, UA_UInt32 nb, UA_UInt32 magic) {
...
@@ -180,8 +236,9 @@ void init_node_id(UA_UInt32 id, UA_UInt32 nb, UA_UInt32 magic) {
void
pubsub_update_coordinates
(
UA_UInt32
id
,
const
UA_DataValue
*
var
)
void
pubsub_update_coordinates
(
UA_UInt32
id
,
const
UA_DataValue
*
var
)
{
{
JSDroneData
*
s
;
JSDroneData
*
s
;
UA_String
uaStr
;;
for
(
UA_UInt32
i
=
0
;
i
<
nbDrone
;
i
++
)
{
for
(
UA_UInt32
i
=
0
;
i
<
nbDrone
;
i
++
)
{
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
drone
_object_id_list
[
i
],
js_drone_class_i
d
);
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
drone
ObjectIdList
[
i
],
jsDroneClassI
d
);
if
(
s
->
latitudeId
==
id
)
{
if
(
s
->
latitudeId
==
id
)
{
s
->
latitude
=
*
(
UA_Double
*
)
var
->
value
.
data
;
s
->
latitude
=
*
(
UA_Double
*
)
var
->
value
.
data
;
return
;
return
;
...
@@ -194,8 +251,14 @@ void pubsub_update_coordinates(UA_UInt32 id, const UA_DataValue *var)
...
@@ -194,8 +251,14 @@ void pubsub_update_coordinates(UA_UInt32 id, const UA_DataValue *var)
}
else
if
(
s
->
altitudeRelId
==
id
)
{
}
else
if
(
s
->
altitudeRelId
==
id
)
{
s
->
altitudeRel
=
*
(
UA_Float
*
)
var
->
value
.
data
;
s
->
altitudeRel
=
*
(
UA_Float
*
)
var
->
value
.
data
;
return
;
return
;
}
else
if
(
s
->
lastCheckpointId
==
id
)
{
}
else
if
(
s
->
messageId
==
id
)
{
s
->
lastCheckpoint
=
*
(
UA_UInt32
*
)
var
->
value
.
data
;
uaStr
=
*
(
UA_String
*
)
var
->
value
.
data
;
pthread_mutex_lock
(
&
mutex
);
while
(
strlen
(
s
->
message
)
!=
0
)
pthread_cond_wait
(
&
threadCond
,
&
mutex
);
memcpy
(
s
->
message
,
uaStr
.
data
,
uaStr
.
length
);
s
->
message
[
uaStr
.
length
]
=
'\0'
;
pthread_mutex_unlock
(
&
mutex
);
return
;
return
;
}
}
}
}
...
@@ -205,8 +268,9 @@ void pubsub_update_coordinates(UA_UInt32 id, const UA_DataValue *var)
...
@@ -205,8 +268,9 @@ void pubsub_update_coordinates(UA_UInt32 id, const UA_DataValue *var)
void
pubsub_print_coordinates
(
UA_UInt32
id
,
const
UA_DataValue
*
var
)
void
pubsub_print_coordinates
(
UA_UInt32
id
,
const
UA_DataValue
*
var
)
{
{
JSDroneData
*
s
;
JSDroneData
*
s
;
UA_String
uaStr
;
for
(
UA_UInt32
i
=
0
;
i
<
nbDrone
;
i
++
)
{
for
(
UA_UInt32
i
=
0
;
i
<
nbDrone
;
i
++
)
{
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
drone
_object_id_list
[
i
],
js_drone_class_i
d
);
s
=
(
JSDroneData
*
)
JS_GetOpaque
(
drone
ObjectIdList
[
i
],
jsDroneClassI
d
);
if
(
s
->
latitudeId
==
id
)
{
if
(
s
->
latitudeId
==
id
)
{
s
->
latitude
=
*
(
UA_Double
*
)
var
->
value
.
data
;
s
->
latitude
=
*
(
UA_Double
*
)
var
->
value
.
data
;
UA_LOG_INFO
(
UA_Log_Stdout
,
UA_LOGCATEGORY_CLIENT
,
"Received latitude of drone %d: %f°"
,
s
->
id
,
s
->
latitude
);
UA_LOG_INFO
(
UA_Log_Stdout
,
UA_LOGCATEGORY_CLIENT
,
"Received latitude of drone %d: %f°"
,
s
->
id
,
s
->
latitude
);
...
@@ -223,9 +287,11 @@ void pubsub_print_coordinates(UA_UInt32 id, const UA_DataValue *var)
...
@@ -223,9 +287,11 @@ void pubsub_print_coordinates(UA_UInt32 id, const UA_DataValue *var)
s
->
altitudeRel
=
*
(
UA_Float
*
)
var
->
value
.
data
;
s
->
altitudeRel
=
*
(
UA_Float
*
)
var
->
value
.
data
;
UA_LOG_INFO
(
UA_Log_Stdout
,
UA_LOGCATEGORY_CLIENT
,
"Received relative altitude of drone %d: %fm"
,
s
->
id
,
s
->
altitudeRel
);
UA_LOG_INFO
(
UA_Log_Stdout
,
UA_LOGCATEGORY_CLIENT
,
"Received relative altitude of drone %d: %fm"
,
s
->
id
,
s
->
altitudeRel
);
return
;
return
;
}
else
if
(
s
->
lastCheckpointId
==
id
)
{
}
else
if
(
s
->
messageId
==
id
)
{
s
->
lastCheckpoint
=
*
(
UA_UInt32
*
)
var
->
value
.
data
;
uaStr
=
*
(
UA_String
*
)
var
->
value
.
data
;
UA_LOG_INFO
(
UA_Log_Stdout
,
UA_LOGCATEGORY_CLIENT
,
"Received checkpoint of drone %d: %dm"
,
s
->
id
,
s
->
lastCheckpoint
);
memcpy
(
s
->
message
,
uaStr
.
data
,
uaStr
.
length
);
s
->
message
[
uaStr
.
length
]
=
'\0'
;
UA_LOG_INFO
(
UA_Log_Stdout
,
UA_LOGCATEGORY_CLIENT
,
"Received message of drone %d: %s"
,
s
->
id
,
s
->
message
);
return
;
return
;
}
}
}
}
...
@@ -237,73 +303,88 @@ void pubsub_print_coordinates(UA_UInt32 id, const UA_DataValue *var)
...
@@ -237,73 +303,88 @@ void pubsub_print_coordinates(UA_UInt32 id, const UA_DataValue *var)
* arg 1 (string): port used for multicast communication
* arg 1 (string): port used for multicast communication
* arg 2 (string): network interface used for multicast communication
* arg 2 (string): network interface used for multicast communication
* arg 3 (int): ID of the drone
* arg 3 (int): ID of the drone
* arg 4 (bool): true if there will be data to publish
* arg 4 (double): publication/subscription interval in ms
* arg 5 (bool): true if there will be data to publish
*/
*/
static
JSValue
js_run_pubsub
(
JSContext
*
ctx
,
JSValueConst
this_val
,
static
JSValue
js_run_pubsub
(
JSContext
*
ctx
,
JSValueConst
this_val
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
const
char
*
ipv6
;
const
char
*
ipv6
;
const
char
*
port
;
const
char
*
port
;
const
char
*
net
_i
face
;
const
char
*
net
I
face
;
char
*
not
_const_net_i
face
;
char
*
not
ConstNetI
face
;
char
urlBuffer
[
44
];
char
urlBuffer
[
44
];
UA_UInt32
id
;
UA_UInt32
id
;
UA_Duration
interval
;
int
res
;
int
res
;
ipv6
=
JS_ToCString
(
ctx
,
argv
[
0
]);
ipv6
=
JS_ToCString
(
ctx
,
argv
[
0
]);
port
=
JS_ToCString
(
ctx
,
argv
[
1
]);
port
=
JS_ToCString
(
ctx
,
argv
[
1
]);
net
_i
face
=
JS_ToCString
(
ctx
,
argv
[
2
]);
net
I
face
=
JS_ToCString
(
ctx
,
argv
[
2
]);
UA_snprintf
(
urlBuffer
,
sizeof
(
urlBuffer
),
"opc.udp://[%s]:%s/"
,
ipv6
,
port
);
UA_snprintf
(
urlBuffer
,
sizeof
(
urlBuffer
),
"opc.udp://[%s]:%s/"
,
ipv6
,
port
);
UA_String
transportProfile
=
UA_String
transportProfile
=
UA_STRING
(
"http://opcfoundation.org/UA-Profile/Transport/pubsub-udp-uadp"
);
UA_STRING
(
"http://opcfoundation.org/UA-Profile/Transport/pubsub-udp-uadp"
);
UA_NetworkAddressUrlDataType
networkAddressUrl
;
UA_NetworkAddressUrlDataType
networkAddressUrl
;
not
_const_net_iface
=
strdup
(
net_i
face
);
not
ConstNetIface
=
strdup
(
netI
face
);
networkAddressUrl
.
networkInterface
=
UA_STRING
(
not
_const_net_i
face
);
networkAddressUrl
.
networkInterface
=
UA_STRING
(
not
ConstNetI
face
);
networkAddressUrl
.
url
=
UA_STRING
(
urlBuffer
);
networkAddressUrl
.
url
=
UA_STRING
(
urlBuffer
);
if
(
JS_ToUint32
(
ctx
,
&
id
,
argv
[
3
]))
if
(
JS_ToUint32
(
ctx
,
&
id
,
argv
[
3
]))
return
JS_EXCEPTION
;
return
JS_EXCEPTION
;
if
(
JS_ToBool
(
ctx
,
argv
[
4
]))
{
if
(
JS_ToFloat64
(
ctx
,
&
interval
,
argv
[
4
]))
return
JS_EXCEPTION
;
if
(
JS_ToBool
(
ctx
,
argv
[
5
]))
{
res
=
runPubsub
(
&
transportProfile
,
&
networkAddressUrl
,
res
=
runPubsub
(
&
transportProfile
,
&
networkAddressUrl
,
droneVariableArray
,
countof
(
droneVariableArray
),
id
,
droneVariableArray
,
countof
(
droneVariableArray
),
id
,
nbDrone
,
init_node_id
,
get_drone_id
,
pubsub_get_value
,
nbDrone
,
interval
,
init_node_id
,
get_drone_id
,
pubsub_update_coordinates
,
&
pubsub_running
);
pubsub_get_value
,
pubsub_update_coordinates
,
&
pubsubRunning
);
}
else
{
}
else
{
res
=
subscribeOnly
(
&
transportProfile
,
&
networkAddressUrl
,
res
=
subscribeOnly
(
&
transportProfile
,
&
networkAddressUrl
,
droneVariableArray
,
countof
(
droneVariableArray
),
id
,
droneVariableArray
,
countof
(
droneVariableArray
),
id
,
nbDrone
,
init_node_id
,
get_drone_id
,
nbDrone
,
in
terval
,
in
it_node_id
,
get_drone_id
,
pubsub_print_coordinates
,
&
pubsub
_r
unning
);
pubsub_print_coordinates
,
&
pubsub
R
unning
);
}
}
JS_FreeCString
(
ctx
,
ipv6
);
JS_FreeCString
(
ctx
,
ipv6
);
JS_FreeCString
(
ctx
,
port
);
JS_FreeCString
(
ctx
,
port
);
free
(
not
_const_net_i
face
);
free
(
not
ConstNetI
face
);
JS_FreeCString
(
ctx
,
net
_i
face
);
JS_FreeCString
(
ctx
,
net
I
face
);
return
JS_NewInt32
(
ctx
,
res
);
return
JS_NewInt32
(
ctx
,
res
);
}
}
static
JSValue
js_init_pubsub
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_init_pubsub
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
if
(
JS_ToUint32
(
ctx
,
&
nbDrone
,
argv
[
0
]))
if
(
JS_ToUint32
(
ctx
,
&
nbDrone
,
argv
[
0
]))
return
JS_EXCEPTION
;
return
JS_EXCEPTION
;
drone
_object_id_l
ist
=
(
JSValue
*
)
malloc
(
nbDrone
*
sizeof
(
JSValueConst
));
drone
ObjectIdL
ist
=
(
JSValue
*
)
malloc
(
nbDrone
*
sizeof
(
JSValueConst
));
return
JS_NewInt32
(
ctx
,
0
);
return
JS_NewInt32
(
ctx
,
0
);
}
}
static
JSValue
js_stop_pubsub
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_stop_pubsub
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
pubsub_running
=
false
;
struct
messageNode
*
current
;
free
(
drone_object_id_list
);
pubsubRunning
=
false
;
free
(
droneObjectIdList
);
while
(
messageQueue
.
head
!=
NULL
)
{
current
=
messageQueue
.
head
;
messageQueue
.
head
=
current
->
next
;
delete_message_node
(
current
);
}
clear_message
(
currentMessage
);
return
JS_NewInt32
(
ctx
,
0
);
return
JS_NewInt32
(
ctx
,
0
);
}
}
static
JSValue
js_mavsdk_start
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_start
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
const
char
*
url
;
const
char
*
url
;
...
@@ -323,13 +404,13 @@ static JSValue js_mavsdk_start(JSContext *ctx, JSValueConst this_val,
...
@@ -323,13 +404,13 @@ static JSValue js_mavsdk_start(JSContext *ctx, JSValueConst this_val,
return
JS_NewInt32
(
ctx
,
res
);
return
JS_NewInt32
(
ctx
,
res
);
}
}
static
JSValue
js_mavsdk_stop
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_stop
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewInt32
(
ctx
,
mavsdk_stop
());
return
JS_NewInt32
(
ctx
,
mavsdk_stop
());
}
}
static
JSValue
js_mavsdk_reboot
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_reboot
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewInt32
(
ctx
,
mavsdk_reboot
());
return
JS_NewInt32
(
ctx
,
mavsdk_reboot
());
...
@@ -360,7 +441,7 @@ static JSValue js_mavsdk_arm(JSContext *ctx, JSValueConst this_val,
...
@@ -360,7 +441,7 @@ static JSValue js_mavsdk_arm(JSContext *ctx, JSValueConst this_val,
}
}
static
JSValue
js_mavsdk_setTargetCoordinates
(
JSContext
*
ctx
,
static
JSValue
js_mavsdk_setTargetCoordinates
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
double
la_arg_double
;
double
la_arg_double
;
...
@@ -386,7 +467,7 @@ static JSValue js_mavsdk_setManualControlInput(JSContext *ctx,
...
@@ -386,7 +467,7 @@ static JSValue js_mavsdk_setManualControlInput(JSContext *ctx,
return
JS_NewInt32
(
ctx
,
mavsdk_setManualControlInput
());
return
JS_NewInt32
(
ctx
,
mavsdk_setManualControlInput
());
}
}
static
JSValue
js_mavsdk_setAltitude
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_setAltitude
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
double
altitude
;
double
altitude
;
...
@@ -397,7 +478,7 @@ static JSValue js_mavsdk_setAltitude(JSContext *ctx, JSValueConst this_val,
...
@@ -397,7 +478,7 @@ static JSValue js_mavsdk_setAltitude(JSContext *ctx, JSValueConst this_val,
return
JS_NewInt32
(
ctx
,
mavsdk_setAltitude
((
float
)
altitude
));
return
JS_NewInt32
(
ctx
,
mavsdk_setAltitude
((
float
)
altitude
));
}
}
static
JSValue
js_mavsdk_setAirspeed
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_setAirspeed
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
double
altitude
;
double
altitude
;
...
@@ -408,65 +489,65 @@ static JSValue js_mavsdk_setAirspeed(JSContext *ctx, JSValueConst this_val,
...
@@ -408,65 +489,65 @@ static JSValue js_mavsdk_setAirspeed(JSContext *ctx, JSValueConst this_val,
return
JS_NewInt32
(
ctx
,
mavsdk_setAirspeed
((
float
)
altitude
));
return
JS_NewInt32
(
ctx
,
mavsdk_setAirspeed
((
float
)
altitude
));
}
}
static
JSValue
js_mavsdk_getYaw
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_getYaw
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewFloat64
(
ctx
,
mavsdk_getYaw
());
return
JS_NewFloat64
(
ctx
,
mavsdk_getYaw
());
}
}
static
JSValue
js_mavsdk_getInitialLatitude
(
JSContext
*
ctx
,
static
JSValue
js_mavsdk_getInitialLatitude
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewFloat64
(
ctx
,
mavsdk_getInitialLatitude
());
return
JS_NewFloat64
(
ctx
,
mavsdk_getInitialLatitude
());
}
}
static
JSValue
js_mavsdk_getLatitude
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_getLatitude
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewFloat64
(
ctx
,
mavsdk_getLatitude
());
return
JS_NewFloat64
(
ctx
,
mavsdk_getLatitude
());
}
}
static
JSValue
js_mavsdk_getInitialLongitude
(
JSContext
*
ctx
,
static
JSValue
js_mavsdk_getInitialLongitude
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewFloat64
(
ctx
,
mavsdk_getInitialLongitude
());
return
JS_NewFloat64
(
ctx
,
mavsdk_getInitialLongitude
());
}
}
static
JSValue
js_mavsdk_getLongitude
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_getLongitude
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewFloat64
(
ctx
,
mavsdk_getLongitude
());
return
JS_NewFloat64
(
ctx
,
mavsdk_getLongitude
());
}
}
static
JSValue
js_mavsdk_getTakeOffAltitude
(
JSContext
*
ctx
,
static
JSValue
js_mavsdk_getTakeOffAltitude
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewFloat64
(
ctx
,
mavsdk_getTakeOffAltitude
());
return
JS_NewFloat64
(
ctx
,
mavsdk_getTakeOffAltitude
());
}
}
static
JSValue
js_mavsdk_getInitialAltitude
(
JSContext
*
ctx
,
static
JSValue
js_mavsdk_getInitialAltitude
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewFloat64
(
ctx
,
mavsdk_getInitialAltitude
());
return
JS_NewFloat64
(
ctx
,
mavsdk_getInitialAltitude
());
}
}
static
JSValue
js_mavsdk_getAltitude
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_getAltitude
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewFloat64
(
ctx
,
mavsdk_getAltitude
());
return
JS_NewFloat64
(
ctx
,
mavsdk_getAltitude
());
}
}
static
JSValue
js_mavsdk_getAltitudeRel
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_getAltitudeRel
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewFloat64
(
ctx
,
mavsdk_getAltitudeRel
());
return
JS_NewFloat64
(
ctx
,
mavsdk_getAltitudeRel
());
}
}
static
JSValue
js_mavsdk_loiter
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_loiter
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
double
radius
=
100
;
double
radius
=
100
;
...
@@ -484,19 +565,19 @@ static JSValue js_mavsdk_triggerParachute(JSContext *ctx, JSValueConst this_val,
...
@@ -484,19 +565,19 @@ static JSValue js_mavsdk_triggerParachute(JSContext *ctx, JSValueConst this_val,
return
JS_NewInt32
(
ctx
,
mavsdk_triggerParachute
());
return
JS_NewInt32
(
ctx
,
mavsdk_triggerParachute
());
}
}
static
JSValue
js_mavsdk_takeOff
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_takeOff
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewInt32
(
ctx
,
mavsdk_takeOff
());
return
JS_NewInt32
(
ctx
,
mavsdk_takeOff
());
}
}
static
JSValue
js_mavsdk_takeOffAndWait
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_takeOffAndWait
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewInt32
(
ctx
,
mavsdk_takeOffAndWait
());
return
JS_NewInt32
(
ctx
,
mavsdk_takeOffAndWait
());
}
}
static
JSValue
js_mavsdk_land
(
JSContext
*
ctx
,
JSValueConst
this
_v
al
,
static
JSValue
js_mavsdk_land
(
JSContext
*
ctx
,
JSValueConst
this
V
al
,
int
argc
,
JSValueConst
*
argv
)
int
argc
,
JSValueConst
*
argv
)
{
{
return
JS_NewInt32
(
ctx
,
mavsdk_land
());
return
JS_NewInt32
(
ctx
,
mavsdk_land
());
...
@@ -529,28 +610,28 @@ static const JSCFunctionListEntry js_mavsdk_funcs[] = {
...
@@ -529,28 +610,28 @@ static const JSCFunctionListEntry js_mavsdk_funcs[] = {
JS_CFUNC_DEF
(
"takeOffAndWait"
,
0
,
js_mavsdk_takeOffAndWait
),
JS_CFUNC_DEF
(
"takeOffAndWait"
,
0
,
js_mavsdk_takeOffAndWait
),
JS_CFUNC_DEF
(
"land"
,
0
,
js_mavsdk_land
),
JS_CFUNC_DEF
(
"land"
,
0
,
js_mavsdk_land
),
JS_CFUNC_DEF
(
"initPubsub"
,
1
,
js_init_pubsub
),
JS_CFUNC_DEF
(
"initPubsub"
,
1
,
js_init_pubsub
),
JS_CFUNC_DEF
(
"runPubsub"
,
5
,
js_run_pubsub
),
JS_CFUNC_DEF
(
"runPubsub"
,
6
,
js_run_pubsub
),
JS_CFUNC_DEF
(
"set
Checkpoint"
,
1
,
js_drone_set_checkpoint
),
JS_CFUNC_DEF
(
"set
Message"
,
1
,
js_drone_set_message
),
JS_CFUNC_DEF
(
"stopPubsub"
,
0
,
js_stop_pubsub
),
JS_CFUNC_DEF
(
"stopPubsub"
,
0
,
js_stop_pubsub
),
};
};
static
int
js_mavsdk_init
(
JSContext
*
ctx
,
JSModuleDef
*
m
)
static
int
js_mavsdk_init
(
JSContext
*
ctx
,
JSModuleDef
*
m
)
{
{
JSValue
drone
_proto
,
drone_c
lass
;
JSValue
drone
Proto
,
droneC
lass
;
JS_NewClassID
(
&
js
_drone_class_i
d
);
JS_NewClassID
(
&
js
DroneClassI
d
);
JS_NewClass
(
JS_GetRuntime
(
ctx
),
js
_drone_class_id
,
&
js_drone_c
lass
);
JS_NewClass
(
JS_GetRuntime
(
ctx
),
js
DroneClassId
,
&
jsDroneC
lass
);
drone
_p
roto
=
JS_NewObject
(
ctx
);
drone
P
roto
=
JS_NewObject
(
ctx
);
JS_SetPropertyFunctionList
(
ctx
,
drone
_p
roto
,
js_drone_proto_funcs
,
JS_SetPropertyFunctionList
(
ctx
,
drone
P
roto
,
js_drone_proto_funcs
,
countof
(
js_drone_proto_funcs
));
countof
(
js_drone_proto_funcs
));
drone
_c
lass
=
JS_NewCFunction2
(
ctx
,
js_drone_ctor
,
"Drone"
,
1
,
drone
C
lass
=
JS_NewCFunction2
(
ctx
,
js_drone_ctor
,
"Drone"
,
1
,
JS_CFUNC_constructor
,
0
);
JS_CFUNC_constructor
,
0
);
JS_SetConstructor
(
ctx
,
drone
_class
,
drone_p
roto
);
JS_SetConstructor
(
ctx
,
drone
Class
,
droneP
roto
);
JS_SetClassProto
(
ctx
,
js
_drone_class_id
,
drone_p
roto
);
JS_SetClassProto
(
ctx
,
js
DroneClassId
,
droneP
roto
);
JS_SetModuleExport
(
ctx
,
m
,
"Drone"
,
drone
_c
lass
);
JS_SetModuleExport
(
ctx
,
m
,
"Drone"
,
drone
C
lass
);
return
JS_SetModuleExportList
(
ctx
,
m
,
js_mavsdk_funcs
,
return
JS_SetModuleExportList
(
ctx
,
m
,
js_mavsdk_funcs
,
countof
(
js_mavsdk_funcs
));
countof
(
js_mavsdk_funcs
));
...
...
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