forked from Archive/PX4-Autopilot
Merge pull request #1960 from dagar/format
Trivial code style cleanup round 2
This commit is contained in:
commit
b24af0f402
|
@ -3,6 +3,7 @@ set -eu
|
||||||
failed=0
|
failed=0
|
||||||
for fn in $(find . -path './src/lib/uavcan' -prune -o \
|
for fn in $(find . -path './src/lib/uavcan' -prune -o \
|
||||||
-path './src/lib/mathlib/CMSIS' -prune -o \
|
-path './src/lib/mathlib/CMSIS' -prune -o \
|
||||||
|
-path './src/lib/eigen' -prune -o \
|
||||||
-path './src/modules/attitude_estimator_ekf/codegen' -prune -o \
|
-path './src/modules/attitude_estimator_ekf/codegen' -prune -o \
|
||||||
-path './NuttX' -prune -o \
|
-path './NuttX' -prune -o \
|
||||||
-path './Build' -prune -o \
|
-path './Build' -prune -o \
|
||||||
|
|
|
@ -90,7 +90,7 @@ static const int ERROR = -1;
|
||||||
class __EXPORT Airspeed : public device::I2C
|
class __EXPORT Airspeed : public device::I2C
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
Airspeed(int bus, int address, unsigned conversion_interval, const char* path);
|
Airspeed(int bus, int address, unsigned conversion_interval, const char *path);
|
||||||
virtual ~Airspeed();
|
virtual ~Airspeed();
|
||||||
|
|
||||||
virtual int init();
|
virtual int init();
|
||||||
|
@ -108,8 +108,8 @@ private:
|
||||||
perf_counter_t _buffer_overflows;
|
perf_counter_t _buffer_overflows;
|
||||||
|
|
||||||
/* this class has pointer data members and should not be copied */
|
/* this class has pointer data members and should not be copied */
|
||||||
Airspeed(const Airspeed&);
|
Airspeed(const Airspeed &);
|
||||||
Airspeed& operator=(const Airspeed&);
|
Airspeed &operator=(const Airspeed &);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
virtual int probe();
|
virtual int probe();
|
||||||
|
|
|
@ -85,7 +85,8 @@ int ar_init_motors(int ardrone_uart, int gpio);
|
||||||
/**
|
/**
|
||||||
* Set LED pattern.
|
* Set LED pattern.
|
||||||
*/
|
*/
|
||||||
void ar_set_leds(int ardrone_uart, uint8_t led1_red, uint8_t led1_green, uint8_t led2_red, uint8_t led2_green, uint8_t led3_red, uint8_t led3_green, uint8_t led4_red, uint8_t led4_green);
|
void ar_set_leds(int ardrone_uart, uint8_t led1_red, uint8_t led1_green, uint8_t led2_red, uint8_t led2_green,
|
||||||
|
uint8_t led3_red, uint8_t led3_green, uint8_t led4_red, uint8_t led4_green);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Mix motors and output actuators
|
* Mix motors and output actuators
|
||||||
|
|
|
@ -144,8 +144,8 @@ private:
|
||||||
uint32_t _frequency;
|
uint32_t _frequency;
|
||||||
struct i2c_dev_s *_dev;
|
struct i2c_dev_s *_dev;
|
||||||
|
|
||||||
I2C(const device::I2C&);
|
I2C(const device::I2C &);
|
||||||
I2C operator=(const device::I2C&);
|
I2C operator=(const device::I2C &);
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace device
|
} // namespace device
|
||||||
|
|
|
@ -127,7 +127,8 @@ __EXPORT extern void hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, h
|
||||||
* Note thet the interval is timed between scheduled, not actual, call times, so the call rate may
|
* Note thet the interval is timed between scheduled, not actual, call times, so the call rate may
|
||||||
* jitter but should not drift.
|
* jitter but should not drift.
|
||||||
*/
|
*/
|
||||||
__EXPORT extern void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg);
|
__EXPORT extern void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval,
|
||||||
|
hrt_callout callout, void *arg);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* If this returns true, the entry has been invoked and removed from the callout list,
|
* If this returns true, the entry has been invoked and removed from the callout list,
|
||||||
|
|
|
@ -222,6 +222,7 @@ void frsky_send_frame2(int uart)
|
||||||
float course = 0, lat = 0, lon = 0, speed = 0, alt = 0;
|
float course = 0, lat = 0, lon = 0, speed = 0, alt = 0;
|
||||||
char lat_ns = 0, lon_ew = 0;
|
char lat_ns = 0, lon_ew = 0;
|
||||||
int sec = 0;
|
int sec = 0;
|
||||||
|
|
||||||
if (global_pos.timestamp != 0 && hrt_absolute_time() < global_pos.timestamp + 20000) {
|
if (global_pos.timestamp != 0 && hrt_absolute_time() < global_pos.timestamp + 20000) {
|
||||||
time_t time_gps = global_pos.time_utc_usec / 1000000ULL;
|
time_t time_gps = global_pos.time_utc_usec / 1000000ULL;
|
||||||
struct tm *tm_gps = gmtime(&time_gps);
|
struct tm *tm_gps = gmtime(&time_gps);
|
||||||
|
|
|
@ -1,7 +1,8 @@
|
||||||
#include <controllib/block/Block.hpp>
|
#include <controllib/block/Block.hpp>
|
||||||
#include <controllib/block/BlockParam.hpp>
|
#include <controllib/block/BlockParam.hpp>
|
||||||
|
|
||||||
class BlockSysIdent : public control::Block {
|
class BlockSysIdent : public control::Block
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
BlockSysIdent();
|
BlockSysIdent();
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -44,7 +44,8 @@
|
||||||
#include "Limits.hpp"
|
#include "Limits.hpp"
|
||||||
|
|
||||||
|
|
||||||
namespace math {
|
namespace math
|
||||||
|
{
|
||||||
|
|
||||||
#ifndef CONFIG_ARCH_ARM
|
#ifndef CONFIG_ARCH_ARM
|
||||||
#define M_PI_F 3.14159265358979323846f
|
#define M_PI_F 3.14159265358979323846f
|
||||||
|
|
|
@ -42,7 +42,8 @@
|
||||||
#include <platforms/px4_defines.h>
|
#include <platforms/px4_defines.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
namespace math {
|
namespace math
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
float __EXPORT min(float val1, float val2);
|
float __EXPORT min(float val1, float val2);
|
||||||
|
|
|
@ -51,7 +51,7 @@ bool __EXPORT equal(float a, float b, float epsilon)
|
||||||
printf("not equal ->\n\ta: %12.8f\n\tb: %12.8f\n", double(a), double(b));
|
printf("not equal ->\n\ta: %12.8f\n\tb: %12.8f\n", double(a), double(b));
|
||||||
return false;
|
return false;
|
||||||
|
|
||||||
} else return true;
|
} else { return true; }
|
||||||
}
|
}
|
||||||
|
|
||||||
void __EXPORT float2SigExp(
|
void __EXPORT float2SigExp(
|
||||||
|
@ -84,10 +84,10 @@ void __EXPORT float2SigExp(
|
||||||
|
|
||||||
// cheap power since it is integer
|
// cheap power since it is integer
|
||||||
if (exp > 0) {
|
if (exp > 0) {
|
||||||
for (int i = 0; i < abs(exp); i++) sig /= 10;
|
for (int i = 0; i < abs(exp); i++) { sig /= 10; }
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
for (int i = 0; i < abs(exp); i++) sig *= 10;
|
for (int i = 0; i < abs(exp); i++) { sig *= 10; }
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -113,6 +113,7 @@ int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channe
|
||||||
case ST24_DECODE_STATE_UNSYNCED:
|
case ST24_DECODE_STATE_UNSYNCED:
|
||||||
if (byte == ST24_STX1) {
|
if (byte == ST24_STX1) {
|
||||||
_decode_state = ST24_DECODE_STATE_GOT_STX1;
|
_decode_state = ST24_DECODE_STATE_GOT_STX1;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
ret = 3;
|
ret = 3;
|
||||||
}
|
}
|
||||||
|
|
|
@ -45,7 +45,8 @@
|
||||||
|
|
||||||
|
|
||||||
int sphere_fit_least_squares(const float x[], const float y[], const float z[],
|
int sphere_fit_least_squares(const float x[], const float y[], const float z[],
|
||||||
unsigned int size, unsigned int max_iterations, float delta, float *sphere_x, float *sphere_y, float *sphere_z, float *sphere_radius)
|
unsigned int size, unsigned int max_iterations, float delta, float *sphere_x, float *sphere_y, float *sphere_z,
|
||||||
|
float *sphere_radius)
|
||||||
{
|
{
|
||||||
|
|
||||||
float x_sumplain = 0.0f;
|
float x_sumplain = 0.0f;
|
||||||
|
|
|
@ -376,7 +376,7 @@ int do_gyro_calibration(int mavlink_fd)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (res == OK) {
|
if (res == OK) {
|
||||||
/* auto-save to EEPROM */
|
/* auto-save to EEPROM */
|
||||||
|
|
|
@ -58,7 +58,7 @@ public:
|
||||||
*
|
*
|
||||||
* @param parent_prefix Set to true to include the parent name in the parameter name
|
* @param parent_prefix Set to true to include the parent name in the parameter name
|
||||||
*/
|
*/
|
||||||
BlockParamBase(Block *parent, const char *name, bool parent_prefix=true);
|
BlockParamBase(Block *parent, const char *name, bool parent_prefix = true);
|
||||||
virtual ~BlockParamBase() {};
|
virtual ~BlockParamBase() {};
|
||||||
virtual void update() = 0;
|
virtual void update() = 0;
|
||||||
const char *getName() { return param_name(_handle); }
|
const char *getName() { return param_name(_handle); }
|
||||||
|
@ -75,7 +75,7 @@ class BlockParam : public BlockParamBase
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
BlockParam(Block *block, const char *name,
|
BlockParam(Block *block, const char *name,
|
||||||
bool parent_prefix=true);
|
bool parent_prefix = true);
|
||||||
T get();
|
T get();
|
||||||
void set(T val);
|
void set(T val);
|
||||||
void update();
|
void update();
|
||||||
|
|
|
@ -114,7 +114,7 @@ public:
|
||||||
// methods
|
// methods
|
||||||
BlockLowPass(SuperBlock *parent, const char *name) :
|
BlockLowPass(SuperBlock *parent, const char *name) :
|
||||||
Block(parent, name),
|
Block(parent, name),
|
||||||
_state(0.0f/0.0f /* initialize to invalid val, force into is_finite() check on first call */),
|
_state(0.0f / 0.0f /* initialize to invalid val, force into is_finite() check on first call */),
|
||||||
_fCut(this, "") // only one parameter, no need to name
|
_fCut(this, "") // only one parameter, no need to name
|
||||||
{};
|
{};
|
||||||
virtual ~BlockLowPass() {};
|
virtual ~BlockLowPass() {};
|
||||||
|
@ -492,8 +492,9 @@ public:
|
||||||
|
|
||||||
X = V1 * float(sqrt(-2 * float(log(S)) / S));
|
X = V1 * float(sqrt(-2 * float(log(S)) / S));
|
||||||
|
|
||||||
} else
|
} else {
|
||||||
X = V2 * float(sqrt(-2 * float(log(S)) / S));
|
X = V2 * float(sqrt(-2 * float(log(S)) / S));
|
||||||
|
}
|
||||||
|
|
||||||
phase = 1 - phase;
|
phase = 1 - phase;
|
||||||
return X * getStdDev() + getMean();
|
return X * getStdDev() + getMean();
|
||||||
|
|
|
@ -136,7 +136,8 @@ PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.2f);
|
||||||
* @max 2.0
|
* @max 2.0
|
||||||
* @group FW Attitude Control
|
* @group FW Attitude Control
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_P_ROLLFF, 0.0f); //xxx: set to 0 as default, see comment in ECL_PitchController::control_attitude (float turn_offset = ...)
|
PARAM_DEFINE_FLOAT(FW_P_ROLLFF,
|
||||||
|
0.0f); //xxx: set to 0 as default, see comment in ECL_PitchController::control_attitude (float turn_offset = ...)
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Roll rate proportional Gain
|
* Roll rate proportional Gain
|
||||||
|
|
|
@ -184,11 +184,13 @@ int gpio_led_main(int argc, char *argv[])
|
||||||
warnx("start, using pin: %s", pin_name);
|
warnx("start, using pin: %s", pin_name);
|
||||||
exit(0);
|
exit(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
} else if (!strcmp(argv[1], "stop")) {
|
} else if (!strcmp(argv[1], "stop")) {
|
||||||
if (gpio_led_started) {
|
if (gpio_led_started) {
|
||||||
gpio_led_started = false;
|
gpio_led_started = false;
|
||||||
warnx("stop");
|
warnx("stop");
|
||||||
exit(0);
|
exit(0);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
errx(1, "not running");
|
errx(1, "not running");
|
||||||
}
|
}
|
||||||
|
|
|
@ -188,6 +188,6 @@ private:
|
||||||
uint64_t _time_offset;
|
uint64_t _time_offset;
|
||||||
|
|
||||||
/* do not allow copying this class */
|
/* do not allow copying this class */
|
||||||
MavlinkReceiver(const MavlinkReceiver&);
|
MavlinkReceiver(const MavlinkReceiver &);
|
||||||
MavlinkReceiver operator=(const MavlinkReceiver&);
|
MavlinkReceiver operator=(const MavlinkReceiver &);
|
||||||
};
|
};
|
||||||
|
|
|
@ -89,7 +89,7 @@ public:
|
||||||
virtual unsigned get_size() = 0;
|
virtual unsigned get_size() = 0;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
Mavlink * _mavlink;
|
Mavlink *_mavlink;
|
||||||
unsigned int _interval;
|
unsigned int _interval;
|
||||||
|
|
||||||
virtual void send(const hrt_abstime t) = 0;
|
virtual void send(const hrt_abstime t) = 0;
|
||||||
|
@ -98,8 +98,8 @@ private:
|
||||||
hrt_abstime _last_sent;
|
hrt_abstime _last_sent;
|
||||||
|
|
||||||
/* do not allow top copying this class */
|
/* do not allow top copying this class */
|
||||||
MavlinkStream(const MavlinkStream&);
|
MavlinkStream(const MavlinkStream &);
|
||||||
MavlinkStream& operator=(const MavlinkStream&);
|
MavlinkStream &operator=(const MavlinkStream &);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -88,9 +88,9 @@ private:
|
||||||
bool _task_should_exit; /**< if true, sensor task should exit */
|
bool _task_should_exit; /**< if true, sensor task should exit */
|
||||||
bool _actuators_0_circuit_breaker_enabled; /**< circuit breaker to suppress output */
|
bool _actuators_0_circuit_breaker_enabled; /**< circuit breaker to suppress output */
|
||||||
|
|
||||||
px4::Publisher<px4_vehicle_attitude_setpoint> * _att_sp_pub; /**< attitude setpoint publication */
|
px4::Publisher<px4_vehicle_attitude_setpoint> *_att_sp_pub; /**< attitude setpoint publication */
|
||||||
px4::Publisher<px4_vehicle_rates_setpoint> * _v_rates_sp_pub; /**< rate setpoint publication */
|
px4::Publisher<px4_vehicle_rates_setpoint> *_v_rates_sp_pub; /**< rate setpoint publication */
|
||||||
px4::Publisher<px4_actuator_controls_0> * _actuators_0_pub; /**< attitude actuator controls publication */
|
px4::Publisher<px4_actuator_controls_0> *_actuators_0_pub; /**< attitude actuator controls publication */
|
||||||
|
|
||||||
px4::NodeHandle _n;
|
px4::NodeHandle _n;
|
||||||
|
|
||||||
|
|
|
@ -78,7 +78,8 @@ public:
|
||||||
/*
|
/*
|
||||||
* Returns true if mission is feasible and false otherwise
|
* Returns true if mission is feasible and false otherwise
|
||||||
*/
|
*/
|
||||||
bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
|
bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence,
|
||||||
|
float home_alt);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -58,7 +58,8 @@ NavigatorMode::~NavigatorMode()
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
NavigatorMode::run(bool active) {
|
NavigatorMode::run(bool active)
|
||||||
|
{
|
||||||
if (active) {
|
if (active) {
|
||||||
if (_first_run) {
|
if (_first_run) {
|
||||||
/* first run */
|
/* first run */
|
||||||
|
|
|
@ -92,8 +92,8 @@ private:
|
||||||
/* this class has ptr data members, so it should not be copied,
|
/* this class has ptr data members, so it should not be copied,
|
||||||
* consequently the copy constructors are private.
|
* consequently the copy constructors are private.
|
||||||
*/
|
*/
|
||||||
NavigatorMode(const NavigatorMode&);
|
NavigatorMode(const NavigatorMode &);
|
||||||
NavigatorMode operator=(const NavigatorMode&);
|
NavigatorMode operator=(const NavigatorMode &);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -219,7 +219,8 @@ extern int dsm_init(const char *device);
|
||||||
extern bool dsm_input(uint16_t *values, uint16_t *num_values, uint8_t *n_bytes, uint8_t **bytes);
|
extern bool dsm_input(uint16_t *values, uint16_t *num_values, uint8_t *n_bytes, uint8_t **bytes);
|
||||||
extern void dsm_bind(uint16_t cmd, int pulses);
|
extern void dsm_bind(uint16_t cmd, int pulses);
|
||||||
extern int sbus_init(const char *device);
|
extern int sbus_init(const char *device);
|
||||||
extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels);
|
extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop,
|
||||||
|
uint16_t max_channels);
|
||||||
extern void sbus1_output(uint16_t *values, uint16_t num_values);
|
extern void sbus1_output(uint16_t *values, uint16_t num_values);
|
||||||
extern void sbus2_output(uint16_t *values, uint16_t num_values);
|
extern void sbus2_output(uint16_t *values, uint16_t num_values);
|
||||||
|
|
||||||
|
|
|
@ -97,7 +97,8 @@ void cpuload_initialize_once()
|
||||||
system_load.tasks[system_load.total_count].start_time = now;
|
system_load.tasks[system_load.total_count].start_time = now;
|
||||||
system_load.tasks[system_load.total_count].total_runtime = 0;
|
system_load.tasks[system_load.total_count].total_runtime = 0;
|
||||||
system_load.tasks[system_load.total_count].curr_start_time = 0;
|
system_load.tasks[system_load.total_count].curr_start_time = 0;
|
||||||
system_load.tasks[system_load.total_count].tcb = sched_gettcb(system_load.total_count); // it is assumed that these static threads have consecutive PIDs
|
system_load.tasks[system_load.total_count].tcb = sched_gettcb(
|
||||||
|
system_load.total_count); // it is assumed that these static threads have consecutive PIDs
|
||||||
system_load.tasks[system_load.total_count].valid = true;
|
system_load.tasks[system_load.total_count].valid = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -62,6 +62,6 @@ __EXPORT void mcu_unique_id(uint32_t *uid_96_bit);
|
||||||
* @param revstr The full chip name string
|
* @param revstr The full chip name string
|
||||||
* @return The silicon revision / version number as integer
|
* @return The silicon revision / version number as integer
|
||||||
*/
|
*/
|
||||||
__EXPORT int mcu_version(char* rev, char** revstr);
|
__EXPORT int mcu_version(char *rev, char **revstr);
|
||||||
|
|
||||||
__END_DECLS
|
__END_DECLS
|
||||||
|
|
|
@ -76,8 +76,9 @@ MixerGroup::add_mixer(Mixer *mixer)
|
||||||
|
|
||||||
mpp = &_first;
|
mpp = &_first;
|
||||||
|
|
||||||
while (*mpp != nullptr)
|
while (*mpp != nullptr) {
|
||||||
mpp = &((*mpp)->_next);
|
mpp = &((*mpp)->_next);
|
||||||
|
}
|
||||||
|
|
||||||
*mpp = mixer;
|
*mpp = mixer;
|
||||||
mixer->_next = nullptr;
|
mixer->_next = nullptr;
|
||||||
|
@ -185,6 +186,7 @@ MixerGroup::load_from_buf(const char *buf, unsigned &buflen)
|
||||||
/* only adjust buflen if parsing was successful */
|
/* only adjust buflen if parsing was successful */
|
||||||
buflen = resid;
|
buflen = resid;
|
||||||
debug("SUCCESS - buflen: %d", buflen);
|
debug("SUCCESS - buflen: %d", buflen);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -72,7 +72,8 @@ typedef struct {
|
||||||
|
|
||||||
__EXPORT void pwm_limit_init(pwm_limit_t *limit);
|
__EXPORT void pwm_limit_init(pwm_limit_t *limit);
|
||||||
|
|
||||||
__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
|
__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm,
|
||||||
|
const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
|
||||||
|
|
||||||
__END_DECLS
|
__END_DECLS
|
||||||
|
|
||||||
|
|
|
@ -66,10 +66,11 @@ systemreset(bool to_bootloader)
|
||||||
/* XXX wow, this is evil - write a magic number into backup register zero */
|
/* XXX wow, this is evil - write a magic number into backup register zero */
|
||||||
*(uint32_t *)0x40002850 = 0xb007b007;
|
*(uint32_t *)0x40002850 = 0xb007b007;
|
||||||
}
|
}
|
||||||
|
|
||||||
up_systemreset();
|
up_systemreset();
|
||||||
|
|
||||||
/* lock up here */
|
/* lock up here */
|
||||||
while(true);
|
while (true);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);
|
static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);
|
||||||
|
@ -87,7 +88,7 @@ static void kill_task(FAR struct tcb_s *tcb, FAR void *arg)
|
||||||
kill(tcb->pid, SIGUSR1);
|
kill(tcb->pid, SIGUSR1);
|
||||||
}
|
}
|
||||||
|
|
||||||
int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char * const argv[])
|
int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char *const argv[])
|
||||||
{
|
{
|
||||||
int pid;
|
int pid;
|
||||||
|
|
||||||
|
|
|
@ -50,8 +50,7 @@
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
struct geofence_result_s
|
struct geofence_result_s {
|
||||||
{
|
|
||||||
bool geofence_violated; /**< true if the geofence is violated */
|
bool geofence_violated; /**< true if the geofence is violated */
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -55,8 +55,7 @@
|
||||||
/**
|
/**
|
||||||
* GPS home position in WGS84 coordinates.
|
* GPS home position in WGS84 coordinates.
|
||||||
*/
|
*/
|
||||||
struct home_position_s
|
struct home_position_s {
|
||||||
{
|
|
||||||
uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
|
uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
|
||||||
|
|
||||||
double lat; /**< Latitude in degrees */
|
double lat; /**< Latitude in degrees */
|
||||||
|
|
|
@ -53,8 +53,7 @@
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
|
|
||||||
struct mission_result_s
|
struct mission_result_s {
|
||||||
{
|
|
||||||
unsigned seq_reached; /**< Sequence of the mission item which has been reached */
|
unsigned seq_reached; /**< Sequence of the mission item which has been reached */
|
||||||
unsigned seq_current; /**< Sequence of the current mission item */
|
unsigned seq_current; /**< Sequence of the current mission item */
|
||||||
bool reached; /**< true if mission has been reached */
|
bool reached; /**< true if mission has been reached */
|
||||||
|
|
|
@ -60,9 +60,9 @@ typedef enum {
|
||||||
TECS_MODE_CLIMBOUT
|
TECS_MODE_CLIMBOUT
|
||||||
} tecs_mode;
|
} tecs_mode;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Internal values of the (m)TECS fixed wing speed alnd altitude control system
|
* Internal values of the (m)TECS fixed wing speed alnd altitude control system
|
||||||
*/
|
*/
|
||||||
struct tecs_status_s {
|
struct tecs_status_s {
|
||||||
uint64_t timestamp; /**< timestamp, in microseconds since system start */
|
uint64_t timestamp; /**< timestamp, in microseconds since system start */
|
||||||
|
|
||||||
|
|
|
@ -184,7 +184,8 @@ extern orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *d
|
||||||
* ORB_DEFINE with no corresponding ORB_DECLARE)
|
* ORB_DEFINE with no corresponding ORB_DECLARE)
|
||||||
* this function will return -1 and set errno to ENOENT.
|
* this function will return -1 and set errno to ENOENT.
|
||||||
*/
|
*/
|
||||||
extern orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority) __EXPORT;
|
extern orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
|
||||||
|
int priority) __EXPORT;
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -47,7 +47,7 @@ class UavcanBarometerBridge : public UavcanCDevSensorBridgeBase
|
||||||
public:
|
public:
|
||||||
static const char *const NAME;
|
static const char *const NAME;
|
||||||
|
|
||||||
UavcanBarometerBridge(uavcan::INode& node);
|
UavcanBarometerBridge(uavcan::INode &node);
|
||||||
|
|
||||||
const char *get_name() const override { return NAME; }
|
const char *get_name() const override { return NAME; }
|
||||||
|
|
||||||
|
@ -58,9 +58,9 @@ private:
|
||||||
|
|
||||||
void air_data_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData> &msg);
|
void air_data_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData> &msg);
|
||||||
|
|
||||||
typedef uavcan::MethodBinder<UavcanBarometerBridge*,
|
typedef uavcan::MethodBinder < UavcanBarometerBridge *,
|
||||||
void (UavcanBarometerBridge::*)
|
void (UavcanBarometerBridge::*)
|
||||||
(const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData>&)>
|
(const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData> &) >
|
||||||
AirDataCbBinder;
|
AirDataCbBinder;
|
||||||
|
|
||||||
uavcan::Subscriber<uavcan::equipment::air_data::StaticAirData, AirDataCbBinder> _sub_air_data;
|
uavcan::Subscriber<uavcan::equipment::air_data::StaticAirData, AirDataCbBinder> _sub_air_data;
|
||||||
|
|
|
@ -56,7 +56,7 @@ class UavcanGnssBridge : public IUavcanSensorBridge
|
||||||
public:
|
public:
|
||||||
static const char *const NAME;
|
static const char *const NAME;
|
||||||
|
|
||||||
UavcanGnssBridge(uavcan::INode& node);
|
UavcanGnssBridge(uavcan::INode &node);
|
||||||
|
|
||||||
const char *get_name() const override { return NAME; }
|
const char *get_name() const override { return NAME; }
|
||||||
|
|
||||||
|
@ -72,8 +72,8 @@ private:
|
||||||
*/
|
*/
|
||||||
void gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &msg);
|
void gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &msg);
|
||||||
|
|
||||||
typedef uavcan::MethodBinder<UavcanGnssBridge*,
|
typedef uavcan::MethodBinder < UavcanGnssBridge *,
|
||||||
void (UavcanGnssBridge::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix>&)>
|
void (UavcanGnssBridge::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &) >
|
||||||
FixCbBinder;
|
FixCbBinder;
|
||||||
|
|
||||||
uavcan::INode &_node;
|
uavcan::INode &_node;
|
||||||
|
|
|
@ -47,7 +47,7 @@ class UavcanMagnetometerBridge : public UavcanCDevSensorBridgeBase
|
||||||
public:
|
public:
|
||||||
static const char *const NAME;
|
static const char *const NAME;
|
||||||
|
|
||||||
UavcanMagnetometerBridge(uavcan::INode& node);
|
UavcanMagnetometerBridge(uavcan::INode &node);
|
||||||
|
|
||||||
const char *get_name() const override { return NAME; }
|
const char *get_name() const override { return NAME; }
|
||||||
|
|
||||||
|
@ -59,9 +59,9 @@ private:
|
||||||
|
|
||||||
void mag_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer> &msg);
|
void mag_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer> &msg);
|
||||||
|
|
||||||
typedef uavcan::MethodBinder<UavcanMagnetometerBridge*,
|
typedef uavcan::MethodBinder < UavcanMagnetometerBridge *,
|
||||||
void (UavcanMagnetometerBridge::*)
|
void (UavcanMagnetometerBridge::*)
|
||||||
(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer>&)>
|
(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer> &) >
|
||||||
MagCbBinder;
|
MagCbBinder;
|
||||||
|
|
||||||
uavcan::Subscriber<uavcan::equipment::ahrs::Magnetometer, MagCbBinder> _sub_mag;
|
uavcan::Subscriber<uavcan::equipment::ahrs::Magnetometer, MagCbBinder> _sub_mag;
|
||||||
|
|
|
@ -82,7 +82,7 @@ public:
|
||||||
|
|
||||||
static int start(uavcan::NodeID node_id, uint32_t bitrate);
|
static int start(uavcan::NodeID node_id, uint32_t bitrate);
|
||||||
|
|
||||||
Node& get_node() { return _node; }
|
Node &get_node() { return _node; }
|
||||||
|
|
||||||
// TODO: move the actuator mixing stuff into the ESC controller class
|
// TODO: move the actuator mixing stuff into the ESC controller class
|
||||||
static int control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input);
|
static int control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input);
|
||||||
|
@ -94,7 +94,7 @@ public:
|
||||||
|
|
||||||
void print_info();
|
void print_info();
|
||||||
|
|
||||||
static UavcanNode* instance() { return _instance; }
|
static UavcanNode *instance() { return _instance; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void fill_node_info();
|
void fill_node_info();
|
||||||
|
@ -122,7 +122,7 @@ private:
|
||||||
|
|
||||||
UavcanEscController _esc_controller;
|
UavcanEscController _esc_controller;
|
||||||
|
|
||||||
List<IUavcanSensorBridge*> _sensor_bridges; ///< List of active sensor bridges
|
List<IUavcanSensorBridge *> _sensor_bridges; ///< List of active sensor bridges
|
||||||
|
|
||||||
MixerGroup *_mixers = nullptr;
|
MixerGroup *_mixers = nullptr;
|
||||||
|
|
||||||
|
|
|
@ -57,13 +57,14 @@ void UnitTest::print_results(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
/// @brief Used internally to the ut_assert macro to print assert failures.
|
/// @brief Used internally to the ut_assert macro to print assert failures.
|
||||||
void UnitTest::_print_assert(const char* msg, const char* test, const char* file, int line)
|
void UnitTest::_print_assert(const char *msg, const char *test, const char *file, int line)
|
||||||
{
|
{
|
||||||
warnx("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
|
warnx("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// @brief Used internally to the ut_compare macro to print assert failures.
|
/// @brief Used internally to the ut_compare macro to print assert failures.
|
||||||
void UnitTest::_print_compare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line)
|
void UnitTest::_print_compare(const char *msg, const char *v1_text, int v1, const char *v2_text, int v2,
|
||||||
|
const char *file, int line)
|
||||||
{
|
{
|
||||||
warnx("Compare failed: %s - (%s:%d) (%s:%d) (%s:%d)", msg, v1_text, v1, v2_text, v2, file, line);
|
warnx("Compare failed: %s - (%s:%d) (%s:%d) (%s:%d)", msg, v1_text, v1, v2_text, v2, file, line);
|
||||||
}
|
}
|
||||||
|
|
|
@ -39,7 +39,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#if defined(__PX4_ROS)
|
#if defined(__PX4_ROS)
|
||||||
typedef const char* PX4TopicHandle;
|
typedef const char *PX4TopicHandle;
|
||||||
#else
|
#else
|
||||||
#include <uORB/uORB.h>
|
#include <uORB/uORB.h>
|
||||||
typedef orb_id_t PX4TopicHandle;
|
typedef orb_id_t PX4TopicHandle;
|
||||||
|
@ -68,8 +68,8 @@ public:
|
||||||
|
|
||||||
virtual ~PX4Message() {};
|
virtual ~PX4Message() {};
|
||||||
|
|
||||||
virtual M& data() {return _data;}
|
virtual M &data() {return _data;}
|
||||||
virtual const M& data() const {return _data;}
|
virtual const M &data() const {return _data;}
|
||||||
private:
|
private:
|
||||||
M _data;
|
M _data;
|
||||||
};
|
};
|
||||||
|
|
|
@ -64,14 +64,16 @@ void PositionEstimator::ModelStatesCallback(const gazebo_msgs::ModelStatesConstP
|
||||||
|
|
||||||
/* Fill px4 position topic with contents from modelstates topic */
|
/* Fill px4 position topic with contents from modelstates topic */
|
||||||
int index = 0;
|
int index = 0;
|
||||||
|
|
||||||
//XXX: maybe a more clever approach would be to do this not on every loop, need to check if and when
|
//XXX: maybe a more clever approach would be to do this not on every loop, need to check if and when
|
||||||
//gazebo rearranges indexes.
|
//gazebo rearranges indexes.
|
||||||
for(std::vector<std::string>::const_iterator it = msg->name.begin(); it != msg->name.end(); ++it) {
|
for (std::vector<std::string>::const_iterator it = msg->name.begin(); it != msg->name.end(); ++it) {
|
||||||
if (*it == "iris" || *it == "ardrone") {
|
if (*it == "iris" || *it == "ardrone") {
|
||||||
index = it - msg->name.begin();
|
index = it - msg->name.begin();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
msg_v_l_pos.xy_valid = true;
|
msg_v_l_pos.xy_valid = true;
|
||||||
msg_v_l_pos.z_valid = true;
|
msg_v_l_pos.z_valid = true;
|
||||||
msg_v_l_pos.v_xy_valid = true;
|
msg_v_l_pos.v_xy_valid = true;
|
||||||
|
|
|
@ -68,11 +68,13 @@ int perf_main(int argc, char *argv[])
|
||||||
if (strcmp(argv[1], "reset") == 0) {
|
if (strcmp(argv[1], "reset") == 0) {
|
||||||
perf_reset_all();
|
perf_reset_all();
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
} else if (strcmp(argv[1], "latency") == 0) {
|
} else if (strcmp(argv[1], "latency") == 0) {
|
||||||
perf_print_latency(0 /* stdout */);
|
perf_print_latency(0 /* stdout */);
|
||||||
fflush(stdout);
|
fflush(stdout);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
printf("Usage: perf [reset | latency]\n");
|
printf("Usage: perf [reset | latency]\n");
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
|
@ -57,6 +57,7 @@ int reboot_main(int argc, char *argv[])
|
||||||
case 'b':
|
case 'b':
|
||||||
to_bootloader = true;
|
to_bootloader = true;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
errx(1, "usage: reboot [-b]\n"
|
errx(1, "usage: reboot [-b]\n"
|
||||||
" -b reboot into the bootloader");
|
" -b reboot into the bootloader");
|
||||||
|
|
|
@ -71,8 +71,9 @@ int test_adc(int argc, char *argv[])
|
||||||
/* read all channels available */
|
/* read all channels available */
|
||||||
ssize_t count = read(fd, data, sizeof(data));
|
ssize_t count = read(fd, data, sizeof(data));
|
||||||
|
|
||||||
if (count < 0)
|
if (count < 0) {
|
||||||
goto errout_with_dev;
|
goto errout_with_dev;
|
||||||
|
}
|
||||||
|
|
||||||
unsigned channels = count / sizeof(data[0]);
|
unsigned channels = count / sizeof(data[0]);
|
||||||
|
|
||||||
|
@ -88,7 +89,7 @@ int test_adc(int argc, char *argv[])
|
||||||
|
|
||||||
errout_with_dev:
|
errout_with_dev:
|
||||||
|
|
||||||
if (fd != 0) close(fd);
|
if (fd != 0) { close(fd); }
|
||||||
|
|
||||||
return OK;
|
return OK;
|
||||||
}
|
}
|
||||||
|
|
|
@ -190,7 +190,8 @@ int test_hott_telemetry(int argc, char *argv[])
|
||||||
warnx("PASS: Received %d out of %d valid byte pairs from the HoTT receiver device.", received_count, max_polls);
|
warnx("PASS: Received %d out of %d valid byte pairs from the HoTT receiver device.", received_count, max_polls);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
warnx("WARN: Received %d out of %d byte pairs of which %d were valid from the HoTT receiver device.", received_count, max_polls, valid_count);
|
warnx("WARN: Received %d out of %d byte pairs of which %d were valid from the HoTT receiver device.", received_count,
|
||||||
|
max_polls, valid_count);
|
||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -146,9 +146,10 @@ int test_uart_baudchange(int argc, char *argv[])
|
||||||
/* uart2 -> */
|
/* uart2 -> */
|
||||||
r = write(uart2, sample_uart2, sizeof(sample_uart2));
|
r = write(uart2, sample_uart2, sizeof(sample_uart2));
|
||||||
|
|
||||||
if (r > 0)
|
if (r > 0) {
|
||||||
uart2_nwrite += r;
|
uart2_nwrite += r;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
close(uart2);
|
close(uart2);
|
||||||
|
|
||||||
|
|
|
@ -8,8 +8,9 @@
|
||||||
|
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
TEST(SUMDTest, SUMD) {
|
TEST(SUMDTest, SUMD)
|
||||||
const char* filepath = "testdata/sumd_data.txt";
|
{
|
||||||
|
const char *filepath = "testdata/sumd_data.txt";
|
||||||
|
|
||||||
warnx("loading data from: %s", filepath);
|
warnx("loading data from: %s", filepath);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue