AP_Mission: add mission command to turn sprayer on and off

This commit is contained in:
Peter Barker 2020-07-03 09:04:27 +10:00 committed by Peter Barker
parent 98287a1b2f
commit c3b005e1d9
3 changed files with 36 additions and 0 deletions

View File

@ -297,6 +297,7 @@ bool AP_Mission::verify_command(const Mission_Command& cmd)
case MAV_CMD_DO_DIGICAM_CONTROL:
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
case MAV_CMD_DO_PARACHUTE:
case MAV_CMD_DO_SPRAYER:
case MAV_CMD_DO_SET_RESUME_REPEAT_DIST:
return true;
default:
@ -327,6 +328,8 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
return start_command_camera(cmd);
case MAV_CMD_DO_PARACHUTE:
return start_command_parachute(cmd);
case MAV_CMD_DO_SPRAYER:
return start_command_do_sprayer(cmd);
case MAV_CMD_DO_SET_RESUME_REPEAT_DIST:
return command_do_set_repeat_dist(cmd);
default:
@ -1091,6 +1094,10 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
cmd.p1 = packet.param1; // Resume repeat distance (m)
break;
case MAV_CMD_DO_SPRAYER:
cmd.p1 = packet.param1; // action 0=disable, 1=enable
break;
default:
// unrecognised command
return MAV_MISSION_UNSUPPORTED;
@ -1464,6 +1471,10 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
packet.param1 = cmd.p1; // action 0=disable, 1=enable, 2=release. See PARACHUTE_ACTION enum
break;
case MAV_CMD_DO_SPRAYER:
packet.param1 = cmd.p1; // action 0=disable, 1=enable
break;
case MAV_CMD_DO_INVERTED_FLIGHT: // MAV ID: 210
packet.param1 = cmd.p1; // normal=0 inverted=1
break;
@ -2230,6 +2241,8 @@ const char *AP_Mission::Mission_Command::type() const
return "PayloadPlace";
case MAV_CMD_DO_PARACHUTE:
return "Parachute";
case MAV_CMD_DO_SPRAYER:
return "Sprayer";
case MAV_CMD_DO_MOUNT_CONTROL:
return "MountControl";
case MAV_CMD_DO_WINCH:

View File

@ -696,6 +696,8 @@ private:
bool start_command_camera(const AP_Mission::Mission_Command& cmd);
bool start_command_parachute(const AP_Mission::Mission_Command& cmd);
bool command_do_set_repeat_dist(const AP_Mission::Mission_Command& cmd);
bool start_command_do_sprayer(const AP_Mission::Mission_Command& cmd);
};
namespace AP

View File

@ -5,6 +5,7 @@
#include <AP_Gripper/AP_Gripper.h>
#include <AP_Parachute/AP_Parachute.h>
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AC_Sprayer/AC_Sprayer.h>
bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd)
{
@ -146,3 +147,23 @@ bool AP_Mission::command_do_set_repeat_dist(const AP_Mission::Mission_Command& c
gcs().send_text(MAV_SEVERITY_INFO, "Resume repeat dist set to %u m",_repeat_dist);
return true;
}
bool AP_Mission::start_command_do_sprayer(const AP_Mission::Mission_Command& cmd)
{
#if HAL_SPRAYER_ENABLED
AC_Sprayer *sprayer = AP::sprayer();
if (sprayer == nullptr) {
return false;
}
if (cmd.p1 == 1) {
sprayer->run(true);
} else {
sprayer->run(false);
}
return true;
#else
return false;
#endif // HAL_SPRAYER_ENABLED
}