ardupilot/APMrover2/commands_logic.cpp

431 lines
15 KiB
C++

#include "Rover.h"
// update mission including starting or stopping commands. called by scheduler at 10Hz
void Rover::update_mission(void)
{
if (control_mode == &mode_auto) {
if (home_is_set != HOME_UNSET && mission.num_commands() > 1) {
mission.update();
}
}
}
/********************************************************************************/
// Command Event Handlers
/********************************************************************************/
bool Rover::start_command(const AP_Mission::Mission_Command& cmd)
{
// log when new commands start
if (should_log(MASK_LOG_CMD)) {
DataFlash.Log_Write_Mission_Cmd(mission, cmd);
}
gcs().send_text(MAV_SEVERITY_INFO, "Executing command ID #%i", cmd.id);
switch (cmd.id) {
case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint
do_nav_wp(cmd, false);
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
do_RTL();
break;
case MAV_CMD_NAV_LOITER_UNLIM: // Loiter indefinitely
do_loiter_unlimited(cmd);
break;
case MAV_CMD_NAV_LOITER_TIME:
do_loiter_time(cmd);
break;
case MAV_CMD_NAV_SET_YAW_SPEED:
do_nav_set_yaw_speed(cmd);
break;
// Conditional commands
case MAV_CMD_CONDITION_DELAY:
do_wait_delay(cmd);
break;
case MAV_CMD_CONDITION_DISTANCE:
do_within_distance(cmd);
break;
// Do commands
case MAV_CMD_DO_CHANGE_SPEED:
do_change_speed(cmd);
break;
case MAV_CMD_DO_SET_HOME:
do_set_home(cmd);
break;
case MAV_CMD_DO_SET_SERVO:
ServoRelayEvents.do_set_servo(cmd.content.servo.channel, cmd.content.servo.pwm);
break;
case MAV_CMD_DO_SET_RELAY:
ServoRelayEvents.do_set_relay(cmd.content.relay.num, cmd.content.relay.state);
break;
case MAV_CMD_DO_REPEAT_SERVO:
ServoRelayEvents.do_repeat_servo(cmd.content.repeat_servo.channel, cmd.content.repeat_servo.pwm,
cmd.content.repeat_servo.repeat_count, cmd.content.repeat_servo.cycle_time * 1000.0f);
break;
case MAV_CMD_DO_REPEAT_RELAY:
ServoRelayEvents.do_repeat_relay(cmd.content.repeat_relay.num, cmd.content.repeat_relay.repeat_count,
cmd.content.repeat_relay.cycle_time * 1000.0f);
break;
#if CAMERA == ENABLED
case MAV_CMD_DO_CONTROL_VIDEO: // Control on-board camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
break;
case MAV_CMD_DO_DIGICAM_CONFIGURE: // Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|
do_digicam_configure(cmd);
break;
case MAV_CMD_DO_DIGICAM_CONTROL: // Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|
do_digicam_control(cmd);
break;
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
camera.set_trigger_distance(cmd.content.cam_trigg_dist.meters);
break;
#endif
#if MOUNT == ENABLED
// Sets the region of interest (ROI) for a sensor set or the
// vehicle itself. This can then be used by the vehicles control
// system to control the vehicle attitude and the attitude of various
// devices such as cameras.
// |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
case MAV_CMD_DO_SET_ROI:
if (cmd.content.location.alt == 0 && cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {
// switch off the camera tracking if enabled
if (camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
camera_mount.set_mode_to_default();
}
} else {
// send the command to the camera mount
camera_mount.set_roi_target(cmd.content.location);
}
break;
#endif
case MAV_CMD_DO_SET_REVERSE:
do_set_reverse(cmd);
break;
default:
// return false for unhandled commands
return false;
}
// if we got this far we must have been successful
return true;
}
// exit_mission - callback function called from ap-mission when the mission has completed
void Rover::exit_mission()
{
gcs().send_text(MAV_SEVERITY_NOTICE, "Mission Complete");
set_mode(mode_hold, MODE_REASON_MISSION_END);
}
// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
bool Rover::verify_command_callback(const AP_Mission::Mission_Command& cmd)
{
const bool cmd_complete = verify_command(cmd);
// send message to GCS
if (cmd_complete) {
gcs().send_mission_item_reached_message(cmd.index);
}
return cmd_complete;
}
/*******************************************************************************
Verify command Handlers
Each type of mission element has a "verify" operation. The verify
operation returns true when the mission element has completed and we
should move onto the next mission element.
Return true if we do not recognize the command so that we move on to the next command
*******************************************************************************/
bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
{
switch (cmd.id) {
case MAV_CMD_NAV_WAYPOINT:
return verify_nav_wp(cmd);
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
return verify_RTL();
case MAV_CMD_NAV_LOITER_UNLIM:
return verify_loiter_unlimited(cmd);
case MAV_CMD_NAV_LOITER_TIME:
return verify_loiter_time(cmd);
case MAV_CMD_CONDITION_DELAY:
return verify_wait_delay();
case MAV_CMD_CONDITION_DISTANCE:
return verify_within_distance();
case MAV_CMD_NAV_SET_YAW_SPEED:
return verify_nav_set_yaw_speed();
// do commands (always return true)
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_SET_HOME:
case MAV_CMD_DO_SET_SERVO:
case MAV_CMD_DO_SET_RELAY:
case MAV_CMD_DO_REPEAT_SERVO:
case MAV_CMD_DO_REPEAT_RELAY:
case MAV_CMD_DO_CONTROL_VIDEO:
case MAV_CMD_DO_DIGICAM_CONFIGURE:
case MAV_CMD_DO_DIGICAM_CONTROL:
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
case MAV_CMD_DO_SET_ROI:
case MAV_CMD_DO_SET_REVERSE:
return true;
default:
// error message
gcs().send_text(MAV_SEVERITY_WARNING, "Skipping invalid cmd #%i", cmd.id);
// return true if we do not recognize the command so that we move on to the next command
return true;
}
}
/********************************************************************************/
// Nav (Must) commands
/********************************************************************************/
void Rover::do_RTL(void)
{
set_mode(mode_rtl, MODE_REASON_MISSION_COMMAND);
}
void Rover::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool stay_active_at_dest)
{
// just starting so we haven't previously reached the waypoint
previously_reached_wp = false;
// this will be used to remember the time in millis after we reach or pass the WP.
loiter_start_time = 0;
// this is the delay, stored in seconds
loiter_duration = cmd.p1;
// get heading to following waypoint (auto mode reduces speed to allow corning without large overshoot)
// in case of non-zero loiter duration, we provide heading-unknown to signal we should stop at the point
float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN;
if (loiter_duration == 0) {
next_leg_bearing_cd = mission.get_next_ground_course_cd(MODE_NEXT_HEADING_UNKNOWN);
}
// retrieve and sanitize target location
Location cmdloc = cmd.content.location;
location_sanitize(current_loc, cmdloc);
mode_auto.set_desired_location(cmdloc, next_leg_bearing_cd, stay_active_at_dest);
}
void Rover::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
{
do_nav_wp(cmd, true);
}
// do_loiter_time - initiate loitering at a point for a given time period
// if the vehicle is moved off the loiter point (i.e. a boat in a current)
// then the vehicle will actively return to the loiter coords.
void Rover::do_loiter_time(const AP_Mission::Mission_Command& cmd)
{
do_nav_wp(cmd, true);
}
// do_set_yaw_speed - turn to a specified heading and achieve and given speed
void Rover::do_nav_set_yaw_speed(const AP_Mission::Mission_Command& cmd)
{
float desired_heading_cd;
// get final angle, 1 = Relative, 0 = Absolute
if (cmd.content.set_yaw_speed.relative_angle > 0) {
// relative angle
desired_heading_cd = wrap_180_cd(ahrs.yaw_sensor + cmd.content.set_yaw_speed.angle_deg * 100.0f);
} else {
// absolute angle
desired_heading_cd = cmd.content.set_yaw_speed.angle_deg * 100.0f;
}
// set auto target
mode_auto.set_desired_heading_and_speed(desired_heading_cd, constrain_float(cmd.content.set_yaw_speed.speed, -g.speed_cruise, g.speed_cruise));
}
/********************************************************************************/
// Verify Nav (Must) commands
/********************************************************************************/
bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
{
// exit immediately if we haven't reached the destination
if (!mode_auto.reached_destination()) {
return false;
}
// Check if this is the first time we have noticed reaching the waypoint
if (!previously_reached_wp) {
previously_reached_wp = true;
// check if we are loitering at this waypoint - the message sent to the GCS is different
if (loiter_duration > 0) {
// send message including loiter time
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u. Loiter for %u seconds",
static_cast<uint32_t>(cmd.index),
static_cast<uint32_t>(loiter_duration));
// record the current time i.e. start timer
loiter_start_time = millis();
} else {
// send simpler message to GCS
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%u", static_cast<uint32_t>(cmd.index));
}
}
// Check if we have loitered long enough
if (loiter_duration == 0) {
return true;
} else {
return (((millis() - loiter_start_time) / 1000) >= loiter_duration);
}
}
bool Rover::verify_RTL()
{
return mode_rtl.reached_destination();
}
bool Rover::verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
{
verify_nav_wp(cmd);
return false;
}
// verify_loiter_time - check if we have loitered long enough
bool Rover::verify_loiter_time(const AP_Mission::Mission_Command& cmd)
{
const bool result = verify_nav_wp(cmd);
if (result) {
gcs().send_text(MAV_SEVERITY_WARNING, "Finished active loiter\n");
}
return result;
}
// verify_yaw - return true if we have reached the desired heading
bool Rover::verify_nav_set_yaw_speed()
{
return mode_auto.reached_heading();
}
/********************************************************************************/
// Condition (May) commands
/********************************************************************************/
void Rover::do_wait_delay(const AP_Mission::Mission_Command& cmd)
{
condition_start = millis();
condition_value = static_cast<int32_t>(cmd.content.delay.seconds * 1000); // convert seconds to milliseconds
}
void Rover::do_within_distance(const AP_Mission::Mission_Command& cmd)
{
condition_value = cmd.content.distance.meters;
}
/********************************************************************************/
// Verify Condition (May) commands
/********************************************************************************/
bool Rover::verify_wait_delay()
{
if (static_cast<uint32_t>(millis() - condition_start) > static_cast<uint32_t>(condition_value)) {
condition_value = 0;
return true;
}
return false;
}
bool Rover::verify_within_distance()
{
if (mode_auto.get_distance_to_destination() < condition_value) {
condition_value = 0;
return true;
}
return false;
}
/********************************************************************************/
// Do (Now) commands
/********************************************************************************/
void Rover::do_change_speed(const AP_Mission::Mission_Command& cmd)
{
if (cmd.content.speed.target_ms > 0.0f) {
g.speed_cruise.set(cmd.content.speed.target_ms);
gcs().send_text(MAV_SEVERITY_INFO, "Cruise speed: %.1f m/s", static_cast<double>(g.speed_cruise.get()));
}
if (cmd.content.speed.throttle_pct > 0.0f && cmd.content.speed.throttle_pct <= 100.0f) {
g.throttle_cruise.set(cmd.content.speed.throttle_pct);
gcs().send_text(MAV_SEVERITY_INFO, "Cruise throttle: %.1f", static_cast<double>(g.throttle_cruise.get()));
}
}
void Rover::do_set_home(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 == 1 && have_position) {
set_home_to_current_location(false);
} else {
set_home(cmd.content.location, false);
}
}
#if CAMERA == ENABLED
// do_digicam_configure Send Digicam Configure message with the camera library
void Rover::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
{
camera.configure(cmd.content.digicam_configure.shooting_mode,
cmd.content.digicam_configure.shutter_speed,
cmd.content.digicam_configure.aperture,
cmd.content.digicam_configure.ISO,
cmd.content.digicam_configure.exposure_type,
cmd.content.digicam_configure.cmd_id,
cmd.content.digicam_configure.engine_cutoff_time);
}
// do_digicam_control Send Digicam Control message with the camera library
void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd)
{
camera.control(cmd.content.digicam_control.session,
cmd.content.digicam_control.zoom_pos,
cmd.content.digicam_control.zoom_step,
cmd.content.digicam_control.focus_lock,
cmd.content.digicam_control.shooting_cmd,
cmd.content.digicam_control.cmd_id);
}
#endif
void Rover::do_set_reverse(const AP_Mission::Mission_Command& cmd)
{
mode_auto.set_reversed(cmd.p1 == 1);
set_reverse(cmd.p1 == 1);
}