mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-05 21:52:10 +01:00
OP-1308 Uncrustify operation
This commit is contained in:
parent
6d3ade4947
commit
70ba6850d0
@ -113,7 +113,7 @@ static const controlHandler handler_PATHPLANNER = {
|
|||||||
.handler = &pathPlannerHandler,
|
.handler = &pathPlannerHandler,
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif /* ifndef PIOS_EXCLUDE_ADVANCED_FEATURES */
|
||||||
// Private variables
|
// Private variables
|
||||||
static DelayedCallbackInfo *callbackHandle;
|
static DelayedCallbackInfo *callbackHandle;
|
||||||
|
|
||||||
|
@ -167,9 +167,9 @@ static int32_t maininit(stateFilter *self)
|
|||||||
*/
|
*/
|
||||||
static filterResult filter(stateFilter *self, stateEstimation *state)
|
static filterResult filter(stateFilter *self, stateEstimation *state)
|
||||||
{
|
{
|
||||||
struct data *this = (struct data *)self->localdata;
|
struct data *this = (struct data *)self->localdata;
|
||||||
|
|
||||||
filterResult result = FILTERRESULT_OK;
|
filterResult result = FILTERRESULT_OK;
|
||||||
|
|
||||||
if (IS_SET(state->updated, SENSORUPDATES_mag)) {
|
if (IS_SET(state->updated, SENSORUPDATES_mag)) {
|
||||||
this->magUpdated = 1;
|
this->magUpdated = 1;
|
||||||
|
@ -35,11 +35,11 @@
|
|||||||
|
|
||||||
// Enumeration for filter result
|
// Enumeration for filter result
|
||||||
typedef enum {
|
typedef enum {
|
||||||
FILTERRESULT_UNINITIALISED=-1,
|
FILTERRESULT_UNINITIALISED = -1,
|
||||||
FILTERRESULT_OK=0,
|
FILTERRESULT_OK = 0,
|
||||||
FILTERRESULT_WARNING=1,
|
FILTERRESULT_WARNING = 1,
|
||||||
FILTERRESULT_CRITICAL=2,
|
FILTERRESULT_CRITICAL = 2,
|
||||||
FILTERRESULT_ERROR=3,
|
FILTERRESULT_ERROR = 3,
|
||||||
} filterResult;
|
} filterResult;
|
||||||
|
|
||||||
|
|
||||||
|
@ -334,9 +334,9 @@ MODULE_INITCALL(StateEstimationInitialize, StateEstimationStart);
|
|||||||
static void StateEstimationCb(void)
|
static void StateEstimationCb(void)
|
||||||
{
|
{
|
||||||
static enum { RUNSTATE_LOAD = 0, RUNSTATE_FILTER = 1, RUNSTATE_SAVE = 2 } runState = RUNSTATE_LOAD;
|
static enum { RUNSTATE_LOAD = 0, RUNSTATE_FILTER = 1, RUNSTATE_SAVE = 2 } runState = RUNSTATE_LOAD;
|
||||||
static filterResult alarm = FILTERRESULT_OK;
|
static filterResult alarm = FILTERRESULT_OK;
|
||||||
static filterResult lastAlarm = FILTERRESULT_UNINITIALISED;
|
static filterResult lastAlarm = FILTERRESULT_UNINITIALISED;
|
||||||
static uint16_t alarmcounter = 0;
|
static uint16_t alarmcounter = 0;
|
||||||
static const filterPipeline *current;
|
static const filterPipeline *current;
|
||||||
static stateEstimation states;
|
static stateEstimation states;
|
||||||
static uint32_t last_time;
|
static uint32_t last_time;
|
||||||
|
Loading…
x
Reference in New Issue
Block a user