Mission: add decoding of NAV_SPLINE command
This commit is contained in:
parent
e7be622eef
commit
ac339a0289
@ -447,6 +447,11 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
|
|||||||
cmd.p1 = packet.param1; // minimum pitch (plane only)
|
cmd.p1 = packet.param1; // minimum pitch (plane only)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_NAV_SPLINE_WAYPOINT: // MAV ID: 82
|
||||||
|
copy_location = true;
|
||||||
|
cmd.p1 = packet.param1; // delay at waypoint in seconds
|
||||||
|
break;
|
||||||
|
|
||||||
case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
|
case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
|
||||||
cmd.content.delay.seconds = packet.param1; // delay in seconds
|
cmd.content.delay.seconds = packet.param1; // delay in seconds
|
||||||
break;
|
break;
|
||||||
@ -661,6 +666,11 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
|
|||||||
packet.param1 = cmd.p1; // minimum pitch (plane only)
|
packet.param1 = cmd.p1; // minimum pitch (plane only)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_NAV_SPLINE_WAYPOINT: // MAV ID: 82
|
||||||
|
copy_location = true;
|
||||||
|
packet.param1 = cmd.p1; // delay at waypoint in seconds
|
||||||
|
break;
|
||||||
|
|
||||||
case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
|
case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
|
||||||
packet.param1 = cmd.content.delay.seconds; // delay in seconds
|
packet.param1 = cmd.content.delay.seconds; // delay in seconds
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user