mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-30 13:14:06 +08:00
add missing conversion from mission item to mavlink mission item after changes from b7652986d9cc0fe3edc765e3485b696b4b639b03
This commit is contained in:
parent
546964332d
commit
94b68aa1cc
@ -133,6 +133,15 @@ int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *missio
|
||||
mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
|
||||
}
|
||||
|
||||
switch (mission_item->nav_cmd) {
|
||||
case NAV_CMD_TAKEOFF:
|
||||
mavlink_mission_item->param1 = mission_item->pitch_min;
|
||||
break;
|
||||
default:
|
||||
mavlink_mission_item->param1 = mission_item->radius;
|
||||
break;
|
||||
}
|
||||
|
||||
mavlink_mission_item->x = (float)mission_item->lat;
|
||||
mavlink_mission_item->y = (float)mission_item->lon;
|
||||
mavlink_mission_item->z = mission_item->altitude;
|
||||
@ -140,7 +149,6 @@ int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *missio
|
||||
mavlink_mission_item->param4 = mission_item->yaw*M_RAD_TO_DEG_F;
|
||||
mavlink_mission_item->param3 = mission_item->loiter_radius*(float)mission_item->loiter_direction;
|
||||
mavlink_mission_item->command = mission_item->nav_cmd;
|
||||
mavlink_mission_item->param1 = mission_item->radius;
|
||||
mavlink_mission_item->param2 = mission_item->time_inside * 1e3f; /* from seconds to milliseconds */
|
||||
mavlink_mission_item->autocontinue = mission_item->autocontinue;
|
||||
mavlink_mission_item->seq = mission_item->index;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user