diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 8703b161d142d..1cb332597dfa9 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -9851,7 +9851,7 @@ def Sprayer(self): self.start_subtest("Checking mavlink commands") self.progress("Starting Sprayer") - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1) + self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1) self.progress("Testing speed-ramping") self.wait_servo_channel_value( diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 7ba2c0c2c8b46..94c938f6c5702 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -658,7 +658,7 @@ class GCS_MAVLINK MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc); MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_sprayer(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_do_sprayer(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_set_mode(const mavlink_command_int_t &packet); MAV_RESULT handle_command_get_home_position(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_fence_enable(const mavlink_command_int_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 0cff164fd2944..becbc4e3c091d 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4584,7 +4584,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_long_t & #endif // AP_GRIPPER_ENABLED #if HAL_SPRAYER_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_do_sprayer(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_do_sprayer(const mavlink_command_int_t &packet) { AC_Sprayer *sprayer = AP::sprayer(); if (sprayer == nullptr) { @@ -4731,11 +4731,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t result = handle_command_do_gripper(packet); break; #endif -#if HAL_SPRAYER_ENABLED - case MAV_CMD_DO_SPRAYER: - result = handle_command_do_sprayer(packet); - break; -#endif #if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: { @@ -5059,6 +5054,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_DO_SET_MODE: return handle_command_do_set_mode(packet); +#if HAL_SPRAYER_ENABLED + case MAV_CMD_DO_SPRAYER: + return handle_command_do_sprayer(packet); +#endif + #if AP_CAMERA_ENABLED case MAV_CMD_DO_DIGICAM_CONFIGURE: case MAV_CMD_DO_DIGICAM_CONTROL: