mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 22:48:29 -04:00
AP_HAL_Linux: re-order initialiser lines so -Werror=reorder will work
This commit is contained in:
parent
cc9279713a
commit
27df5e0479
@ -16,11 +16,11 @@ const char* AnalogSource_IIO::analog_sources[] = {
|
|||||||
};
|
};
|
||||||
|
|
||||||
AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling) :
|
AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling) :
|
||||||
_pin(pin),
|
|
||||||
_value(initial_value),
|
_value(initial_value),
|
||||||
_voltage_scaling(voltage_scaling),
|
|
||||||
_sum_value(0),
|
_sum_value(0),
|
||||||
|
_voltage_scaling(voltage_scaling),
|
||||||
_sum_count(0),
|
_sum_count(0),
|
||||||
|
_pin(pin),
|
||||||
_pin_fd(-1)
|
_pin_fd(-1)
|
||||||
{
|
{
|
||||||
init_pins();
|
init_pins();
|
||||||
|
@ -58,8 +58,8 @@ class CANIface: public AP_HAL::CANIface {
|
|||||||
public:
|
public:
|
||||||
CANIface(int index)
|
CANIface(int index)
|
||||||
: _self_index(index)
|
: _self_index(index)
|
||||||
, _frames_in_socket_tx_queue(0)
|
|
||||||
, _max_frames_in_socket_tx_queue(2)
|
, _max_frames_in_socket_tx_queue(2)
|
||||||
|
, _frames_in_socket_tx_queue(0)
|
||||||
{ }
|
{ }
|
||||||
|
|
||||||
~CANIface() { }
|
~CANIface() { }
|
||||||
|
@ -113,8 +113,8 @@ CameraSensor_Mt9v117::CameraSensor_Mt9v117(const char *device_path,
|
|||||||
uint16_t nrst_gpio, uint32_t clock_freq)
|
uint16_t nrst_gpio, uint32_t clock_freq)
|
||||||
: CameraSensor(device_path)
|
: CameraSensor(device_path)
|
||||||
, _dev(std::move(dev))
|
, _dev(std::move(dev))
|
||||||
, _nrst_gpio(nrst_gpio)
|
|
||||||
, _clock_freq(clock_freq)
|
, _clock_freq(clock_freq)
|
||||||
|
, _nrst_gpio(nrst_gpio)
|
||||||
{
|
{
|
||||||
if (!_dev) {
|
if (!_dev) {
|
||||||
AP_HAL::panic("Could not find I2C bus for CameraSensor_Mt9v117");
|
AP_HAL::panic("Could not find I2C bus for CameraSensor_Mt9v117");
|
||||||
|
@ -36,8 +36,8 @@ union gpio_params {
|
|||||||
#define GPIO_PATH_MAX (sizeof(GPIO_BASE_PATH) + sizeof(gpio_params) - 1)
|
#define GPIO_PATH_MAX (sizeof(GPIO_BASE_PATH) + sizeof(gpio_params) - 1)
|
||||||
|
|
||||||
DigitalSource_Sysfs::DigitalSource_Sysfs(unsigned pin, int value_fd)
|
DigitalSource_Sysfs::DigitalSource_Sysfs(unsigned pin, int value_fd)
|
||||||
: _pin(pin)
|
: _value_fd(value_fd)
|
||||||
, _value_fd(value_fd)
|
, _pin(pin)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -33,12 +33,12 @@ namespace Linux {
|
|||||||
PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path,
|
PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path,
|
||||||
char* enable_path, char* duty_path,
|
char* enable_path, char* duty_path,
|
||||||
char* period_path, uint8_t channel)
|
char* period_path, uint8_t channel)
|
||||||
: _export_path(export_path)
|
: _channel(channel)
|
||||||
|
, _export_path(export_path)
|
||||||
, _polarity_path(polarity_path)
|
, _polarity_path(polarity_path)
|
||||||
, _enable_path(enable_path)
|
, _enable_path(enable_path)
|
||||||
, _duty_path(duty_path)
|
, _duty_path(duty_path)
|
||||||
, _period_path(period_path)
|
, _period_path(period_path)
|
||||||
, _channel(channel)
|
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -116,7 +116,8 @@ private:
|
|||||||
prev_tick(0), delta_time(0),
|
prev_tick(0), delta_time(0),
|
||||||
width_s0(0), width_s1(0),
|
width_s0(0), width_s1(0),
|
||||||
curr_signal(0), last_signal(0),
|
curr_signal(0), last_signal(0),
|
||||||
enable_pin(0), state(RCIN_RPI_INITIAL_STATE)
|
state(RCIN_RPI_INITIAL_STATE),
|
||||||
|
enable_pin(0)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
uint64_t prev_tick;
|
uint64_t prev_tick;
|
||||||
|
@ -62,8 +62,8 @@ RCOutput_PCA9685::RCOutput_PCA9685(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
|||||||
uint32_t external_clock,
|
uint32_t external_clock,
|
||||||
uint8_t channel_offset,
|
uint8_t channel_offset,
|
||||||
int16_t oe_pin_number) :
|
int16_t oe_pin_number) :
|
||||||
_dev(std::move(dev)),
|
|
||||||
_enable_pin(nullptr),
|
_enable_pin(nullptr),
|
||||||
|
_dev(std::move(dev)),
|
||||||
_frequency(50),
|
_frequency(50),
|
||||||
_pulses_buffer(NEW_NOTHROW uint16_t[PWM_CHAN_COUNT - channel_offset]),
|
_pulses_buffer(NEW_NOTHROW uint16_t[PWM_CHAN_COUNT - channel_offset]),
|
||||||
_external_clock(external_clock),
|
_external_clock(external_clock),
|
||||||
|
Loading…
Reference in New Issue
Block a user