2012-04-30 04:17:14 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2014-03-10 05:45:26 -03:00
// forward declarations to make compiler happy
static void do_nav_wp(const AP_Mission::Mission_Command& cmd);
static void do_wait_delay(const AP_Mission::Mission_Command& cmd);
static void do_within_distance(const AP_Mission::Mission_Command& cmd);
static void do_change_speed(const AP_Mission::Mission_Command& cmd);
static void do_set_home(const AP_Mission::Mission_Command& cmd);
static bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
2012-04-30 04:17:14 -03:00
/********************************************************************************/
// Command Event Handlers
/********************************************************************************/
2014-03-10 05:45:26 -03:00
static bool
start_command(const AP_Mission::Mission_Command& cmd)
2012-04-30 04:17:14 -03:00
{
2014-03-18 23:42:02 -03:00
// log when new commands start
if (should_log(MASK_LOG_CMD)) {
Log_Write_Cmd(cmd);
}
2014-03-17 04:08:10 -03:00
// exit immediately if not in AUTO mode
if (control_mode != AUTO) {
return false;
}
2014-03-10 05:45:26 -03:00
gcs_send_text_fmt(PSTR("Executing command ID #%i"),cmd.id);
2012-04-30 04:17:14 -03:00
2014-04-06 20:30:39 -03:00
// remember the course of our next navigation leg
next_navigation_leg_cd = mission.get_next_ground_course_cd(0);
2014-03-10 05:45:26 -03:00
switch(cmd.id){
2012-04-30 04:17:14 -03:00
case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint
2014-03-10 05:45:26 -03:00
do_nav_wp(cmd);
2012-04-30 04:17:14 -03:00
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
do_RTL();
break;
2014-03-10 05:45:26 -03:00
// Conditional commands
2012-04-30 04:17:14 -03:00
case MAV_CMD_CONDITION_DELAY:
2014-03-10 05:45:26 -03:00
do_wait_delay(cmd);
2012-04-30 04:17:14 -03:00
break;
case MAV_CMD_CONDITION_DISTANCE:
2014-03-10 05:45:26 -03:00
do_within_distance(cmd);
2012-04-30 04:17:14 -03:00
break;
2014-03-10 05:45:26 -03:00
// Do commands
2012-04-30 04:17:14 -03:00
case MAV_CMD_DO_CHANGE_SPEED:
2014-03-10 05:45:26 -03:00
do_change_speed(cmd);
2012-04-30 04:17:14 -03:00
break;
case MAV_CMD_DO_SET_HOME:
2014-03-10 05:45:26 -03:00
do_set_home(cmd);
2012-04-30 04:17:14 -03:00
break;
2014-01-20 01:05:23 -04:00
case MAV_CMD_DO_SET_SERVO:
2014-03-17 04:08:10 -03:00
ServoRelayEvents.do_set_servo(cmd.content.servo.channel, cmd.content.servo.pwm);
2014-01-20 01:05:23 -04:00
break;
2012-04-30 04:17:14 -03:00
2014-01-20 01:05:23 -04:00
case MAV_CMD_DO_SET_RELAY:
2014-03-17 04:08:10 -03:00
ServoRelayEvents.do_set_relay(cmd.content.relay.num, cmd.content.relay.state);
2014-01-20 01:05:23 -04:00
break;
2012-04-30 04:17:14 -03:00
2014-01-20 01:05:23 -04:00
case MAV_CMD_DO_REPEAT_SERVO:
2014-03-18 23:14:31 -03:00
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);
2014-01-20 01:05:23 -04:00
break;
2012-04-30 04:17:14 -03:00
2014-01-20 01:05:23 -04:00
case MAV_CMD_DO_REPEAT_RELAY:
2014-03-18 23:14:31 -03:00
ServoRelayEvents.do_repeat_relay(cmd.content.repeat_relay.num, cmd.content.repeat_relay.repeat_count,
cmd.content.repeat_relay.cycle_time * 1000.0f);
2014-01-20 01:05:23 -04:00
break;
2012-04-30 04:17:14 -03:00
2013-07-14 20:57:00 -03:00
#if CAMERA == ENABLED
2014-03-10 05:45:26 -03:00
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;
2013-07-14 20:57:00 -03:00
2014-03-10 05:45:26 -03:00
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)|
break;
2013-07-14 20:57:00 -03:00
2014-03-10 05:45:26 -03:00
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_take_picture();
break;
2013-10-11 07:36:07 -03:00
2014-03-10 05:45:26 -03:00
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
2014-03-17 04:08:10 -03:00
camera.set_trigger_distance(cmd.content.cam_trigg_dist.meters);
2014-03-10 05:45:26 -03:00
break;
2013-07-14 20:57:00 -03:00
#endif
2012-04-30 04:17:14 -03:00
#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|
2014-07-04 03:43:08 -03:00
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_cmd(&cmd.content.location);
}
break;
2012-04-30 04:17:14 -03:00
case MAV_CMD_DO_MOUNT_CONFIGURE: // Mission command to configure a camera mount |Mount operation mode (see MAV_CONFIGURE_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
camera_mount.configure_cmd();
break;
case MAV_CMD_DO_MOUNT_CONTROL: // Mission command to control a camera mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|
camera_mount.control_cmd();
break;
#endif
2014-03-10 05:45:26 -03:00
default:
// return false for unhandled commands
return false;
2012-04-30 04:17:14 -03:00
}
2014-03-10 05:45:26 -03:00
// if we got this far we must have been successful
return true;
2012-04-30 04:17:14 -03:00
}
2014-03-17 04:08:10 -03:00
// exit_mission - callback function called from ap-mission when the mission has completed
// 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
2014-03-10 05:45:26 -03:00
static void exit_mission()
{
2014-03-17 04:08:10 -03:00
if (control_mode == AUTO) {
gcs_send_text_fmt(PSTR("No commands - setting HOLD"));
set_mode(HOLD);
}
2012-04-30 04:17:14 -03:00
}
/********************************************************************************/
// Verify command Handlers
2014-03-10 05:45:26 -03:00
// Returns true if command complete
2012-04-30 04:17:14 -03:00
/********************************************************************************/
2014-03-10 05:45:26 -03:00
static bool verify_command(const AP_Mission::Mission_Command& cmd)
2012-04-30 04:17:14 -03:00
{
2014-03-17 04:08:10 -03:00
// exit immediately if not in AUTO mode
// we return true or we will continue to be called by ap-mission
if (control_mode != AUTO) {
return true;
}
2014-03-10 05:45:26 -03:00
switch(cmd.id) {
2012-04-30 04:17:14 -03:00
case MAV_CMD_NAV_WAYPOINT:
2014-03-10 05:45:26 -03:00
return verify_nav_wp(cmd);
2012-04-30 04:17:14 -03:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
return verify_RTL();
2014-03-10 05:45:26 -03:00
case MAV_CMD_CONDITION_DELAY:
return verify_wait_delay();
break;
2012-04-30 04:17:14 -03:00
2014-03-10 05:45:26 -03:00
case MAV_CMD_CONDITION_DISTANCE:
return verify_within_distance();
break;
default:
2014-06-04 01:00:31 -03:00
if (cmd.id > MAV_CMD_CONDITION_LAST) {
// this is a command that doesn't require verify
return true;
}
2014-03-10 05:45:26 -03:00
gcs_send_text_P(SEVERITY_HIGH,PSTR("verify_conditon: Unsupported command"));
return true;
break;
2012-04-30 04:17:14 -03:00
}
return false;
}
/********************************************************************************/
// Nav (Must) commands
/********************************************************************************/
static void do_RTL(void)
{
2014-03-17 04:44:25 -03:00
prev_WP = current_loc;
2012-04-30 04:17:14 -03:00
control_mode = RTL;
2014-03-17 04:44:25 -03:00
next_WP = home;
2012-04-30 04:17:14 -03:00
}
2014-03-10 05:45:26 -03:00
static void do_nav_wp(const AP_Mission::Mission_Command& cmd)
2012-04-30 04:17:14 -03:00
{
2014-03-17 04:44:25 -03:00
set_next_WP(cmd.content.location);
2012-04-30 04:17:14 -03:00
}
/********************************************************************************/
// Verify Nav (Must) commands
/********************************************************************************/
2014-03-10 05:45:26 -03:00
static bool verify_nav_wp(const AP_Mission::Mission_Command& cmd)
2012-04-30 04:17:14 -03:00
{
2012-11-18 01:07:50 -04:00
if ((wp_distance > 0) && (wp_distance <= g.waypoint_radius)) {
gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"),
2014-03-10 05:45:26 -03:00
(unsigned)cmd.index,
2014-03-17 04:44:25 -03:00
(unsigned)get_distance(current_loc, next_WP));
2012-11-18 01:07:50 -04:00
return true;
}
2012-11-27 18:20:20 -04:00
// have we gone past the waypoint?
2014-03-17 04:44:25 -03:00
if (location_passed_point(current_loc, prev_WP, next_WP)) {
2012-11-18 01:07:50 -04:00
gcs_send_text_fmt(PSTR("Passed Waypoint #%i dist %um"),
2014-03-10 05:45:26 -03:00
(unsigned)cmd.index,
2014-03-17 04:44:25 -03:00
(unsigned)get_distance(current_loc, next_WP));
2012-11-18 01:07:50 -04:00
return true;
}
return false;
2012-04-30 04:17:14 -03:00
}
static bool verify_RTL()
{
if (wp_distance <= g.waypoint_radius) {
gcs_send_text_P(SEVERITY_LOW,PSTR("Reached home"));
2012-05-14 12:47:08 -03:00
rtl_complete = true;
2012-04-30 04:17:14 -03:00
return true;
}
2013-03-28 20:24:59 -03:00
// have we gone past the waypoint?
2014-03-17 04:44:25 -03:00
if (location_passed_point(current_loc, prev_WP, next_WP)) {
2013-03-28 20:24:59 -03:00
gcs_send_text_fmt(PSTR("Reached Home dist %um"),
2014-03-17 04:44:25 -03:00
(unsigned)get_distance(current_loc, next_WP));
2013-03-28 20:24:59 -03:00
return true;
}
return false;
2012-04-30 04:17:14 -03:00
}
/********************************************************************************/
// Condition (May) commands
/********************************************************************************/
2014-03-10 05:45:26 -03:00
static void do_wait_delay(const AP_Mission::Mission_Command& cmd)
2012-04-30 04:17:14 -03:00
{
condition_start = millis();
2014-03-17 04:08:10 -03:00
condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds
2012-04-30 04:17:14 -03:00
}
2014-03-10 05:45:26 -03:00
static void do_within_distance(const AP_Mission::Mission_Command& cmd)
2012-04-30 04:17:14 -03:00
{
2014-03-17 04:08:10 -03:00
condition_value = cmd.content.distance.meters;
2012-04-30 04:17:14 -03:00
}
/********************************************************************************/
// Verify Condition (May) commands
/********************************************************************************/
static bool verify_wait_delay()
{
2012-11-27 18:20:20 -04:00
if ((uint32_t)(millis() - condition_start) > (uint32_t)condition_value){
2012-04-30 04:17:14 -03:00
condition_value = 0;
return true;
}
return false;
}
static bool verify_within_distance()
{
if (wp_distance < condition_value){
condition_value = 0;
return true;
}
return false;
}
/********************************************************************************/
// Do (Now) commands
/********************************************************************************/
2014-03-10 05:45:26 -03:00
static void do_change_speed(const AP_Mission::Mission_Command& cmd)
2012-04-30 04:17:14 -03:00
{
2014-03-10 05:45:26 -03:00
switch (cmd.p1)
2012-04-30 04:17:14 -03:00
{
2013-02-07 18:21:22 -04:00
case 0:
2014-03-17 04:08:10 -03:00
if (cmd.content.speed.target_ms > 0) {
g.speed_cruise.set(cmd.content.speed.target_ms);
gcs_send_text_fmt(PSTR("Cruise speed: %.1f m/s"), g.speed_cruise.get());
2013-05-26 22:08:25 -03:00
}
2012-04-30 04:17:14 -03:00
break;
}
2014-03-17 04:08:10 -03:00
if (cmd.content.speed.throttle_pct > 0 && cmd.content.speed.throttle_pct <= 100) {
g.throttle_cruise.set(cmd.content.speed.throttle_pct);
2013-05-26 22:08:25 -03:00
gcs_send_text_fmt(PSTR("Cruise throttle: %.1f"), g.throttle_cruise.get());
}
2012-04-30 04:17:14 -03:00
}
2014-03-10 05:45:26 -03:00
static void do_set_home(const AP_Mission::Mission_Command& cmd)
2012-04-30 04:17:14 -03:00
{
2014-03-10 05:45:26 -03:00
if(cmd.p1 == 1 && have_position) {
2012-04-30 04:17:14 -03:00
init_home();
} else {
2014-03-30 22:01:54 -03:00
ahrs.set_home(cmd.content.location);
2012-04-30 04:17:14 -03:00
home_is_set = true;
}
}
2013-07-14 20:57:00 -03:00
// do_take_picture - take a picture with the camera library
static void do_take_picture()
{
#if CAMERA == ENABLED
camera.trigger_pic();
2014-01-14 00:10:13 -04:00
if (should_log(MASK_LOG_CAMERA)) {
2014-06-10 23:57:54 -03:00
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
2013-07-14 20:57:00 -03:00
}
#endif
}