Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: accept MAV_CMD_DO_AUTOTUNE_ENABLE as both long and int #25047

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
15 changes: 10 additions & 5 deletions ArduPlane/GCS_Mavlink.cpp
Expand Up @@ -954,6 +954,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
{
switch(packet.command) {

case MAV_CMD_DO_AUTOTUNE_ENABLE:
return handle_MAV_CMD_DO_AUTOTUNE_ENABLE(packet);

case MAV_CMD_DO_REPOSITION:
return handle_command_int_do_reposition(packet);

Expand Down Expand Up @@ -1059,16 +1062,18 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
case MAV_CMD_DO_GO_AROUND:
return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;

case MAV_CMD_DO_AUTOTUNE_ENABLE:
// param1 : enable/disable
plane.autotune_enable(!is_zero(packet.param1));
return MAV_RESULT_ACCEPTED;

default:
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
}
}

MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet)
{
// param1 : enable/disable
plane.autotune_enable(!is_zero(packet.param1));
return MAV_RESULT_ACCEPTED;
}

#if PARACHUTE == ENABLED
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
{
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/GCS_Mavlink.h
Expand Up @@ -54,6 +54,7 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet);
MAV_RESULT handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet);
MAV_RESULT handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet);
MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);
MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);
Expand Down
9 changes: 9 additions & 0 deletions Tools/autotest/arduplane.py
Expand Up @@ -4879,6 +4879,14 @@ def check_altitude(mav, m):

self.fly_home_land_and_disarm()

def MAV_CMD_DO_AUTOTUNE_ENABLE(self):
'''test enabling autotune via mavlink'''
self.context_collect('STATUSTEXT')
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_AUTOTUNE_ENABLE, p1=1)
self.wait_statustext('Started autotune', check_context=True)
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_AUTOTUNE_ENABLE, p1=0)
self.wait_statustext('Stopped autotune', check_context=True)

def DO_PARACHUTE(self):
'''test triggering parachute via mavlink'''
self.set_parameters({
Expand Down Expand Up @@ -4995,6 +5003,7 @@ def tests(self):
self.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
self.MAV_CMD_PREFLIGHT_CALIBRATION,
self.MAV_CMD_DO_INVERTED_FLIGHT,
self.MAV_CMD_DO_AUTOTUNE_ENABLE,
])
return ret

Expand Down