mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
uncrustify ArduPlane/commands.pde
This commit is contained in:
parent
43991712be
commit
ff4afa767b
@ -1,6 +1,6 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
/*
|
/*
|
||||||
logic for dealing with the current command in the mission and home location
|
* logic for dealing with the current command in the mission and home location
|
||||||
*/
|
*/
|
||||||
|
|
||||||
static void init_commands()
|
static void init_commands()
|
||||||
@ -90,7 +90,7 @@ static void set_cmd_with_index(struct Location temp, int16_t i)
|
|||||||
|
|
||||||
// Set altitude options bitmask
|
// Set altitude options bitmask
|
||||||
// XXX What is this trying to do?
|
// XXX What is this trying to do?
|
||||||
if (temp.options & MASK_OPTIONS_RELATIVE_ALT && i != 0){
|
if (temp.options & MASK_OPTIONS_RELATIVE_ALT && i != 0) {
|
||||||
temp.options = MASK_OPTIONS_RELATIVE_ALT;
|
temp.options = MASK_OPTIONS_RELATIVE_ALT;
|
||||||
} else {
|
} else {
|
||||||
temp.options = 0;
|
temp.options = 0;
|
||||||
@ -131,9 +131,9 @@ static int32_t read_alt_to_hold()
|
|||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
This function stores waypoint commands
|
* This function stores waypoint commands
|
||||||
It looks to see what the next command type is and finds the last command.
|
* It looks to see what the next command type is and finds the last command.
|
||||||
*/
|
*/
|
||||||
static void set_next_WP(struct Location *wp)
|
static void set_next_WP(struct Location *wp)
|
||||||
{
|
{
|
||||||
// copy the current WP into the OldWP slot
|
// copy the current WP into the OldWP slot
|
||||||
|
Loading…
Reference in New Issue
Block a user