Browse Source

AP_Mission: enable DO_AUTOTUNE_ENABLE

mission-4.1.18
Andrew Tridgell 11 years ago committed by Andrew Tridgell
parent
commit
9bd8e215b2
  1. 12
      libraries/AP_Mission/AP_Mission.cpp

12
libraries/AP_Mission/AP_Mission.cpp

@ -672,7 +672,11 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP @@ -672,7 +672,11 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
cmd.content.guided_limits.alt_max = packet.param3; // max alt above which the command will be aborted. 0 for no upper alt limit
cmd.content.guided_limits.horiz_max = packet.param4;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
case MAV_CMD_NAV_ALTITUDE_WAIT:
case MAV_CMD_DO_AUTOTUNE_ENABLE: // MAV ID: 211
cmd.p1 = packet.param1; // disable=0 enable=1
break;
case MAV_CMD_NAV_ALTITUDE_WAIT: // MAV ID: 83
cmd.content.altitude_wait.altitude = packet.param1;
cmd.content.altitude_wait.descent_rate = packet.param2;
cmd.content.altitude_wait.wiggle_time = packet.param3;
@ -980,7 +984,11 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd, @@ -980,7 +984,11 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
packet.param3 = cmd.content.guided_limits.alt_max; // max alt above which the command will be aborted. 0 for no upper alt limit
packet.param4 = cmd.content.guided_limits.horiz_max;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
case MAV_CMD_NAV_ALTITUDE_WAIT:
case MAV_CMD_DO_AUTOTUNE_ENABLE:
packet.param1 = cmd.p1; // disable=0 enable=1
break;
case MAV_CMD_NAV_ALTITUDE_WAIT: // MAV ID: 83
packet.param1 = cmd.content.altitude_wait.altitude;
packet.param2 = cmd.content.altitude_wait.descent_rate;
packet.param3 = cmd.content.altitude_wait.wiggle_time;

Loading…
Cancel
Save