@@ -12815,6 +12815,28 @@ def RTLStoppingDistanceSpeed(self):
1281512815 self .change_mode ('LOITER' )
1281612816 self .do_RTL ()
1281712817
12818+ def MISSION_OPTION_CLEAR_MISSION_AT_BOOT (self ):
12819+ '''check functionality of mission-clear-at-boot option'''
12820+ self .upload_simple_relhome_mission ([
12821+ (mavutil .mavlink .MAV_CMD_NAV_TAKEOFF , 0 , 0 , 20 ),
12822+ (mavutil .mavlink .MAV_CMD_NAV_WAYPOINT , 20 , 0 , 20 ),
12823+ (mavutil .mavlink .MAV_CMD_NAV_RETURN_TO_LAUNCH , 0 , 0 , 0 ),
12824+ ])
12825+ if len (self .download_using_mission_protocol (mavutil .mavlink .MAV_MISSION_TYPE_MISSION )) != 4 :
12826+ raise NotAchievedException ("No mission after upload?!" )
12827+
12828+ self .reboot_sitl ()
12829+ if len (self .download_using_mission_protocol (mavutil .mavlink .MAV_MISSION_TYPE_MISSION )) != 4 :
12830+ raise NotAchievedException ("No mission after reboot?!" )
12831+
12832+ self .set_parameters ({
12833+ "MIS_OPTIONS" : 1 ,
12834+ })
12835+ self .reboot_sitl ()
12836+
12837+ if len (self .download_using_mission_protocol (mavutil .mavlink .MAV_MISSION_TYPE_MISSION )) != 0 :
12838+ raise NotAchievedException ("Mission did not clear after reboot with option set" )
12839+
1281812840 def do_land (self ):
1281912841 self .change_mode ('LAND' )
1282012842 self .wait_disarmed ()
@@ -12900,6 +12922,7 @@ def tests2b(self): # this block currently around 9.5mins here
1290012922 self .ArmSwitchAfterReboot ,
1290112923 self .RPLidarA1 ,
1290212924 self .RPLidarA2 ,
12925+ self .MISSION_OPTION_CLEAR_MISSION_AT_BOOT ,
1290312926 self .SafetySwitch ,
1290412927 self .BrakeZ ,
1290512928 self .MAV_CMD_DO_FLIGHTTERMINATION ,
0 commit comments