mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Blimp: remove misleading implementation of MAV_CMD_CONDITION_YAW
this would return success when it, in fact, does nothing.
This commit is contained in:
parent
7a937cd23a
commit
b183d167d9
@ -488,23 +488,6 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_long_packet(const mavlink_command_l
|
|||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
|
||||||
case MAV_CMD_CONDITION_YAW:
|
|
||||||
// param1 : target angle [0-360]
|
|
||||||
// param2 : speed during change [deg per second]
|
|
||||||
// param3 : direction (-1:ccw, +1:cw)
|
|
||||||
// param4 : relative offset (1) or absolute angle (0)
|
|
||||||
if ((packet.param1 >= 0.0f) &&
|
|
||||||
(packet.param1 <= 360.0f) &&
|
|
||||||
(is_zero(packet.param4) || is_equal(packet.param4,1.0f))) {
|
|
||||||
// blimp.flightmode->auto_yaw.set_fixed_yaw(
|
|
||||||
// packet.param1,
|
|
||||||
// packet.param2,
|
|
||||||
// (int8_t)packet.param3,
|
|
||||||
// is_positive(packet.param4));
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
|
||||||
}
|
|
||||||
return MAV_RESULT_FAILED;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user