Clean up formatting for AP_Common

This commit is contained in:
James Goppert 2011-10-28 14:43:43 -04:00
parent 02ab5bea78
commit 585507f188
9 changed files with 264 additions and 257 deletions

View File

@ -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

View File

@ -26,7 +26,7 @@
// auto-detect at compile time if a call to a string function is using
// a flash-stored string or not
typedef struct {
char c;
char c;
} prog_char_t;
#include <stdint.h>
@ -97,17 +97,17 @@ typedef struct {
static inline int strcasecmp_P(const char *str1, const prog_char_t *pstr)
{
return strcasecmp_P(str1, (const prog_char *)pstr);
return strcasecmp_P(str1, (const prog_char *)pstr);
}
static inline int strcmp_P(const char *str1, const prog_char_t *pstr)
{
return strcmp_P(str1, (const prog_char *)pstr);
return strcmp_P(str1, (const prog_char *)pstr);
}
static inline size_t strlcat_P(char *buffer, const prog_char_t *pstr, size_t buffer_size)
{
return strlcat_P(buffer, (const prog_char *)pstr, buffer_size);
return strlcat_P(buffer, (const prog_char *)pstr, buffer_size);
}
//@}
@ -145,12 +145,12 @@ static inline size_t strlcat_P(char *buffer, const prog_char_t *pstr, size_t buf
//@{
struct Location {
uint8_t id; ///< command id
uint8_t options; ///< options bitmask (1<<0 = relative altitude)
uint8_t p1; ///< param 1
int32_t alt; ///< param 2 - Altitude in centimeters (meters * 100)
int32_t lat; ///< param 3 - Lattitude * 10**7
int32_t lng; ///< param 4 - Longitude * 10**7
uint8_t id; ///< command id
uint8_t options; ///< options bitmask (1<<0 = relative altitude)
uint8_t p1; ///< param 1
int32_t alt; ///< param 2 - Altitude in centimeters (meters * 100)
int32_t lat; ///< param 3 - Lattitude * 10**7
int32_t lng; ///< param 4 - Longitude * 10**7
};
//@}

View File

@ -68,8 +68,8 @@ private:
/// Constructor
///
Test::Test(const char *name) :
_name(name),
_fail(false)
_name(name),
_fail(false)
{
}

View File

@ -40,10 +40,10 @@ uint16_t AP_Var::_bytes_in_use;
// Constructor for standalone variables
//
AP_Var::AP_Var(Key p_key, const prog_char_t *name, Flags flags) :
_group(NULL),
_key(p_key | k_key_not_located),
_name(name),
_flags(flags)
_group(NULL),
_key(p_key | k_key_not_located),
_name(name),
_flags(flags)
{
// Insert the variable or group into the list of known variables, unless
// it wants to be unlisted.
@ -57,10 +57,10 @@ AP_Var::AP_Var(Key p_key, const prog_char_t *name, Flags flags) :
// Constructor for variables in a group
//
AP_Var::AP_Var(AP_Var_group *pGroup, Key index, const prog_char_t *name, Flags flags) :
_group(pGroup),
_key(index),
_name(name),
_flags(flags)
_group(pGroup),
_key(index),
_name(name),
_flags(flags)
{
AP_Var **vp;
@ -76,10 +76,10 @@ AP_Var::AP_Var(AP_Var_group *pGroup, Key index, const prog_char_t *name, Flags f
size_t loopCount = 0;
while (*vp != NULL) {
if (loopCount++>k_num_max) return;
if (loopCount++>k_num_max) return;
if ((*vp)->_key >= _key) {
break;
break;
}
vp = &((*vp)->_link);
}
@ -106,17 +106,17 @@ AP_Var::~AP_Var(void)
// Scan the list and remove this if we find it
{
size_t loopCount = 0;
while (*vp) {
size_t loopCount = 0;
while (*vp) {
if (loopCount++>k_num_max) return;
if (loopCount++>k_num_max) return;
if (*vp == this) {
*vp = _link;
break;
}
vp = &((*vp)->_link);
}
if (*vp == this) {
*vp = _link;
break;
}
vp = &((*vp)->_link);
}
}
// If we are destroying a group, remove all its variables from the list
@ -129,7 +129,7 @@ AP_Var::~AP_Var(void)
while (*vp) {
if (loopCount++>k_num_max) return;
if (loopCount++>k_num_max) return;
// Does the variable claim us as its group?
if ((*vp)->_group == this) {
@ -166,7 +166,7 @@ AP_Var::find(const char *name)
for (vp = first(); vp; vp = vp->next()) {
if (loopCount++>k_num_max) return NULL;
if (loopCount++>k_num_max) return NULL;
char name_buffer[32];
@ -189,7 +189,7 @@ AP_Var::find(Key key)
AP_Var *vp;
size_t loopCount = 0;
for (vp = first(); vp; vp = vp->next()) {
if (loopCount++>k_num_max) return NULL;
if (loopCount++>k_num_max) return NULL;
if (key == vp->key()) {
return vp;
}
@ -242,7 +242,7 @@ bool AP_Var::save(void)
newv = eeprom_read_byte(ep);
if (newv != vbuf[i]) {
serialDebug("readback failed at offset %p: got %u, expected %u",
ep, newv, vbuf[i]);
ep, newv, vbuf[i]);
return false;
}
}
@ -304,10 +304,10 @@ bool AP_Var::save_all(void)
while (vp) {
if (loopCount++>k_num_max) return false;
if (loopCount++>k_num_max) return false;
if (!vp->has_flags(k_flag_no_auto_load) && // not opted out of autosave
(vp->_key != k_key_none)) { // has a key
(vp->_key != k_key_none)) { // has a key
if (!vp->save()) {
result = false;
@ -329,10 +329,10 @@ bool AP_Var::load_all(void)
while (vp) {
if (loopCount++>k_num_max) return false;
if (loopCount++>k_num_max) return false;
if (!vp->has_flags(k_flag_no_auto_load) && // not opted out of autoload
(vp->_key != k_key_none)) { // has a key
(vp->_key != k_key_none)) { // has a key
if (!vp->load()) {
result = false;
@ -365,7 +365,7 @@ AP_Var::erase_all()
while (vp) {
if (loopCount++>k_num_max) return;
if (loopCount++>k_num_max) return;
vp->_key = vp->key() | k_key_not_located;
vp = vp->_link;
@ -449,7 +449,7 @@ AP_Var::first_member(AP_Var_group *group)
while (*vp) {
if (loopCount++>k_num_max) return NULL;
if (loopCount++>k_num_max) return NULL;
serialDebug("consider %p with %p", *vp, (*vp)->_group);
if ((*vp)->_group == group) {
@ -471,7 +471,7 @@ AP_Var::next_member()
while (vp) {
if (loopCount++>k_num_max) return NULL;
if (loopCount++>k_num_max) return NULL;
if (vp->_group == _group) {
return vp;
@ -498,7 +498,7 @@ bool AP_Var::_EEPROM_scan(void)
eeprom_address = 0;
eeprom_read_block(&ee_header, (void *)eeprom_address, sizeof(ee_header));
if ((ee_header.magic != k_EEPROM_magic) ||
(ee_header.revision != k_EEPROM_revision)) {
(ee_header.revision != k_EEPROM_revision)) {
serialDebug("no header, magic 0x%x revision %u", ee_header.magic, ee_header.revision);
return false;
@ -514,7 +514,7 @@ bool AP_Var::_EEPROM_scan(void)
while (eeprom_address < (k_EEPROM_size - sizeof(var_header) - 1)) {
if (loopCount++>k_num_max) return NULL;
if (loopCount++>k_num_max) return NULL;
// Read a variable header
//
@ -531,10 +531,10 @@ bool AP_Var::_EEPROM_scan(void)
// Sanity-check the variable header and abort if it looks bad
//
if (k_EEPROM_size <= (
eeprom_address + // current position
sizeof(var_header) + // header for this variable
var_header.size + 1 + // data for this variable
sizeof(var_header))) { // header for sentinel
eeprom_address + // current position
sizeof(var_header) + // header for this variable
var_header.size + 1 + // data for this variable
sizeof(var_header))) { // header for sentinel
serialDebug("header overruns EEPROM");
return false;
@ -544,7 +544,7 @@ bool AP_Var::_EEPROM_scan(void)
vp = _variables;
size_t loopCount2 = 0;
while(vp) {
if (loopCount2++>k_num_max) return false;
if (loopCount2++>k_num_max) return false;
if (vp->key() == var_header.key) {
// adjust the variable's key to point to this entry
vp->_key = eeprom_address + sizeof(var_header);
@ -572,7 +572,7 @@ bool AP_Var::_EEPROM_scan(void)
vp = _variables;
size_t loopCount3 = 0;
while(vp) {
if (loopCount3++>k_num_max) return false;
if (loopCount3++>k_num_max) return false;
if (vp->_key & k_key_not_located) {
vp->_key |= k_key_not_allocated;
serialDebug("key %u not allocated", vp->key());
@ -661,7 +661,7 @@ bool AP_Var::_EEPROM_locate(bool allocate)
ee_header.spare = 0;
eeprom_write_block(&ee_header, (void *)0, sizeof(ee_header));
_tail_sentinel = sizeof(ee_header);
// Write a variable-sized pad header with a reserved key value
@ -737,7 +737,7 @@ AP_Var_group::_serialize_unserialize(void *buf, size_t buf_size, bool do_seriali
while (vp) {
if (loopCount++>k_num_max) return false;
if (loopCount++>k_num_max) return false;
// (un)serialise the group member
if (do_serialize) {

View File

@ -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

View File

@ -14,29 +14,29 @@
void * operator new(size_t size)
{
#ifdef AP_DISPLAYMEM
displayMemory();
displayMemory();
#endif
return(calloc(size, 1));
return(calloc(size, 1));
}
void operator delete(void *p)
{
if (p) free(p);
if (p) free(p);
}
extern "C" void __cxa_pure_virtual()
{
while (1)
{
Serial.println("Error: pure virtual call");
delay(1000);
}
while (1)
{
Serial.println("Error: pure virtual call");
delay(1000);
}
}
void * operator new[](size_t size)
{
#ifdef AP_DISPLAYMEM
displayMemory();
displayMemory();
#endif
return(calloc(size, 1));
}
@ -50,12 +50,12 @@ __extension__ typedef int __guard __attribute__((mode (__DI__)));
int __cxa_guard_acquire(__guard *g)
{
return !*(char *)(g);
return !*(char *)(g);
};
void __cxa_guard_release (__guard *g)
{
*(char *)g = 1;
*(char *)g = 1;
};
void __cxa_guard_abort (__guard *) {};

View File

@ -7,24 +7,24 @@ FastSerialPort0(Serial);
int8_t
menu_test(uint8_t argc, const Menu::arg *argv)
{
int i;
int i;
Serial.printf("This is a test with %d arguments\n", argc);
for (i = 1; i < argc; i++) {
Serial.printf("%d: int %ld float ", i, argv[i].i);
Serial.println(argv[i].f, 6); // gross
}
Serial.printf("This is a test with %d arguments\n", argc);
for (i = 1; i < argc; i++) {
Serial.printf("%d: int %ld float ", i, argv[i].i);
Serial.println(argv[i].f, 6); // gross
}
}
int8_t
menu_auto(uint8_t argc, const Menu::arg *argv)
{
Serial.println("auto text");
Serial.println("auto text");
}
const struct Menu::command top_menu_commands[] PROGMEM = {
{"*", menu_auto},
{"test", menu_test},
{"*", menu_auto},
{"test", menu_test},
};
MENU(top, "menu", top_menu_commands);
@ -32,8 +32,8 @@ MENU(top, "menu", top_menu_commands);
void
setup(void)
{
Serial.begin(38400);
top.run();
Serial.begin(38400);
top.run();
}
void

View File

@ -23,101 +23,101 @@
/// Class defining and handling one menu tree
class Menu {
public:
/// argument passed to a menu function
///
/// Space-delimited arguments are parsed from the commandline and
/// separated into these structures.
///
/// If the argument cannot be parsed as a float or a long, the value
/// of f or i respectively is undefined. You should range-check
/// the inputs to your function.
///
struct arg {
const char *str; ///< string form of the argument
long i; ///< integer form of the argument (if a number)
float f; ///< floating point form of the argument (if a number)
};
/// argument passed to a menu function
///
/// Space-delimited arguments are parsed from the commandline and
/// separated into these structures.
///
/// If the argument cannot be parsed as a float or a long, the value
/// of f or i respectively is undefined. You should range-check
/// the inputs to your function.
///
struct arg {
const char *str; ///< string form of the argument
long i; ///< integer form of the argument (if a number)
float f; ///< floating point form of the argument (if a number)
};
/// menu command function
///
/// Functions called by menu array entries are expected to be of this
/// type.
///
/// @param argc The number of valid arguments, including the
/// name of the command in argv[0]. Will never be
/// more than MENU_ARGS_MAX.
/// @param argv Pointer to an array of Menu::arg structures
/// detailing any optional arguments given to the
/// command. argv[0] is always the name of the
/// command, so that the same function can be used
/// to handle more than one command.
///
typedef int8_t (*func)(uint8_t argc, const struct arg *argv);
/// menu command function
///
/// Functions called by menu array entries are expected to be of this
/// type.
///
/// @param argc The number of valid arguments, including the
/// name of the command in argv[0]. Will never be
/// more than MENU_ARGS_MAX.
/// @param argv Pointer to an array of Menu::arg structures
/// detailing any optional arguments given to the
/// command. argv[0] is always the name of the
/// command, so that the same function can be used
/// to handle more than one command.
///
typedef int8_t (*func)(uint8_t argc, const struct arg *argv);
/// menu pre-prompt function
///
/// Called immediately before waiting for the user to type a command; can be
/// used to display help text or status, for example.
///
/// If this function returns false, the menu exits.
///
typedef bool (*preprompt)(void);
/// menu pre-prompt function
///
/// Called immediately before waiting for the user to type a command; can be
/// used to display help text or status, for example.
///
/// If this function returns false, the menu exits.
///
typedef bool (*preprompt)(void);
/// menu command description
///
struct command {
/// Name of the command, as typed or received.
/// Command names are limited in size to keep this structure compact.
///
const char command[MENU_COMMAND_MAX];
/// menu command description
///
struct command {
/// Name of the command, as typed or received.
/// Command names are limited in size to keep this structure compact.
///
const char command[MENU_COMMAND_MAX];
/// The function to call when the command is received.
///
/// The argc argument will be at least 1, and no more than
/// MENU_ARGS_MAX. The argv array will be populated with
/// arguments typed/received up to MENU_ARGS_MAX. The command
/// name will always be in argv[0].
///
/// Commands may return -2 to cause the menu itself to exit.
/// The "?", "help" and "exit" commands are always defined, but
/// can be overridden by explicit entries in the command array.
///
int8_t (*func)(uint8_t argc, const struct arg *argv); ///< callback function
};
/// The function to call when the command is received.
///
/// The argc argument will be at least 1, and no more than
/// MENU_ARGS_MAX. The argv array will be populated with
/// arguments typed/received up to MENU_ARGS_MAX. The command
/// name will always be in argv[0].
///
/// Commands may return -2 to cause the menu itself to exit.
/// The "?", "help" and "exit" commands are always defined, but
/// can be overridden by explicit entries in the command array.
///
int8_t (*func)(uint8_t argc, const struct arg *argv); ///< callback function
};
/// constructor
///
/// Note that you should normally not call the constructor directly. Use
/// the MENU and MENU2 macros defined below.
///
/// @param prompt The prompt to be displayed with this menu.
/// @param commands An array of ::command structures in program memory (PROGMEM).
/// @param entries The number of entries in the menu.
///
Menu(const char *prompt, const struct command *commands, uint8_t entries, preprompt ppfunc = 0);
/// constructor
///
/// Note that you should normally not call the constructor directly. Use
/// the MENU and MENU2 macros defined below.
///
/// @param prompt The prompt to be displayed with this menu.
/// @param commands An array of ::command structures in program memory (PROGMEM).
/// @param entries The number of entries in the menu.
///
Menu(const char *prompt, const struct command *commands, uint8_t entries, preprompt ppfunc = 0);
/// menu runner
void run(void);
/// menu runner
void run(void);
private:
/// Implements the default 'help' command.
///
void _help(void); ///< implements the 'help' command
/// Implements the default 'help' command.
///
void _help(void); ///< implements the 'help' command
/// calls the function for the n'th menu item
///
/// @param n Index for the menu item to call
/// @param argc Number of arguments prepared for the menu item
///
int8_t _call(uint8_t n, uint8_t argc);
/// calls the function for the n'th menu item
///
/// @param n Index for the menu item to call
/// @param argc Number of arguments prepared for the menu item
///
int8_t _call(uint8_t n, uint8_t argc);
const char *_prompt; ///< prompt to display
const command *_commands; ///< array of commands
const uint8_t _entries; ///< size of the menu
const preprompt _ppfunc; ///< optional pre-prompt action
const char *_prompt; ///< prompt to display
const command *_commands; ///< array of commands
const uint8_t _entries; ///< size of the menu
const preprompt _ppfunc; ///< optional pre-prompt action
static char _inbuf[MENU_COMMANDLINE_MAX]; ///< input buffer
static arg _argv[MENU_ARGS_MAX + 1]; ///< arguments
static char _inbuf[MENU_COMMANDLINE_MAX]; ///< input buffer
static arg _argv[MENU_ARGS_MAX + 1]; ///< arguments
};
/// Macros used to define a menu.

View File

@ -19,10 +19,10 @@ Menu::arg Menu::_argv[MENU_ARGS_MAX + 1];
// constructor
Menu::Menu(const prog_char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) :
_prompt(prompt),
_commands(commands),
_entries(entries),
_ppfunc(ppfunc)
_prompt(prompt),
_commands(commands),
_entries(entries),
_ppfunc(ppfunc)
{
}
@ -30,112 +30,112 @@ Menu::Menu(const prog_char *prompt, const Menu::command *commands, uint8_t entri
void
Menu::run(void)
{
uint8_t len, i, ret;
uint8_t argc;
int c;
char *s;
// loop performing commands
for (;;) {
uint8_t len, i, ret;
uint8_t argc;
int c;
char *s;
// run the pre-prompt function, if one is defined
if ((NULL != _ppfunc) && !_ppfunc())
return;
// loop performing commands
for (;;) {
// loop reading characters from the input
len = 0;
Serial.printf("%S] ", FPSTR(_prompt));
for (;;) {
c = Serial.read();
if (-1 == c)
continue;
// carriage return -> process command
if ('\r' == c) {
_inbuf[len] = '\0';
Serial.write('\r');
Serial.write('\n');
break;
}
// backspace
if ('\b' == c) {
if (len > 0) {
len--;
Serial.write('\b');
Serial.write(' ');
Serial.write('\b');
continue;
}
}
// printable character
if (isprint(c) && (len < (MENU_COMMANDLINE_MAX - 1))) {
_inbuf[len++] = c;
Serial.write((char)c);
continue;
}
}
// split the input line into tokens
argc = 0;
_argv[argc++].str = strtok_r(_inbuf, " ", &s);
// XXX should an empty line by itself back out of the current menu?
while (argc <= MENU_ARGS_MAX) {
_argv[argc].str = strtok_r(NULL, " ", &s);
if ('\0' == _argv[argc].str)
break;
_argv[argc].i = atol(_argv[argc].str);
_argv[argc].f = atof(_argv[argc].str); // calls strtod, > 700B !
argc++;
}
// run the pre-prompt function, if one is defined
if ((NULL != _ppfunc) && !_ppfunc())
return;
// populate arguments that have not been specified with "" and 0
// this is safer than NULL in the case where commands may look
// without testing argc
i = argc;
while (i <= MENU_ARGS_MAX) {
_argv[i].str = "";
_argv[i].i = 0;
_argv[i].f = 0;
i++;
}
// look for a command matching the first word (note that it may be empty)
for (i = 0; i < _entries; i++) {
if (!strcasecmp_P(_argv[0].str, _commands[i].command)) {
ret = _call(i, argc);
if (-2 == ret)
return;
break;
}
}
// loop reading characters from the input
len = 0;
Serial.printf("%S] ", FPSTR(_prompt));
for (;;) {
c = Serial.read();
if (-1 == c)
continue;
// carriage return -> process command
if ('\r' == c) {
_inbuf[len] = '\0';
Serial.write('\r');
Serial.write('\n');
break;
}
// backspace
if ('\b' == c) {
if (len > 0) {
len--;
Serial.write('\b');
Serial.write(' ');
Serial.write('\b');
continue;
}
}
// printable character
if (isprint(c) && (len < (MENU_COMMANDLINE_MAX - 1))) {
_inbuf[len++] = c;
Serial.write((char)c);
continue;
}
}
// implicit commands
if (i == _entries) {
if (!strcmp(_argv[0].str, "?") || (!strcasecmp_P(_argv[0].str, PSTR("help")))) {
_help();
} else if (!strcasecmp_P(_argv[0].str, PSTR("exit"))) {
return;
}
}
}
// split the input line into tokens
argc = 0;
_argv[argc++].str = strtok_r(_inbuf, " ", &s);
// XXX should an empty line by itself back out of the current menu?
while (argc <= MENU_ARGS_MAX) {
_argv[argc].str = strtok_r(NULL, " ", &s);
if ('\0' == _argv[argc].str)
break;
_argv[argc].i = atol(_argv[argc].str);
_argv[argc].f = atof(_argv[argc].str); // calls strtod, > 700B !
argc++;
}
// populate arguments that have not been specified with "" and 0
// this is safer than NULL in the case where commands may look
// without testing argc
i = argc;
while (i <= MENU_ARGS_MAX) {
_argv[i].str = "";
_argv[i].i = 0;
_argv[i].f = 0;
i++;
}
// look for a command matching the first word (note that it may be empty)
for (i = 0; i < _entries; i++) {
if (!strcasecmp_P(_argv[0].str, _commands[i].command)) {
ret = _call(i, argc);
if (-2 == ret)
return;
break;
}
}
// implicit commands
if (i == _entries) {
if (!strcmp(_argv[0].str, "?") || (!strcasecmp_P(_argv[0].str, PSTR("help")))) {
_help();
} else if (!strcasecmp_P(_argv[0].str, PSTR("exit"))) {
return;
}
}
}
}
// display the list of commands in response to the 'help' command
void
Menu::_help(void)
{
int i;
Serial.println("Commands:");
for (i = 0; i < _entries; i++)
Serial.printf(" %S\n", FPSTR(_commands[i].command));
int i;
Serial.println("Commands:");
for (i = 0; i < _entries; i++)
Serial.printf(" %S\n", FPSTR(_commands[i].command));
}
// run the n'th command in the menu
int8_t
Menu::_call(uint8_t n, uint8_t argc)
{
func fn;
func fn;
fn = (func)pgm_read_word(&_commands[n].func);
return(fn(argc, &_argv[0]));
fn = (func)pgm_read_word(&_commands[n].func);
return(fn(argc, &_argv[0]));
}