mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
AP_HAL_SITL: style fixes
This commit is contained in:
parent
5b2b4430b3
commit
8ade9d1fe8
@ -6,4 +6,4 @@
|
||||
|
||||
#include "HAL_SITL_Class.h"
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -14,4 +14,4 @@ class Util;
|
||||
class Semaphore;
|
||||
class GPIO;
|
||||
class DigitalSource;
|
||||
}
|
||||
} // namespace HALSITL
|
||||
|
@ -46,22 +46,22 @@ static Util utilInstance(&sitlState);
|
||||
|
||||
HAL_SITL::HAL_SITL() :
|
||||
AP_HAL::HAL(
|
||||
&sitlUart0Driver, /* uartA */
|
||||
&sitlUart1Driver, /* uartB */
|
||||
&sitlUart2Driver, /* uartC */
|
||||
&sitlUart3Driver, /* uartD */
|
||||
&sitlUart4Driver, /* uartE */
|
||||
&sitlUart5Driver, /* uartF */
|
||||
&sitlUart0Driver, /* uartA */
|
||||
&sitlUart1Driver, /* uartB */
|
||||
&sitlUart2Driver, /* uartC */
|
||||
&sitlUart3Driver, /* uartD */
|
||||
&sitlUart4Driver, /* uartE */
|
||||
&sitlUart5Driver, /* uartF */
|
||||
&i2c_mgr_instance,
|
||||
&emptySPI, /* spi */
|
||||
&sitlAnalogIn, /* analogin */
|
||||
&emptySPI, /* spi */
|
||||
&sitlAnalogIn, /* analogin */
|
||||
&sitlEEPROMStorage, /* storage */
|
||||
&sitlUart0Driver, /* console */
|
||||
&sitlGPIO, /* gpio */
|
||||
&sitlRCInput, /* rcinput */
|
||||
&sitlRCOutput, /* rcoutput */
|
||||
&sitlScheduler, /* scheduler */
|
||||
&utilInstance, /* util */
|
||||
&sitlUart0Driver, /* console */
|
||||
&sitlGPIO, /* gpio */
|
||||
&sitlRCInput, /* rcinput */
|
||||
&sitlRCOutput, /* rcoutput */
|
||||
&sitlScheduler, /* scheduler */
|
||||
&utilInstance, /* util */
|
||||
&emptyOpticalFlow), /* onboard optical flow */
|
||||
_sitl_state(&sitlState)
|
||||
{}
|
||||
@ -77,7 +77,7 @@ void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
rcin->init();
|
||||
rcout->init();
|
||||
|
||||
//spi->init();
|
||||
// spi->init();
|
||||
analogin->init();
|
||||
|
||||
callbacks->setup();
|
||||
@ -93,4 +93,4 @@ const AP_HAL::HAL& AP_HAL::get_HAL() {
|
||||
return hal;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
@ -17,4 +17,4 @@ private:
|
||||
HALSITL::SITL_State *_sitl_state;
|
||||
};
|
||||
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
@ -8,12 +8,12 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace HALSITL;
|
||||
|
||||
bool Semaphore::give()
|
||||
bool Semaphore::give()
|
||||
{
|
||||
return pthread_mutex_unlock(&_lock) == 0;
|
||||
}
|
||||
|
||||
bool Semaphore::take(uint32_t timeout_ms)
|
||||
bool Semaphore::take(uint32_t timeout_ms)
|
||||
{
|
||||
if (timeout_ms == 0) {
|
||||
return pthread_mutex_lock(&_lock) == 0;
|
||||
@ -27,13 +27,13 @@ bool Semaphore::take(uint32_t timeout_ms)
|
||||
if (take_nonblocking()) {
|
||||
return true;
|
||||
}
|
||||
} while ((AP_HAL::micros64() - start) < timeout_ms*1000);
|
||||
} while ((AP_HAL::micros64() - start) < timeout_ms * 1000);
|
||||
return false;
|
||||
}
|
||||
|
||||
bool Semaphore::take_nonblocking()
|
||||
bool Semaphore::take_nonblocking()
|
||||
{
|
||||
return pthread_mutex_trylock(&_lock) == 0;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -17,5 +17,5 @@ public:
|
||||
private:
|
||||
pthread_mutex_t _lock;
|
||||
};
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user