HAL_SITL: reformat HAL_SITL with astyle

This commit is contained in:
Andrew Tridgell 2015-05-05 10:59:07 +10:00
parent 8c8c910ad0
commit c81ad1d622
23 changed files with 889 additions and 868 deletions

View File

@ -3,16 +3,16 @@
#define __AP_HAL_SITL_NAMESPACE_H__ #define __AP_HAL_SITL_NAMESPACE_H__
namespace HALSITL { namespace HALSITL {
class SITLUARTDriver; class SITLUARTDriver;
class SITLScheduler; class SITLScheduler;
class SITL_State; class SITL_State;
class SITLEEPROMStorage; class SITLEEPROMStorage;
class SITLAnalogIn; class SITLAnalogIn;
class SITLRCInput; class SITLRCInput;
class SITLRCOutput; class SITLRCOutput;
class ADCSource; class ADCSource;
class RCInput; class RCInput;
class SITLUtil; class SITLUtil;
} }
#endif // __AP_HAL_SITL_NAMESPACE_H__ #endif // __AP_HAL_SITL_NAMESPACE_H__

View File

@ -19,7 +19,9 @@ public:
void set_pin(uint8_t p); void set_pin(uint8_t p);
float voltage_average(); float voltage_average();
float voltage_latest(); float voltage_latest();
float voltage_average_ratiometric() { return voltage_average(); } float voltage_average_ratiometric() {
return voltage_average();
}
void set_stop_pin(uint8_t pin) {} void set_stop_pin(uint8_t pin) {}
void set_settle_time(uint16_t settle_time_ms) {} void set_settle_time(uint16_t settle_time_ms) {}
@ -37,7 +39,9 @@ public:
} }
void init(void* ap_hal_scheduler); void init(void* ap_hal_scheduler);
AP_HAL::AnalogSource* channel(int16_t n); AP_HAL::AnalogSource* channel(int16_t n);
float board_voltage(void) { return 5.0f; } float board_voltage(void) {
return 5.0f;
}
private: private:
static ADCSource* _channels[SITL_INPUT_MAX_CHANNELS]; static ADCSource* _channels[SITL_INPUT_MAX_CHANNELS];
SITL_State *_sitlState; SITL_State *_sitlState;

View File

@ -13,7 +13,9 @@ public:
} }
void init(void* machtnichts); void init(void* machtnichts);
bool new_input(); bool new_input();
uint8_t num_channels() { return 8; } uint8_t num_channels() {
return 8;
}
uint16_t read(uint8_t ch); uint16_t read(uint8_t ch);
uint8_t read(uint16_t* periods, uint8_t len); uint8_t read(uint16_t* periods, uint8_t len);

View File

@ -45,7 +45,9 @@ public:
uint16_t pwm_input[8]; uint16_t pwm_input[8];
bool new_rc_input; bool new_rc_input;
void loop_hook(void); void loop_hook(void);
uint16_t base_port(void) const { return _base_port; } uint16_t base_port(void) const {
return _base_port;
}
// simulated airspeed, sonar and battery monitor // simulated airspeed, sonar and battery monitor
uint16_t sonar_pin_value; // pin 0 uint16_t sonar_pin_value; // pin 0
@ -77,7 +79,7 @@ private:
bool have_lock; bool have_lock;
}; };
#define MAX_GPS_DELAY 100 #define MAX_GPS_DELAY 100
gps_data _gps_data[MAX_GPS_DELAY]; gps_data _gps_data[MAX_GPS_DELAY];
bool _gps_has_basestation_position; bool _gps_has_basestation_position;

View File

@ -39,14 +39,21 @@ public:
void reboot(bool hold_in_bootloader); void reboot(bool hold_in_bootloader);
void panic(const prog_char_t *errormsg); void panic(const prog_char_t *errormsg);
bool interrupts_are_blocked(void) { return _nested_atomic_ctr != 0; } bool interrupts_are_blocked(void) {
return _nested_atomic_ctr != 0;
}
void sitl_begin_atomic() { _nested_atomic_ctr++; } void sitl_begin_atomic() {
_nested_atomic_ctr++;
}
void sitl_end_atomic(); void sitl_end_atomic();
// callable from interrupt handler // callable from interrupt handler
static uint64_t _micros64(); static uint64_t _micros64();
static void timer_event() { _run_timer_procs(true); _run_io_procs(true); } static void timer_event() {
_run_timer_procs(true);
_run_io_procs(true);
}
private: private:
SITL_State *_sitlState; SITL_State *_sitlState;

View File

@ -24,11 +24,15 @@ public:
} }
/* Implementations of UARTDriver virtual methods */ /* Implementations of UARTDriver virtual methods */
void begin(uint32_t b) { begin(b, 0, 0); } void begin(uint32_t b) {
begin(b, 0, 0);
}
void begin(uint32_t b, uint16_t rxS, uint16_t txS); void begin(uint32_t b, uint16_t rxS, uint16_t txS);
void end(); void end();
void flush(); void flush();
bool is_initialized() { return true; } bool is_initialized() {
return true;
}
void set_blocking_writes(bool blocking) void set_blocking_writes(bool blocking)
{ {

View File

@ -7,7 +7,9 @@
class HALSITL::SITLUtil : public AP_HAL::Util { class HALSITL::SITLUtil : public AP_HAL::Util {
public: public:
bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; } bool run_debug_shell(AP_HAL::BetterStream *stream) {
return false;
}
}; };
#endif // __AP_HAL_SITL_UTIL_H__ #endif // __AP_HAL_SITL_UTIL_H__