mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_HAL: remove tabs and trailing whitespaces
This commit is contained in:
parent
ab66e3a69a
commit
9738be0ed6
@ -18,14 +18,14 @@ public:
|
|||||||
void clear_capabilities(uint64_t cap) { capabilities &= ~(cap); }
|
void clear_capabilities(uint64_t cap) { capabilities &= ~(cap); }
|
||||||
uint64_t get_capabilities() const { return capabilities; }
|
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; }
|
virtual const char* get_custom_terrain_directory() const { return NULL; }
|
||||||
|
|
||||||
// get path to custom defaults file for AP_Param
|
// get path to custom defaults file for AP_Param
|
||||||
virtual const char* get_custom_defaults_file() const {
|
virtual const char* get_custom_defaults_file() const {
|
||||||
return HAL_PARAM_DEFAULTS_PATH;
|
return HAL_PARAM_DEFAULTS_PATH;
|
||||||
}
|
}
|
||||||
|
|
||||||
// run a debug shall on the given stream if possible. This is used
|
// run a debug shall on the given stream if possible. This is used
|
||||||
// to support dropping into a debug shell to run firmware upgrade
|
// to support dropping into a debug shell to run firmware upgrade
|
||||||
// commands
|
// commands
|
||||||
@ -75,7 +75,7 @@ public:
|
|||||||
return commandline arguments, if available
|
return commandline arguments, if available
|
||||||
*/
|
*/
|
||||||
virtual void commandline_arguments(uint8_t &argc, char * const *&argv) { argc = 0; }
|
virtual void commandline_arguments(uint8_t &argc, char * const *&argv) { argc = 0; }
|
||||||
|
|
||||||
/*
|
/*
|
||||||
ToneAlarm Driver
|
ToneAlarm Driver
|
||||||
*/
|
*/
|
||||||
@ -95,9 +95,9 @@ public:
|
|||||||
performance counter calls - wrapper around original PX4 interface
|
performance counter calls - wrapper around original PX4 interface
|
||||||
*/
|
*/
|
||||||
enum perf_counter_type {
|
enum perf_counter_type {
|
||||||
PC_COUNT, /**< count the number of times an event occurs */
|
PC_COUNT, /**< count the number of times an event occurs */
|
||||||
PC_ELAPSED, /**< measure the time elapsed performing an event */
|
PC_ELAPSED, /**< measure the time elapsed performing an event */
|
||||||
PC_INTERVAL /**< measure the interval between instances of an event */
|
PC_INTERVAL /**< measure the interval between instances of an event */
|
||||||
};
|
};
|
||||||
typedef void *perf_counter_t;
|
typedef void *perf_counter_t;
|
||||||
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return NULL; }
|
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return NULL; }
|
||||||
@ -107,7 +107,7 @@ public:
|
|||||||
|
|
||||||
// create a new semaphore
|
// create a new semaphore
|
||||||
virtual Semaphore *new_semaphore(void) { return nullptr; }
|
virtual Semaphore *new_semaphore(void) { return nullptr; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
// we start soft_armed false, so that actuators don't send any
|
// we start soft_armed false, so that actuators don't send any
|
||||||
// values until the vehicle code has fully started
|
// values until the vehicle code has fully started
|
||||||
|
Loading…
Reference in New Issue
Block a user