mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 02:57:34 +08:00
mavlink and mission topic: added reading in DO_JUMP mission items
This commit is contained in:
@@ -863,7 +863,10 @@ int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item
|
||||
case MAV_CMD_NAV_TAKEOFF:
|
||||
mission_item->pitch_min = mavlink_mission_item->param2;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_JUMP:
|
||||
mission_item->do_jump_mission_index = mavlink_mission_item->param1;
|
||||
/* TODO: also save param2 (repeat count) */
|
||||
break;
|
||||
default:
|
||||
mission_item->acceptance_radius = mavlink_mission_item->param2;
|
||||
break;
|
||||
@@ -896,6 +899,11 @@ int Mavlink::map_mission_item_to_mavlink_mission_item(const struct mission_item_
|
||||
mavlink_mission_item->param2 = mission_item->pitch_min;
|
||||
break;
|
||||
|
||||
case NAV_CMD_DO_JUMP:
|
||||
mavlink_mission_item->param1 = mission_item->do_jump_mission_index;
|
||||
/* TODO: also save param2 (repeat count) */
|
||||
break;
|
||||
|
||||
default:
|
||||
mavlink_mission_item->param2 = mission_item->acceptance_radius;
|
||||
break;
|
||||
|
||||
@@ -58,7 +58,8 @@ enum NAV_CMD {
|
||||
NAV_CMD_LAND=21,
|
||||
NAV_CMD_TAKEOFF=22,
|
||||
NAV_CMD_ROI=80,
|
||||
NAV_CMD_PATHPLANNING=81
|
||||
NAV_CMD_PATHPLANNING=81,
|
||||
NAV_CMD_DO_JUMP=177
|
||||
};
|
||||
|
||||
enum ORIGIN {
|
||||
@@ -91,6 +92,7 @@ struct mission_item_s {
|
||||
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
|
||||
bool autocontinue; /**< true if next waypoint should follow after this one */
|
||||
enum ORIGIN origin; /**< where the waypoint has been generated */
|
||||
int do_jump_mission_index; /**< the mission index that we want to jump to */
|
||||
};
|
||||
|
||||
struct mission_s
|
||||
|
||||
Reference in New Issue
Block a user