mirror of https://github.com/ArduPilot/ardupilot
uncrustify ArduPlane/commands_logic.pde
This commit is contained in:
parent
58381e0d8e
commit
8e3fe50338
|
@ -12,7 +12,7 @@ handle_process_nav_cmd()
|
|||
reset_I();
|
||||
|
||||
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:
|
||||
do_takeoff();
|
||||
|
@ -51,7 +51,7 @@ static void
|
|||
handle_process_condition_command()
|
||||
{
|
||||
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:
|
||||
do_wait_delay();
|
||||
|
@ -73,7 +73,7 @@ handle_process_condition_command()
|
|||
static void handle_process_do_command()
|
||||
{
|
||||
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:
|
||||
do_jump();
|
||||
|
@ -121,12 +121,12 @@ static void handle_process_do_command()
|
|||
// 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_NAV_ROI:
|
||||
#if 0
|
||||
#if 0
|
||||
// send the command to the camera mount
|
||||
camera_mount.set_roi_cmd(&command_nav_queue);
|
||||
#else
|
||||
#else
|
||||
gcs_send_text_P(SEVERITY_LOW, PSTR("DO_SET_ROI not supported"));
|
||||
#endif
|
||||
#endif
|
||||
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|
|
||||
|
@ -366,7 +366,7 @@ static bool verify_nav_wp()
|
|||
}
|
||||
|
||||
// have we circled around the waypoint?
|
||||
if (loiter_sum > 300){
|
||||
if (loiter_sum > 300) {
|
||||
gcs_send_text_P(SEVERITY_MEDIUM,PSTR("Missed WP"));
|
||||
return true;
|
||||
}
|
||||
|
@ -454,7 +454,7 @@ static void do_within_distance()
|
|||
|
||||
static bool verify_wait_delay()
|
||||
{
|
||||
if ((unsigned)(millis() - condition_start) > (unsigned)condition_value){
|
||||
if ((unsigned)(millis() - condition_start) > (unsigned)condition_value) {
|
||||
condition_value = 0;
|
||||
return true;
|
||||
}
|
||||
|
@ -473,7 +473,7 @@ static bool verify_change_alt()
|
|||
|
||||
static bool verify_within_distance()
|
||||
{
|
||||
if (wp_distance < condition_value){
|
||||
if (wp_distance < condition_value) {
|
||||
condition_value = 0;
|
||||
return true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue