@@ -82,12 +82,21 @@ sysids[SYSID] = true;
82
82
// global mav mission object for gettting/sending missions to drone
83
83
var MissionObj = undefined ; // we delay instantion till we know SYSID // new MavMission(SYSID,COMPID,mavlink20, mavParserObj , null, logger);
84
84
85
- function send_canned_mission_to_drone ( ) {
85
+ async function send_canned_mission_to_drone ( ) {
86
86
// obj for missions
87
87
if ( MissionObj == undefined ) MissionObj = new MavMission ( SYSID , COMPID , mavlink20 , mavParserObj , null , logger ) ;
88
88
89
- var readfilename = "./gotmission3.js" ;
90
- var miss = require ( readfilename ) ;
89
+ var module = { exports : { } } ; // hack for node compat
90
+ var readfilename = "/gotmission1.js" ; // no leading . or ./ its an absolute url ah-la http://xxxx/gotmission1.js
91
+ // var miss = require(readfilename); Node.js
92
+
93
+ //let modulePath = prompt("Which module to load?");
94
+
95
+
96
+ mod = await import ( readfilename ) ;
97
+
98
+ var miss = window . missionItems ;
99
+
91
100
92
101
console . log ( 'START SEND MISSION to drone:' , readfilename ) ;
93
102
// awaiting in a non-async is like this...
@@ -1148,14 +1157,23 @@ var mspHelper = (function (gui) {
1148
1157
1149
1158
1150
1159
1151
- case mavlink20 . MAVLINK_MSG_ID_MISSION_ITEM_REACHED :
1160
+ case mavlink20 . MAVLINK_MSG_ID_MISSION_ITEM_REACHED : //46
1152
1161
/* ["seq"]
1153
1162
seq: 7
1154
1163
// note that _header.srcSystem give the vehicle sysid that it came from as well
1155
1164
*/
1156
1165
// buzz todo
1157
1166
break ;
1158
1167
1168
+ case mavlink20 . MAVLINK_MSG_ID_MISSION_ITEM_INT : // 73
1169
+ case mavlink20 . MAVLINK_MSG_ID_MISSION_ITEM : //39
1170
+ case mavlink20 . MAVLINK_MSG_ID_MISSION_REQUEST_INT : //51
1171
+ case mavlink20 . MAVLINK_MSG_ID_MISSION_REQUEST : //40
1172
+ case mavlink20 . MAVLINK_MSG_ID_MISSION_ACK : //47
1173
+
1174
+ // buzz todo
1175
+ break ;
1176
+
1159
1177
// add more here
1160
1178
1161
1179
// case mavlink20.MAVLINK_MSG_ID_SENSOR_OFFSETS:
@@ -4124,51 +4142,57 @@ var mspHelper = (function (gui) {
4124
4142
callback ( ) ; // without a response, we'll call the callback anyway
4125
4143
} ;
4126
4144
4127
- self . loadWaypoints = function ( callback ) {
4145
+ self . loadWaypoints = function ( callback ) { //getWaypointsFromFC
4128
4146
MISSION_PLANER . reinit ( ) ;
4129
4147
let waypointId = 1 ;
4130
- //MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, null);
4131
- getFirstWP ( ) ;
4148
+
4149
+ get_mission_from_drone ( ) ;
4150
+ // //MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, null);
4151
+ // getFirstWP();
4132
4152
4133
- function getFirstWP ( ) {
4134
- //MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, null);
4135
- nextWaypoint ( ) ;
4136
- } ;
4153
+ // function getFirstWP() {
4154
+ // //MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, null);
4155
+ // nextWaypoint();
4156
+ // };
4137
4157
4138
- function nextWaypoint ( ) {
4139
- waypointId ++ ;
4140
- if ( waypointId < MISSION_PLANER . getCountBusyPoints ( ) ) {
4141
- // MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, null);
4142
- nextWaypoint ( ) ;
4143
- }
4144
- else {
4145
- //MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, null);
4146
- callback ( ) ; // without a response, we'll call the callback anyway
4147
- }
4148
- } ;
4158
+ // function nextWaypoint() {
4159
+ // waypointId++;
4160
+ // if (waypointId < MISSION_PLANER.getCountBusyPoints()) {
4161
+ // // MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, null);
4162
+ // nextWaypoint();
4163
+ // }
4164
+ // else {
4165
+ // //MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, null);
4166
+ // callback(); // without a response, we'll call the callback anyway
4167
+ // }
4168
+ // };
4149
4169
} ;
4150
-
4151
- self . saveWaypoints = function ( callback ) {
4170
+
4171
+ self . saveWaypoints = function ( callback ) { //sendWaypointsToFC
4152
4172
let waypointId = 1 ;
4173
+
4174
+ send_canned_mission_to_drone ( ) ;
4175
+
4176
+
4153
4177
//MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, null);
4154
- nextWaypoint ( ) ;
4178
+ // nextWaypoint();
4155
4179
4156
- function nextWaypoint ( ) {
4157
- waypointId ++ ;
4158
- if ( waypointId < MISSION_PLANER . get ( ) . length ) {
4159
- //MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, null);
4160
- nextWaypoint ( ) ;
4161
- }
4162
- else {
4163
- //MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, null);
4164
- endMission ( ) ;
4165
- }
4166
- } ;
4180
+ // function nextWaypoint() {
4181
+ // waypointId++;
4182
+ // if (waypointId < MISSION_PLANER.get().length) {
4183
+ // //MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, null);
4184
+ // nextWaypoint();
4185
+ // }
4186
+ // else {
4187
+ // //MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, null);
4188
+ // endMission();
4189
+ // }
4190
+ // };
4167
4191
4168
- function endMission ( ) {
4169
- //MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, null);
4170
- callback ( ) ; // without a response, we'll call the callback anyway
4171
- }
4192
+ // function endMission() {
4193
+ // //MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, null);
4194
+ // callback(); // without a response, we'll call the callback anyway
4195
+ // }
4172
4196
} ;
4173
4197
4174
4198
self . loadSafehomes = function ( callback ) {
0 commit comments