// start_command - this function will be called when the ap_mission lib wishes to start a new command bool Copter::start_command(const AP_Mission::Mission_Command& cmd) { // To-Do: logging when new commands start/end if (should_log(MASK_LOG_CMD)) { DataFlash.Log_Write_Mission_Cmd(mission, cmd); } switch(cmd.id) { /// /// navigation commands /// case MAV_CMD_NAV_TAKEOFF: // 22 do_takeoff(cmd); break; case MAV_CMD_NAV_WAYPOINT: // 16 Navigate to Waypoint do_nav_wp(cmd); break; case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint do_land(cmd); break; case MAV_CMD_NAV_PAYLOAD_PLACE: // 94 place at Waypoint do_payload_place(cmd); break; case MAV_CMD_NAV_LOITER_UNLIM: // 17 Loiter indefinitely do_loiter_unlimited(cmd); break; case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times do_circle(cmd); break; case MAV_CMD_NAV_LOITER_TIME: // 19 do_loiter_time(cmd); break; case MAV_CMD_NAV_RETURN_TO_LAUNCH: //20 do_RTL(); break; case MAV_CMD_NAV_SPLINE_WAYPOINT: // 82 Navigate to Waypoint using spline do_spline_wp(cmd); break; #if NAV_GUIDED == ENABLED case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer do_nav_guided_enable(cmd); break; #endif case MAV_CMD_NAV_DELAY: // 94 Delay the next navigation command do_nav_delay(cmd); break; // // conditional commands // case MAV_CMD_CONDITION_DELAY: // 112 do_wait_delay(cmd); break; case MAV_CMD_CONDITION_DISTANCE: // 114 do_within_distance(cmd); break; case MAV_CMD_CONDITION_YAW: // 115 do_yaw(cmd); break; /// /// do commands /// case MAV_CMD_DO_CHANGE_SPEED: // 178 do_change_speed(cmd); break; case MAV_CMD_DO_SET_HOME: // 179 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; case MAV_CMD_DO_SET_ROI: // 201 // point the copter and camera at a region of interest (ROI) do_roi(cmd); break; case MAV_CMD_DO_MOUNT_CONTROL: // 205 // point the camera to a specified angle do_mount_control(cmd); 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 PARACHUTE == ENABLED case MAV_CMD_DO_PARACHUTE: // Mission command to configure or release parachute do_parachute(cmd); break; #endif #if GRIPPER_ENABLED == ENABLED case MAV_CMD_DO_GRIPPER: // Mission command to control gripper do_gripper(cmd); break; #endif #if NAV_GUIDED == ENABLED case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits do_guided_limits(cmd); break; #endif default: // do nothing with unrecognized MAVLink messages break; } // always return success return true; }
bool Plane::start_command(const AP_Mission::Mission_Command& cmd) { // log when new commands start if (should_log(MASK_LOG_CMD)) { Log_Write_Cmd(cmd); } // special handling for nav vs non-nav commands if (AP_Mission::is_nav_cmd(cmd)) { // set land_complete to false to stop us zeroing the throttle auto_state.land_complete = false; auto_state.land_sink_rate = 0; // set takeoff_complete to true so we don't add extra evevator // except in a takeoff auto_state.takeoff_complete = true; // if a go around had been commanded, clear it now. auto_state.commanded_go_around = false; gcs_send_text_fmt(PSTR("Executing nav command ID #%i"),cmd.id); } else { gcs_send_text_fmt(PSTR("Executing command ID #%i"),cmd.id); } switch(cmd.id) { case MAV_CMD_NAV_TAKEOFF: do_takeoff(cmd); break; case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint do_nav_wp(cmd); break; case MAV_CMD_NAV_LAND: // LAND to Waypoint do_land(cmd); break; case MAV_CMD_NAV_LOITER_UNLIM: // Loiter indefinitely do_loiter_unlimited(cmd); break; case MAV_CMD_NAV_LOITER_TURNS: // Loiter N Times do_loiter_turns(cmd); break; case MAV_CMD_NAV_LOITER_TIME: do_loiter_time(cmd); break; case MAV_CMD_NAV_LOITER_TO_ALT: do_loiter_to_alt(cmd); break; case MAV_CMD_NAV_RETURN_TO_LAUNCH: set_mode(RTL); break; case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: do_continue_and_change_alt(cmd); break; // Conditional commands case MAV_CMD_CONDITION_DELAY: do_wait_delay(cmd); break; case MAV_CMD_CONDITION_DISTANCE: do_within_distance(cmd); break; case MAV_CMD_CONDITION_CHANGE_ALT: do_change_alt(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; case MAV_CMD_DO_INVERTED_FLIGHT: if (cmd.p1 == 0 || cmd.p1 == 1) { auto_state.inverted_flight = (bool)cmd.p1; gcs_send_text_fmt(PSTR("Set inverted %u"), cmd.p1); } break; case MAV_CMD_DO_LAND_START: //ensure go around hasn't been set auto_state.commanded_go_around = false; break; case MAV_CMD_DO_FENCE_ENABLE: #if GEOFENCE_ENABLED == ENABLED if (cmd.p1 != 2) { if (!geofence_set_enabled((bool) cmd.p1, AUTO_TOGGLED)) { gcs_send_text_fmt(PSTR("Unable to set fence enabled state to %u"), cmd.p1); } else { gcs_send_text_fmt(PSTR("Set fence enabled state to %u"), cmd.p1); } } else { //commanding to only disable floor if (! geofence_set_floor_enabled(false)) { gcs_send_text_fmt(PSTR("Unabled to disable fence floor.\n")); } else { gcs_send_text_fmt(PSTR("Fence floor disabled.\n")); } } #endif 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 Send Digicam Control message with the camera library 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 { // set mount's target location camera_mount.set_roi_target(cmd.content.location); } break; #endif } return true; }
bool Plane::start_command(const AP_Mission::Mission_Command& cmd) { // default to non-VTOL loiter auto_state.vtol_loiter = false; // log when new commands start if (should_log(MASK_LOG_CMD)) { DataFlash.Log_Write_Mission_Cmd(mission, cmd); } // special handling for nav vs non-nav commands if (AP_Mission::is_nav_cmd(cmd)) { // set land_complete to false to stop us zeroing the throttle auto_state.sink_rate = 0; // set takeoff_complete to true so we don't add extra elevator // except in a takeoff auto_state.takeoff_complete = true; // start non-idle auto_state.idle_mode = false; nav_controller->set_data_is_stale(); // reset loiter start time. New command is a new loiter loiter.start_time_ms = 0; AP_Mission::Mission_Command next_nav_cmd; const uint16_t next_index = mission.get_current_nav_index() + 1; auto_state.wp_is_land_approach = mission.get_next_nav_cmd(next_index, next_nav_cmd) && (next_nav_cmd.id == MAV_CMD_NAV_LAND); gcs_send_text_fmt(MAV_SEVERITY_INFO, "Executing nav command ID #%i",cmd.id); } else { gcs_send_text_fmt(MAV_SEVERITY_INFO, "Executing command ID #%i",cmd.id); } switch(cmd.id) { case MAV_CMD_NAV_TAKEOFF: crash_state.is_crashed = false; do_takeoff(cmd); break; case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint do_nav_wp(cmd); break; case MAV_CMD_NAV_LAND: // LAND to Waypoint do_land(cmd); break; case MAV_CMD_NAV_LOITER_UNLIM: // Loiter indefinitely do_loiter_unlimited(cmd); break; case MAV_CMD_NAV_LOITER_TURNS: // Loiter N Times do_loiter_turns(cmd); break; case MAV_CMD_NAV_LOITER_TIME: do_loiter_time(cmd); break; case MAV_CMD_NAV_LOITER_TO_ALT: do_loiter_to_alt(cmd); break; case MAV_CMD_NAV_RETURN_TO_LAUNCH: set_mode(RTL, MODE_REASON_UNKNOWN); break; case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: do_continue_and_change_alt(cmd); break; case MAV_CMD_NAV_ALTITUDE_WAIT: do_altitude_wait(cmd); break; case MAV_CMD_NAV_VTOL_TAKEOFF: crash_state.is_crashed = false; return quadplane.do_vtol_takeoff(cmd); case MAV_CMD_NAV_VTOL_LAND: crash_state.is_crashed = false; return quadplane.do_vtol_land(cmd); // 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; case MAV_CMD_DO_INVERTED_FLIGHT: if (cmd.p1 == 0 || cmd.p1 == 1) { auto_state.inverted_flight = (bool)cmd.p1; gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set inverted %u", cmd.p1); } break; case MAV_CMD_DO_LAND_START: break; case MAV_CMD_DO_FENCE_ENABLE: #if GEOFENCE_ENABLED == ENABLED if (cmd.p1 != 2) { if (!geofence_set_enabled((bool) cmd.p1, AUTO_TOGGLED)) { gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unable to set fence. Enabled state to %u", cmd.p1); } else { gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set fence enabled state to %u", cmd.p1); } } else { //commanding to only disable floor if (! geofence_set_floor_enabled(false)) { gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unable to disable fence floor"); } else { gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Fence floor disabled"); } } #endif break; case MAV_CMD_DO_AUTOTUNE_ENABLE: autotune_enable(cmd.p1); 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 Send Digicam Control message with the camera library 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 PARACHUTE == ENABLED case MAV_CMD_DO_PARACHUTE: do_parachute(cmd); 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 { // set mount's target location camera_mount.set_roi_target(cmd.content.location); } break; case MAV_CMD_DO_MOUNT_CONTROL: // 205 // point the camera to a specified angle camera_mount.set_angle_targets(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw); break; #endif case MAV_CMD_DO_VTOL_TRANSITION: plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)cmd.content.do_vtol_transition.target_state); break; case MAV_CMD_DO_ENGINE_CONTROL: plane.g2.ice_control.engine_control(cmd.content.do_engine_control.start_control, cmd.content.do_engine_control.cold_start, cmd.content.do_engine_control.height_delay_cm*0.01f); break; } return true; }