mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
Clean up formatting for AP_Common
This commit is contained in:
parent
02ab5bea78
commit
585507f188
@ -2,10 +2,11 @@
|
||||
function format {
|
||||
DIR=$1
|
||||
find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec astyle {} \;
|
||||
find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec rm {}.orig \;
|
||||
find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec rm -f {}.orig \;
|
||||
}
|
||||
|
||||
format apo
|
||||
format ArduRover
|
||||
format ArduBoat
|
||||
format libraries/APO
|
||||
format libraries/AP_Common
|
||||
|
@ -302,14 +302,18 @@ public:
|
||||
///
|
||||
/// @return The parent group, or NULL if the variable is not grouped.
|
||||
///
|
||||
AP_Var_group *group(void) { return _group; }
|
||||
AP_Var_group *group(void) {
|
||||
return _group;
|
||||
}
|
||||
|
||||
/// Returns the first variable in the global list.
|
||||
///
|
||||
/// @return The first variable in the global list, or NULL if
|
||||
/// there are none.
|
||||
///
|
||||
static AP_Var *first(void) { return _variables; }
|
||||
static AP_Var *first(void) {
|
||||
return _variables;
|
||||
}
|
||||
|
||||
/// Returns the next variable in the global list.
|
||||
///
|
||||
@ -367,7 +371,9 @@ public:
|
||||
///
|
||||
/// @return The sum of sizeof(*this) for all constructed AP_Var subclass instances.
|
||||
///
|
||||
static uint16_t get_memory_use() { return _bytes_in_use; }
|
||||
static uint16_t get_memory_use() {
|
||||
return _bytes_in_use;
|
||||
}
|
||||
|
||||
protected:
|
||||
// Memory statistics
|
||||
|
Loading…
Reference in New Issue
Block a user