@@ -58,7 +58,7 @@ def default_settings():
5858 MPSetting (
5959 "wp_generator" ,
6060 str ,
61- "SimpleWaypoints " ,
61+ "UseLoiterToAlt " ,
6262 choice = ["SimpleWaypoints" , "UseLoiterToAlt" ],
6363 ),
6464 MPSetting ("wp_spacing" , float , 60.0 ),
@@ -1132,30 +1132,30 @@ def _wp_gen_use_loiter_to_alt(self):
11321132 )
11331133 mission_items .append (mission_item )
11341134 wp_num += 1
1135-
1136- # mission item MAV_CMD_NAV_WAYPOINT (16)
1137- p1 = 0.0 # hold
1138- p2 = 0.0 # accept radius
1139- p3 = 0.0 # pass_radius # pass radius - not working?
1140- p4 = 0.0 # end_yaw_deg # yaw at waypoint - not working?
1141- mission_item = mavutil .mavlink .MAVLink_mission_item_message (
1142- target_system = sys_id ,
1143- target_component = cmp_id ,
1144- seq = wp_num ,
1145- frame = mavutil .mavlink .MAV_FRAME_GLOBAL ,
1146- command = mavutil .mavlink .MAV_CMD_NAV_WAYPOINT ,
1147- current = 0 ,
1148- autocontinue = 1 ,
1149- param1 = p1 ,
1150- param2 = p2 ,
1151- param3 = p3 ,
1152- param4 = p4 ,
1153- x = end_lat ,
1154- y = end_lon ,
1155- z = end_alt ,
1156- )
1157- mission_items .append (mission_item )
1158- wp_num += 1
1135+ else :
1136+ # mission item MAV_CMD_NAV_WAYPOINT (16)
1137+ p1 = 0.0 # hold
1138+ p2 = 0.0 # accept radius
1139+ p3 = 0.0 # pass_radius # pass radius - not working?
1140+ p4 = 0.0 # end_yaw_deg # yaw at waypoint - not working?
1141+ mission_item = mavutil .mavlink .MAVLink_mission_item_message (
1142+ target_system = sys_id ,
1143+ target_component = cmp_id ,
1144+ seq = wp_num ,
1145+ frame = mavutil .mavlink .MAV_FRAME_GLOBAL ,
1146+ command = mavutil .mavlink .MAV_CMD_NAV_WAYPOINT ,
1147+ current = 0 ,
1148+ autocontinue = 1 ,
1149+ param1 = p1 ,
1150+ param2 = p2 ,
1151+ param3 = p3 ,
1152+ param4 = p4 ,
1153+ x = end_lat ,
1154+ y = end_lon ,
1155+ z = end_alt ,
1156+ )
1157+ mission_items .append (mission_item )
1158+ wp_num += 1
11591159
11601160 if add_goal_loiter :
11611161 mission_item = self ._wp_gen_goal_loiter (wp_num )
0 commit comments