@@ -284,35 +284,31 @@ def cmd_time(self, args):
284
284
return
285
285
print ("%s (%s)\n " % (time .ctime (tusec * 1.0e-6 ), time .ctime ()))
286
286
287
+ def _cmd_changealt (self , alt , frame ):
288
+ self .master .mav .mission_item_send (self .settings .target_system ,
289
+ self .settings .target_component ,
290
+ 0 ,
291
+ frame ,
292
+ mavutil .mavlink .MAV_CMD_NAV_WAYPOINT ,
293
+ 3 , 1 , 0 , 0 , 0 , 0 ,
294
+ 0 , 0 , alt )
295
+ print ("Sent change altitude command for %.1f meters" % alt )
296
+
287
297
def cmd_changealt (self , args ):
288
298
'''change target altitude'''
289
299
if len (args ) < 1 :
290
300
print ("usage: changealt <relaltitude>" )
291
301
return
292
302
relalt = float (args [0 ])
293
- self .master .mav .mission_item_send (self .settings .target_system ,
294
- self .settings .target_component ,
295
- 0 ,
296
- 3 ,
297
- mavutil .mavlink .MAV_CMD_NAV_WAYPOINT ,
298
- 3 , 1 , 0 , 0 , 0 , 0 ,
299
- 0 , 0 , relalt )
300
- print ("Sent change altitude command for %.1f meters" % relalt )
303
+ self ._cmd_changealt (relalt , mavutil .mavlink .MAV_FRAME_GLOBAL_RELATIVE_ALT )
301
304
302
305
def cmd_changealt_abs (self , args ):
303
306
'''change target altitude'''
304
307
if len (args ) < 1 :
305
308
print ("usage: changealt_abs <absaltitude>" )
306
309
return
307
310
absalt = float (args [0 ])
308
- self .master .mav .mission_item_send (self .settings .target_system ,
309
- self .settings .target_component ,
310
- 0 ,
311
- 0 ,
312
- mavutil .mavlink .MAV_CMD_NAV_WAYPOINT ,
313
- 3 , 1 , 0 , 0 , 0 , 0 ,
314
- 0 , 0 , absalt )
315
- print ("Sent change altitude command for %.1f meters" % absalt )
311
+ self ._cmd_changealt (absalt , mavutil .mavlink .MAV_FRAME_GLOBAL )
316
312
317
313
def cmd_land (self , args ):
318
314
'''auto land commands'''
0 commit comments