AP_HAL: remove tabs and trailing whitespaces

This commit is contained in:
Lucas De Marchi 2016-05-23 17:14:54 -03:00
parent ab66e3a69a
commit 9738be0ed6

View File

@ -18,14 +18,14 @@ public:
void clear_capabilities(uint64_t cap) { capabilities &= ~(cap); }
uint64_t get_capabilities() const { return capabilities; }
virtual const char* get_custom_log_directory() { return NULL; }
virtual const char* get_custom_log_directory() { return NULL; }
virtual const char* get_custom_terrain_directory() const { return NULL; }
// get path to custom defaults file for AP_Param
virtual const char* get_custom_defaults_file() const {
return HAL_PARAM_DEFAULTS_PATH;
}
// run a debug shall on the given stream if possible. This is used
// to support dropping into a debug shell to run firmware upgrade
// commands
@ -75,7 +75,7 @@ public:
return commandline arguments, if available
*/
virtual void commandline_arguments(uint8_t &argc, char * const *&argv) { argc = 0; }
/*
ToneAlarm Driver
*/
@ -95,9 +95,9 @@ public:
performance counter calls - wrapper around original PX4 interface
*/
enum perf_counter_type {
PC_COUNT, /**< count the number of times an event occurs */
PC_ELAPSED, /**< measure the time elapsed performing an event */
PC_INTERVAL /**< measure the interval between instances of an event */
PC_COUNT, /**< count the number of times an event occurs */
PC_ELAPSED, /**< measure the time elapsed performing an event */
PC_INTERVAL /**< measure the interval between instances of an event */
};
typedef void *perf_counter_t;
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return NULL; }
@ -107,7 +107,7 @@ public:
// create a new semaphore
virtual Semaphore *new_semaphore(void) { return nullptr; }
protected:
// we start soft_armed false, so that actuators don't send any
// values until the vehicle code has fully started