uncrustify ArduPlane/commands_logic.pde

This commit is contained in:
uncrustify 2012-08-16 17:50:15 -07:00 committed by Pat Hickey
parent 58381e0d8e
commit 8e3fe50338
1 changed files with 343 additions and 343 deletions

View File

@ -6,149 +6,149 @@
static void static void
handle_process_nav_cmd() handle_process_nav_cmd()
{ {
// reset navigation integrators // reset navigation integrators
// ------------------------- // -------------------------
land_complete = false; land_complete = false;
reset_I(); reset_I();
gcs_send_text_fmt(PSTR("Executing command ID #%i"),next_nav_command.id); gcs_send_text_fmt(PSTR("Executing command ID #%i"),next_nav_command.id);
switch(next_nav_command.id){ switch(next_nav_command.id) {
case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_TAKEOFF:
do_takeoff(); do_takeoff();
break; break;
case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint
do_nav_wp(); do_nav_wp();
break; break;
case MAV_CMD_NAV_LAND: // LAND to Waypoint case MAV_CMD_NAV_LAND: // LAND to Waypoint
do_land(); do_land();
break; break;
case MAV_CMD_NAV_LOITER_UNLIM: // Loiter indefinitely case MAV_CMD_NAV_LOITER_UNLIM: // Loiter indefinitely
do_loiter_unlimited(); do_loiter_unlimited();
break; break;
case MAV_CMD_NAV_LOITER_TURNS: // Loiter N Times case MAV_CMD_NAV_LOITER_TURNS: // Loiter N Times
do_loiter_turns(); do_loiter_turns();
break; break;
case MAV_CMD_NAV_LOITER_TIME: case MAV_CMD_NAV_LOITER_TIME:
do_loiter_time(); do_loiter_time();
break; break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH: case MAV_CMD_NAV_RETURN_TO_LAUNCH:
do_RTL(); do_RTL();
break; break;
default: default:
break; break;
} }
} }
static void static void
handle_process_condition_command() handle_process_condition_command()
{ {
gcs_send_text_fmt(PSTR("Executing command ID #%i"),next_nonnav_command.id); gcs_send_text_fmt(PSTR("Executing command ID #%i"),next_nonnav_command.id);
switch(next_nonnav_command.id){ switch(next_nonnav_command.id) {
case MAV_CMD_CONDITION_DELAY: case MAV_CMD_CONDITION_DELAY:
do_wait_delay(); do_wait_delay();
break; break;
case MAV_CMD_CONDITION_DISTANCE: case MAV_CMD_CONDITION_DISTANCE:
do_within_distance(); do_within_distance();
break; break;
case MAV_CMD_CONDITION_CHANGE_ALT: case MAV_CMD_CONDITION_CHANGE_ALT:
do_change_alt(); do_change_alt();
break; break;
default: default:
break; break;
} }
} }
static void handle_process_do_command() static void handle_process_do_command()
{ {
gcs_send_text_fmt(PSTR("Executing command ID #%i"),next_nonnav_command.id); gcs_send_text_fmt(PSTR("Executing command ID #%i"),next_nonnav_command.id);
switch(next_nonnav_command.id){ switch(next_nonnav_command.id) {
case MAV_CMD_DO_JUMP: case MAV_CMD_DO_JUMP:
do_jump(); do_jump();
break; break;
case MAV_CMD_DO_CHANGE_SPEED: case MAV_CMD_DO_CHANGE_SPEED:
do_change_speed(); do_change_speed();
break; break;
case MAV_CMD_DO_SET_HOME: case MAV_CMD_DO_SET_HOME:
do_set_home(); do_set_home();
break; break;
case MAV_CMD_DO_SET_SERVO: case MAV_CMD_DO_SET_SERVO:
do_set_servo(); do_set_servo();
break; break;
case MAV_CMD_DO_SET_RELAY: case MAV_CMD_DO_SET_RELAY:
do_set_relay(); do_set_relay();
break; break;
case MAV_CMD_DO_REPEAT_SERVO: case MAV_CMD_DO_REPEAT_SERVO:
do_repeat_servo(); do_repeat_servo();
break; break;
case MAV_CMD_DO_REPEAT_RELAY: case MAV_CMD_DO_REPEAT_RELAY:
do_repeat_relay(); do_repeat_relay();
break; break;
#if CAMERA == ENABLED #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| 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; 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)| 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; 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| 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|
break; break;
#endif #endif
#if MOUNT == ENABLED #if MOUNT == ENABLED
// Sets the region of interest (ROI) for a sensor set or the // Sets the region of interest (ROI) for a sensor set or the
// vehicle itself. This can then be used by the vehicles control // vehicle itself. This can then be used by the vehicles control
// system to control the vehicle attitude and the attitude of various // system to control the vehicle attitude and the attitude of various
// devices such as cameras. // 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| // |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_NAV_ROI: case MAV_CMD_NAV_ROI:
#if 0 #if 0
// send the command to the camera mount // send the command to the camera mount
camera_mount.set_roi_cmd(&command_nav_queue); camera_mount.set_roi_cmd(&command_nav_queue);
#else #else
gcs_send_text_P(SEVERITY_LOW, PSTR("DO_SET_ROI not supported")); gcs_send_text_P(SEVERITY_LOW, PSTR("DO_SET_ROI not supported"));
#endif #endif
break; break;
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| 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(); camera_mount.configure_cmd();
break; 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| 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(); camera_mount.control_cmd();
break; break;
#endif #endif
} }
} }
static void handle_no_commands() static void handle_no_commands()
{ {
gcs_send_text_fmt(PSTR("Returning to Home")); gcs_send_text_fmt(PSTR("Returning to Home"));
next_nav_command = home; next_nav_command = home;
next_nav_command.alt = read_alt_to_hold(); next_nav_command.alt = read_alt_to_hold();
next_nav_command.id = MAV_CMD_NAV_LOITER_UNLIM; next_nav_command.id = MAV_CMD_NAV_LOITER_UNLIM;
nav_command_ID = MAV_CMD_NAV_LOITER_UNLIM; nav_command_ID = MAV_CMD_NAV_LOITER_UNLIM;
non_nav_command_ID = WAIT_COMMAND; non_nav_command_ID = WAIT_COMMAND;
handle_process_nav_cmd(); handle_process_nav_cmd();
} }
@ -156,40 +156,40 @@ static void handle_no_commands()
// Verify command Handlers // Verify command Handlers
/********************************************************************************/ /********************************************************************************/
static bool verify_nav_command() // Returns true if command complete static bool verify_nav_command() // Returns true if command complete
{ {
switch(nav_command_ID) { switch(nav_command_ID) {
case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_TAKEOFF:
return verify_takeoff(); return verify_takeoff();
case MAV_CMD_NAV_LAND: case MAV_CMD_NAV_LAND:
return verify_land(); return verify_land();
case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_WAYPOINT:
return verify_nav_wp(); return verify_nav_wp();
case MAV_CMD_NAV_LOITER_UNLIM: case MAV_CMD_NAV_LOITER_UNLIM:
return verify_loiter_unlim(); return verify_loiter_unlim();
case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TURNS:
return verify_loiter_turns(); return verify_loiter_turns();
case MAV_CMD_NAV_LOITER_TIME: case MAV_CMD_NAV_LOITER_TIME:
return verify_loiter_time(); return verify_loiter_time();
case MAV_CMD_NAV_RETURN_TO_LAUNCH: case MAV_CMD_NAV_RETURN_TO_LAUNCH:
return verify_RTL(); return verify_RTL();
default: default:
gcs_send_text_P(SEVERITY_HIGH,PSTR("verify_nav: Invalid or no current Nav cmd")); gcs_send_text_P(SEVERITY_HIGH,PSTR("verify_nav: Invalid or no current Nav cmd"));
} }
return false; return false;
} }
static bool verify_condition_command() // Returns true if command complete static bool verify_condition_command() // Returns true if command complete
{ {
switch(non_nav_command_ID) { switch(non_nav_command_ID) {
case NO_COMMAND: case NO_COMMAND:
break; break;
@ -213,7 +213,7 @@ static bool verify_condition_command() // Returns true if command complete
default: default:
gcs_send_text_P(SEVERITY_HIGH,PSTR("verify_conditon: Invalid or no current Condition cmd")); gcs_send_text_P(SEVERITY_HIGH,PSTR("verify_conditon: Invalid or no current Condition cmd"));
break; break;
} }
return false; return false;
} }
@ -223,60 +223,60 @@ static bool verify_condition_command() // Returns true if command complete
static void do_RTL(void) static void do_RTL(void)
{ {
control_mode = RTL; control_mode = RTL;
crash_timer = 0; crash_timer = 0;
next_WP = home; next_WP = home;
// Altitude to hold over home // Altitude to hold over home
// Set by configuration tool // Set by configuration tool
// ------------------------- // -------------------------
next_WP.alt = read_alt_to_hold(); next_WP.alt = read_alt_to_hold();
if (g.log_bitmask & MASK_LOG_MODE) if (g.log_bitmask & MASK_LOG_MODE)
Log_Write_Mode(control_mode); Log_Write_Mode(control_mode);
} }
static void do_takeoff() static void do_takeoff()
{ {
set_next_WP(&next_nav_command); set_next_WP(&next_nav_command);
// pitch in deg, airspeed m/s, throttle %, track WP 1 or 0 // pitch in deg, airspeed m/s, throttle %, track WP 1 or 0
takeoff_pitch_cd = (int)next_nav_command.p1 * 100; takeoff_pitch_cd = (int)next_nav_command.p1 * 100;
//Serial.printf_P(PSTR("TO pitch:")); Serial.println(takeoff_pitch); //Serial.printf_P(PSTR("TO pitch:")); Serial.println(takeoff_pitch);
//Serial.printf_P(PSTR("home.alt:")); Serial.println(home.alt); //Serial.printf_P(PSTR("home.alt:")); Serial.println(home.alt);
takeoff_altitude = next_nav_command.alt; takeoff_altitude = next_nav_command.alt;
//Serial.printf_P(PSTR("takeoff_altitude:")); Serial.println(takeoff_altitude); //Serial.printf_P(PSTR("takeoff_altitude:")); Serial.println(takeoff_altitude);
next_WP.lat = home.lat + 1000; // so we don't have bad calcs next_WP.lat = home.lat + 1000; // so we don't have bad calcs
next_WP.lng = home.lng + 1000; // so we don't have bad calcs next_WP.lng = home.lng + 1000; // so we don't have bad calcs
takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction
// Flag also used to override "on the ground" throttle disable // Flag also used to override "on the ground" throttle disable
} }
static void do_nav_wp() static void do_nav_wp()
{ {
set_next_WP(&next_nav_command); set_next_WP(&next_nav_command);
} }
static void do_land() static void do_land()
{ {
set_next_WP(&next_nav_command); set_next_WP(&next_nav_command);
} }
static void do_loiter_unlimited() static void do_loiter_unlimited()
{ {
set_next_WP(&next_nav_command); set_next_WP(&next_nav_command);
} }
static void do_loiter_turns() static void do_loiter_turns()
{ {
set_next_WP(&next_nav_command); set_next_WP(&next_nav_command);
loiter_total = next_nav_command.p1 * 360; loiter_total = next_nav_command.p1 * 360;
} }
static void do_loiter_time() static void do_loiter_time()
{ {
set_next_WP(&next_nav_command); set_next_WP(&next_nav_command);
loiter_time_ms = millis(); loiter_time_ms = millis();
loiter_time_max_ms = next_nav_command.p1 * (uint32_t)1000; // units are seconds loiter_time_max_ms = next_nav_command.p1 * (uint32_t)1000; // units are seconds
} }
/********************************************************************************/ /********************************************************************************/
@ -284,143 +284,143 @@ static void do_loiter_time()
/********************************************************************************/ /********************************************************************************/
static bool verify_takeoff() static bool verify_takeoff()
{ {
if (ahrs.yaw_initialised()) { if (ahrs.yaw_initialised()) {
if (hold_course == -1) { if (hold_course == -1) {
// save our current course to take off // save our current course to take off
hold_course = ahrs.yaw_sensor; hold_course = ahrs.yaw_sensor;
gcs_send_text_fmt(PSTR("Holding course %ld"), hold_course); gcs_send_text_fmt(PSTR("Holding course %ld"), hold_course);
} }
} }
if (hold_course != -1) { if (hold_course != -1) {
// recalc bearing error with hold_course; // recalc bearing error with hold_course;
nav_bearing_cd = hold_course; nav_bearing_cd = hold_course;
// recalc bearing error // recalc bearing error
calc_bearing_error(); calc_bearing_error();
} }
if (current_loc.alt > takeoff_altitude) { if (current_loc.alt > takeoff_altitude) {
hold_course = -1; hold_course = -1;
takeoff_complete = true; takeoff_complete = true;
return true; return true;
} else { } else {
return false; return false;
} }
} }
// we are executing a landing // we are executing a landing
static bool verify_land() static bool verify_land()
{ {
// we don't 'verify' landing in the sense that it never completes, // we don't 'verify' landing in the sense that it never completes,
// so we don't verify command completion. Instead we use this to // so we don't verify command completion. Instead we use this to
// adjust final landing parameters // adjust final landing parameters
// Set land_complete if we are within 2 seconds distance or within // Set land_complete if we are within 2 seconds distance or within
// 3 meters altitude of the landing point // 3 meters altitude of the landing point
if (((wp_distance > 0) && (wp_distance <= (g.land_flare_sec*g_gps->ground_speed*0.01))) if (((wp_distance > 0) && (wp_distance <= (g.land_flare_sec*g_gps->ground_speed*0.01)))
|| (current_loc.alt <= next_WP.alt + g.land_flare_alt*100)) { || (current_loc.alt <= next_WP.alt + g.land_flare_alt*100)) {
land_complete = true; land_complete = true;
if (hold_course == -1) { if (hold_course == -1) {
// we have just reached the threshold of to flare for landing. // we have just reached the threshold of to flare for landing.
// We now don't want to do any radical // We now don't want to do any radical
// turns, as rolling could put the wings into the runway. // turns, as rolling could put the wings into the runway.
// To prevent further turns we set hold_course to the // To prevent further turns we set hold_course to the
// current heading. Previously we set this to // current heading. Previously we set this to
// crosstrack_bearing, but the xtrack bearing can easily // crosstrack_bearing, but the xtrack bearing can easily
// be quite large at this point, and that could induce a // be quite large at this point, and that could induce a
// sudden large roll correction which is very nasty at // sudden large roll correction which is very nasty at
// this point in the landing. // this point in the landing.
hold_course = ahrs.yaw_sensor; hold_course = ahrs.yaw_sensor;
gcs_send_text_fmt(PSTR("Land Complete - Hold course %ld"), hold_course); gcs_send_text_fmt(PSTR("Land Complete - Hold course %ld"), hold_course);
} }
// reload any airspeed or groundspeed parameters that may have // reload any airspeed or groundspeed parameters that may have
// been set for landing // been set for landing
g.airspeed_cruise_cm.load(); g.airspeed_cruise_cm.load();
g.min_gndspeed_cm.load(); g.min_gndspeed_cm.load();
g.throttle_cruise.load(); g.throttle_cruise.load();
} }
if (hold_course != -1) { if (hold_course != -1) {
// recalc bearing error with hold_course; // recalc bearing error with hold_course;
nav_bearing_cd = hold_course; nav_bearing_cd = hold_course;
// recalc bearing error // recalc bearing error
calc_bearing_error(); calc_bearing_error();
} }
update_crosstrack(); update_crosstrack();
return false; return false;
} }
static bool verify_nav_wp() static bool verify_nav_wp()
{ {
hold_course = -1; hold_course = -1;
update_crosstrack(); update_crosstrack();
if ((wp_distance > 0) && (wp_distance <= g.waypoint_radius)) { if ((wp_distance > 0) && (wp_distance <= g.waypoint_radius)) {
gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"), gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"),
(unsigned)nav_command_index,
(unsigned)get_distance(&current_loc, &next_WP));
return true;
}
// have we circled around the waypoint?
if (loiter_sum > 300){
gcs_send_text_P(SEVERITY_MEDIUM,PSTR("Missed WP"));
return true;
}
// have we flown past the waypoint?
if (location_passed_point(current_loc, prev_WP, next_WP)) {
gcs_send_text_fmt(PSTR("Passed Waypoint #%i dist %um"),
(unsigned)nav_command_index, (unsigned)nav_command_index,
(unsigned)get_distance(&current_loc, &next_WP)); (unsigned)get_distance(&current_loc, &next_WP));
return true; return true;
} }
return false; // have we circled around the waypoint?
if (loiter_sum > 300) {
gcs_send_text_P(SEVERITY_MEDIUM,PSTR("Missed WP"));
return true;
}
// have we flown past the waypoint?
if (location_passed_point(current_loc, prev_WP, next_WP)) {
gcs_send_text_fmt(PSTR("Passed Waypoint #%i dist %um"),
(unsigned)nav_command_index,
(unsigned)get_distance(&current_loc, &next_WP));
return true;
}
return false;
} }
static bool verify_loiter_unlim() static bool verify_loiter_unlim()
{ {
update_loiter(); update_loiter();
calc_bearing_error(); calc_bearing_error();
return false; return false;
} }
static bool verify_loiter_time() static bool verify_loiter_time()
{ {
update_loiter(); update_loiter();
calc_bearing_error(); calc_bearing_error();
if ((millis() - loiter_time_ms) > loiter_time_max_ms) { if ((millis() - loiter_time_ms) > loiter_time_max_ms) {
gcs_send_text_P(SEVERITY_LOW,PSTR("verify_nav: LOITER time complete")); gcs_send_text_P(SEVERITY_LOW,PSTR("verify_nav: LOITER time complete"));
return true; return true;
} }
return false; return false;
} }
static bool verify_loiter_turns() static bool verify_loiter_turns()
{ {
update_loiter(); update_loiter();
calc_bearing_error(); calc_bearing_error();
if(loiter_sum > loiter_total) { if(loiter_sum > loiter_total) {
loiter_total = 0; loiter_total = 0;
gcs_send_text_P(SEVERITY_LOW,PSTR("verify_nav: LOITER orbits complete")); gcs_send_text_P(SEVERITY_LOW,PSTR("verify_nav: LOITER orbits complete"));
// clear the command queue; // clear the command queue;
return true; return true;
} }
return false; return false;
} }
static bool verify_RTL() static bool verify_RTL()
{ {
if (wp_distance <= g.waypoint_radius) { if (wp_distance <= g.waypoint_radius) {
gcs_send_text_P(SEVERITY_LOW,PSTR("Reached home")); gcs_send_text_P(SEVERITY_LOW,PSTR("Reached home"));
return true; return true;
}else{ }else{
return false; return false;
} }
} }
/********************************************************************************/ /********************************************************************************/
@ -429,23 +429,23 @@ static bool verify_RTL()
static void do_wait_delay() static void do_wait_delay()
{ {
condition_start = millis(); condition_start = millis();
condition_value = next_nonnav_command.lat * 1000; // convert to milliseconds condition_value = next_nonnav_command.lat * 1000; // convert to milliseconds
} }
static void do_change_alt() static void do_change_alt()
{ {
condition_rate = labs((int)next_nonnav_command.lat); condition_rate = labs((int)next_nonnav_command.lat);
condition_value = next_nonnav_command.alt; condition_value = next_nonnav_command.alt;
if(condition_value < current_loc.alt) condition_rate = -condition_rate; if(condition_value < current_loc.alt) condition_rate = -condition_rate;
target_altitude_cm = current_loc.alt + (condition_rate / 10); // Divide by ten for 10Hz update target_altitude_cm = current_loc.alt + (condition_rate / 10); // Divide by ten for 10Hz update
next_WP.alt = condition_value; // For future nav calculations next_WP.alt = condition_value; // For future nav calculations
offset_altitude_cm = 0; // For future nav calculations offset_altitude_cm = 0; // For future nav calculations
} }
static void do_within_distance() static void do_within_distance()
{ {
condition_value = next_nonnav_command.lat; condition_value = next_nonnav_command.lat;
} }
/********************************************************************************/ /********************************************************************************/
@ -454,30 +454,30 @@ static void do_within_distance()
static bool verify_wait_delay() static bool verify_wait_delay()
{ {
if ((unsigned)(millis() - condition_start) > (unsigned)condition_value){ if ((unsigned)(millis() - condition_start) > (unsigned)condition_value) {
condition_value = 0; condition_value = 0;
return true; return true;
} }
return false; return false;
} }
static bool verify_change_alt() static bool verify_change_alt()
{ {
if( (condition_rate>=0 && current_loc.alt >= condition_value) || (condition_rate<=0 && current_loc.alt <= condition_value)) { if( (condition_rate>=0 && current_loc.alt >= condition_value) || (condition_rate<=0 && current_loc.alt <= condition_value)) {
condition_value = 0; condition_value = 0;
return true; return true;
} }
target_altitude_cm += condition_rate / 10; target_altitude_cm += condition_rate / 10;
return false; return false;
} }
static bool verify_within_distance() static bool verify_within_distance()
{ {
if (wp_distance < condition_value){ if (wp_distance < condition_value) {
condition_value = 0; condition_value = 0;
return true; return true;
} }
return false; return false;
} }
/********************************************************************************/ /********************************************************************************/
@ -486,122 +486,122 @@ static bool verify_within_distance()
static void do_loiter_at_location() static void do_loiter_at_location()
{ {
next_WP = current_loc; next_WP = current_loc;
} }
static void do_jump() static void do_jump()
{ {
struct Location temp; struct Location temp;
gcs_send_text_fmt(PSTR("Jump to WP %u. Jumps left: %d"), gcs_send_text_fmt(PSTR("Jump to WP %u. Jumps left: %d"),
(unsigned)next_nonnav_command.p1, (unsigned)next_nonnav_command.p1,
(int)next_nonnav_command.lat); (int)next_nonnav_command.lat);
if (next_nonnav_command.lat > 0) { if (next_nonnav_command.lat > 0) {
nav_command_ID = NO_COMMAND; nav_command_ID = NO_COMMAND;
next_nav_command.id = NO_COMMAND; next_nav_command.id = NO_COMMAND;
non_nav_command_ID = NO_COMMAND; non_nav_command_ID = NO_COMMAND;
temp = get_cmd_with_index(g.command_index); temp = get_cmd_with_index(g.command_index);
temp.lat = next_nonnav_command.lat - 1; // Decrement repeat counter temp.lat = next_nonnav_command.lat - 1; // Decrement repeat counter
set_cmd_with_index(temp, g.command_index); set_cmd_with_index(temp, g.command_index);
gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1); gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1);
g.command_index.set_and_save(next_nonnav_command.p1 - 1); g.command_index.set_and_save(next_nonnav_command.p1 - 1);
nav_command_index = next_nonnav_command.p1 - 1; nav_command_index = next_nonnav_command.p1 - 1;
next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump
process_next_command(); process_next_command();
} else if (next_nonnav_command.lat == -1) { // A repeat count of -1 = repeat forever } else if (next_nonnav_command.lat == -1) { // A repeat count of -1 = repeat forever
nav_command_ID = NO_COMMAND; nav_command_ID = NO_COMMAND;
non_nav_command_ID = NO_COMMAND; non_nav_command_ID = NO_COMMAND;
gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1); gcs_send_text_fmt(PSTR("setting command index: %i"),next_nonnav_command.p1 - 1);
g.command_index.set_and_save(next_nonnav_command.p1 - 1); g.command_index.set_and_save(next_nonnav_command.p1 - 1);
nav_command_index = next_nonnav_command.p1 - 1; nav_command_index = next_nonnav_command.p1 - 1;
next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump next_WP = prev_WP; // Need to back "next_WP" up as it was set to the next waypoint following the jump
process_next_command(); process_next_command();
} }
} }
static void do_change_speed() static void do_change_speed()
{ {
switch (next_nonnav_command.p1) switch (next_nonnav_command.p1)
{ {
case 0: // Airspeed case 0: // Airspeed
if (next_nonnav_command.alt > 0) { if (next_nonnav_command.alt > 0) {
g.airspeed_cruise_cm.set(next_nonnav_command.alt * 100); g.airspeed_cruise_cm.set(next_nonnav_command.alt * 100);
gcs_send_text_fmt(PSTR("Set airspeed %u m/s"), (unsigned)next_nonnav_command.alt); gcs_send_text_fmt(PSTR("Set airspeed %u m/s"), (unsigned)next_nonnav_command.alt);
} }
break; break;
case 1: // Ground speed case 1: // Ground speed
g.min_gndspeed_cm.set(next_nonnav_command.alt * 100); g.min_gndspeed_cm.set(next_nonnav_command.alt * 100);
break; break;
} }
if(next_nonnav_command.lat > 0) if(next_nonnav_command.lat > 0)
g.throttle_cruise.set(next_nonnav_command.lat); g.throttle_cruise.set(next_nonnav_command.lat);
} }
static void do_set_home() static void do_set_home()
{ {
if(next_nonnav_command.p1 == 1 && GPS_enabled) { if(next_nonnav_command.p1 == 1 && GPS_enabled) {
init_home(); init_home();
} else { } else {
home.id = MAV_CMD_NAV_WAYPOINT; home.id = MAV_CMD_NAV_WAYPOINT;
home.lng = next_nonnav_command.lng; // Lon * 10**7 home.lng = next_nonnav_command.lng; // Lon * 10**7
home.lat = next_nonnav_command.lat; // Lat * 10**7 home.lat = next_nonnav_command.lat; // Lat * 10**7
home.alt = max(next_nonnav_command.alt, 0); home.alt = max(next_nonnav_command.alt, 0);
home_is_set = true; home_is_set = true;
} }
} }
static void do_set_servo() static void do_set_servo()
{ {
APM_RC.OutputCh(next_nonnav_command.p1 - 1, next_nonnav_command.alt); APM_RC.OutputCh(next_nonnav_command.p1 - 1, next_nonnav_command.alt);
} }
static void do_set_relay() static void do_set_relay()
{ {
if (next_nonnav_command.p1 == 1) { if (next_nonnav_command.p1 == 1) {
relay.on(); relay.on();
} else if (next_nonnav_command.p1 == 0) { } else if (next_nonnav_command.p1 == 0) {
relay.off(); relay.off();
}else{ }else{
relay.toggle(); relay.toggle();
} }
} }
static void do_repeat_servo() static void do_repeat_servo()
{ {
event_id = next_nonnav_command.p1 - 1; event_id = next_nonnav_command.p1 - 1;
if(next_nonnav_command.p1 >= CH_5 + 1 && next_nonnav_command.p1 <= CH_8 + 1) { if(next_nonnav_command.p1 >= CH_5 + 1 && next_nonnav_command.p1 <= CH_8 + 1) {
event_timer_ms = 0; event_timer_ms = 0;
event_delay_ms = next_nonnav_command.lng * 500.0; // /2 (half cycle time) * 1000 (convert to milliseconds) event_delay_ms = next_nonnav_command.lng * 500.0; // /2 (half cycle time) * 1000 (convert to milliseconds)
event_repeat = next_nonnav_command.lat * 2; event_repeat = next_nonnav_command.lat * 2;
event_value = next_nonnav_command.alt; event_value = next_nonnav_command.alt;
switch(next_nonnav_command.p1) { switch(next_nonnav_command.p1) {
case CH_5: case CH_5:
event_undo_value = g.rc_5.radio_trim; event_undo_value = g.rc_5.radio_trim;
break; break;
case CH_6: case CH_6:
event_undo_value = g.rc_6.radio_trim; event_undo_value = g.rc_6.radio_trim;
break; break;
case CH_7: case CH_7:
event_undo_value = g.rc_7.radio_trim; event_undo_value = g.rc_7.radio_trim;
break; break;
case CH_8: case CH_8:
event_undo_value = g.rc_8.radio_trim; event_undo_value = g.rc_8.radio_trim;
break; break;
} }
update_events(); update_events();
} }
} }
static void do_repeat_relay() static void do_repeat_relay()
{ {
event_id = RELAY_TOGGLE; event_id = RELAY_TOGGLE;
event_timer_ms = 0; event_timer_ms = 0;
event_delay_ms = next_nonnav_command.lat * 500.0; // /2 (half cycle time) * 1000 (convert to milliseconds) event_delay_ms = next_nonnav_command.lat * 500.0; // /2 (half cycle time) * 1000 (convert to milliseconds)
event_repeat = next_nonnav_command.alt * 2; event_repeat = next_nonnav_command.alt * 2;
update_events(); update_events();
} }