Skip to content

Commit

Permalink
Copter: allow DO_CHANGE_SPEED to set speed to zero
Browse files Browse the repository at this point in the history
  • Loading branch information
jschall committed Feb 20, 2015
1 parent 3768201 commit 82431e8
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ArduCopter/GCS_Mavlink.pde
Original file line number Diff line number Diff line change
Expand Up @@ -1063,7 +1063,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// param2 : new speed in m/s
// param3 : unused
// param4 : unused
if (packet.param2 > 0.0f) {
if (packet.param2 >= 0.0f) {
wp_nav.set_speed_xy(packet.param2 * 100.0f);
result = MAV_RESULT_ACCEPTED;
} else {
Expand Down

0 comments on commit 82431e8

Please sign in to comment.