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

ArduCopter: handle DO_PARACHUTE as both command_long and command_int #24970

Merged
merged 2 commits into from Sep 19, 2023
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
19 changes: 13 additions & 6 deletions ArduCopter/GCS_Mavlink.cpp
Expand Up @@ -759,6 +759,11 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
case MAV_CMD_DO_MOTOR_TEST:
return handle_MAV_CMD_DO_MOTOR_TEST(packet);

#if PARACHUTE == ENABLED
case MAV_CMD_DO_PARACHUTE:
return handle_MAV_CMD_DO_PARACHUTE(packet);
#endif

#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
// Solo user presses pause button
case MAV_CMD_SOLO_BTN_PAUSE_CLICK:
Expand Down Expand Up @@ -900,8 +905,14 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
return MAV_RESULT_FAILED;
#endif

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

#if PARACHUTE == ENABLED
case MAV_CMD_DO_PARACHUTE:
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
{
// configure or release parachute
switch ((uint16_t)packet.param1) {
case PARACHUTE_DISABLE:
Expand All @@ -916,12 +927,8 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
#endif

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

MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
{
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/GCS_Mavlink.h
Expand Up @@ -99,6 +99,7 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK


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);

#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
MAV_RESULT handle_MAV_CMD_SOLO_BTN_FLY_CLICK(const mavlink_command_int_t &packet);
Expand Down
21 changes: 13 additions & 8 deletions Tools/autotest/arducopter.py
Expand Up @@ -3666,8 +3666,8 @@ def test_rangefinder_switchover(self):
if ex is not None:
raise ex

def Parachute(self):
'''Test Parachute Functionality'''
def _Parachute(self, command):
'''Test Parachute Functionality using specific mavlink command'''
self.set_rc(9, 1000)
self.set_parameters({
"CHUTE_ENABLED": 1,
Expand All @@ -3690,7 +3690,7 @@ def Parachute(self):

self.progress("Test triggering with mavlink message")
self.takeoff(20)
self.run_cmd(
command(
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
p1=2, # release
)
Expand All @@ -3711,7 +3711,7 @@ def Parachute(self):

self.progress("Test mavlink triggering")
self.takeoff(20)
self.run_cmd(
command(
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
p1=mavutil.mavlink.PARACHUTE_DISABLE,
)
Expand All @@ -3722,7 +3722,7 @@ def Parachute(self):
ok = True
if not ok:
raise NotAchievedException("Disabled parachute fired")
self.run_cmd(
command(
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
p1=mavutil.mavlink.PARACHUTE_ENABLE,
)
Expand All @@ -3740,7 +3740,7 @@ def Parachute(self):

# parachute should not fire if you go from disabled to release:
self.takeoff(20)
self.run_cmd(
command(
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
p1=mavutil.mavlink.PARACHUTE_RELEASE,
)
Expand All @@ -3753,11 +3753,11 @@ def Parachute(self):
raise NotAchievedException("Parachute fired when going straight from disabled to release")

# now enable then release parachute:
self.run_cmd(
command(
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
p1=mavutil.mavlink.PARACHUTE_ENABLE,
)
self.run_cmd(
command(
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
p1=mavutil.mavlink.PARACHUTE_RELEASE,
)
Expand Down Expand Up @@ -3800,6 +3800,11 @@ def Parachute(self):
self.disarm_vehicle(force=True)
self.reboot_sitl()

def Parachute(self):
'''Test Parachute Functionality'''
self._Parachute(self.run_cmd)
self._Parachute(self.run_cmd_int)

def _MotorTest(self, command, timeout=60):
'''Run Motor Tests (with specific mavlink message)'''
self.start_subtest("Testing PWM output")
Expand Down