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

emit MAV_RESULT_DENIED if start/stop item passed to MAV_CMD_MISSION_START #27848

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.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -960,6 +960,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_comm
#if MODE_AUTO_ENABLED == ENABLED
MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet)
{
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
// first-item/last item not supported
return MAV_RESULT_DENIED;
}
if (copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
copter.set_auto_armed(true);
if (copter.mode_auto.mission.state() != AP_Mission::MISSION_RUNNING) {
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1080,6 +1080,10 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
return MAV_RESULT_FAILED;

case MAV_CMD_MISSION_START:
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
// first-item/last item not supported
return MAV_RESULT_DENIED;
}
plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND);
return MAV_RESULT_ACCEPTED;

Expand Down
4 changes: 4 additions & 0 deletions ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -542,6 +542,10 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_
return handle_command_int_do_reposition(packet);

case MAV_CMD_MISSION_START:
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
// first-item/last item not supported
return MAV_RESULT_DENIED;
}
return handle_MAV_CMD_MISSION_START(packet);

case MAV_CMD_NAV_LOITER_UNLIM:
Expand Down
4 changes: 4 additions & 0 deletions Rover/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -701,6 +701,10 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
packet.param4);

case MAV_CMD_MISSION_START:
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
// first-item/last item not supported
return MAV_RESULT_DENIED;
}
if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
Expand Down
31 changes: 31 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -11729,6 +11729,36 @@ def BatteryInternalUseOnly(self):
"id": 1
})

def MAV_CMD_MISSION_START_p1_p2(self):
'''make sure we deny MAV_CMD_MISSION_START if either p1 or p2 non-zero'''
self.upload_simple_relhome_mission([
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20),
])
self.set_parameters({
"AUTO_OPTIONS": 3,
})
self.change_mode('AUTO')
self.wait_ready_to_arm()

self.run_cmd(
mavutil.mavlink.MAV_CMD_MISSION_START,
p1=1,
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
)

self.run_cmd(
mavutil.mavlink.MAV_CMD_MISSION_START,
p2=1,
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
)

self.run_cmd(
mavutil.mavlink.MAV_CMD_MISSION_START,
p1=1,
p2=1,
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
)

def tests2b(self): # this block currently around 9.5mins here
'''return list of all tests'''
ret = ([
Expand Down Expand Up @@ -11828,6 +11858,7 @@ def tests2b(self): # this block currently around 9.5mins here
self.LoggingFormat,
self.MissionRTLYawBehaviour,
self.BatteryInternalUseOnly,
self.MAV_CMD_MISSION_START_p1_p2,
])
return ret

Expand Down
Loading