GCS_MAVLink: take MAV_CMD_DO_SPRAYER as a mavlink command

This commit is contained in:
Peter Barker 2020-07-04 08:46:43 +10:00 committed by Peter Barker
parent b14dcf4bae
commit eefcc92f24
2 changed files with 26 additions and 0 deletions

View File

@ -483,6 +483,7 @@ protected:
MAV_RESULT handle_command_do_set_roi(const mavlink_command_long_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_set_mode(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);

View File

@ -29,6 +29,7 @@
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Camera/AP_Camera.h>
#include <AP_Gripper/AP_Gripper.h>
#include <AC_Sprayer/AC_Sprayer.h>
#include <AP_BLHeli/AP_BLHeli.h>
#include <AP_RSSI/AP_RSSI.h>
#include <AP_RTC/AP_RTC.h>
@ -3866,6 +3867,24 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_long_t &
return result;
}
#if HAL_SPRAYER_ENABLED
MAV_RESULT GCS_MAVLINK::handle_command_do_sprayer(const mavlink_command_long_t &packet)
{
AC_Sprayer *sprayer = AP::sprayer();
if (sprayer == nullptr) {
return MAV_RESULT_FAILED;
}
if (is_equal(packet.param1, 1.0f)) {
sprayer->run(true);
} else if (is_zero(packet.param1)) {
sprayer->run(false);
}
return MAV_RESULT_ACCEPTED;
}
#endif
MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet)
{
if (!AP::ins().get_acal()->gcs_vehicle_position(packet.param1)) {
@ -3991,6 +4010,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
result = handle_command_do_gripper(packet);
break;
#if HAL_SPRAYER_ENABLED
case MAV_CMD_DO_SPRAYER:
result = handle_command_do_sprayer(packet);
break;
#endif
case MAV_CMD_DO_MOUNT_CONFIGURE:
case MAV_CMD_DO_MOUNT_CONTROL:
result = handle_command_mount(packet);