mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
Migrate an additional set of 16 variable initilializations from the Mavlink class constructor list to their respective declarations.
This commit is contained in:
committed by
Mathieu Bresciani
parent
903deb7579
commit
73fb30f251
@@ -162,26 +162,6 @@ bool Mavlink::_boot_complete = false;
|
||||
|
||||
Mavlink::Mavlink() :
|
||||
ModuleParams(nullptr),
|
||||
_task_should_exit(false),
|
||||
_mavlink_log_pub(nullptr),
|
||||
_main_loop_delay(1000),
|
||||
_mavlink_shell(nullptr),
|
||||
_mavlink_ulog(nullptr),
|
||||
_mavlink_ulog_stop_requested(false),
|
||||
_logbuffer(5, sizeof(mavlink_log_s)),
|
||||
_receive_thread{},
|
||||
_forwarding_on(false),
|
||||
_ftp_on(false),
|
||||
_uart_fd(-1),
|
||||
_baudrate(57600),
|
||||
_datarate(1000),
|
||||
_rate_mult(1.0f),
|
||||
_mavlink_param_queue_index(0),
|
||||
mavlink_link_termination_allowed(false),
|
||||
_subscribe_to_stream(nullptr),
|
||||
_subscribe_to_stream_rate(0.0f),
|
||||
_udp_initialised(false),
|
||||
_flow_control_mode(Mavlink::FLOW_CONTROL_OFF),
|
||||
_last_write_success_time(0),
|
||||
_last_write_try_time(0),
|
||||
_mavlink_start_time(0),
|
||||
|
||||
@@ -353,8 +353,6 @@ public:
|
||||
|
||||
void configure_stream_threadsafe(const char *stream_name, float rate = -1.0f);
|
||||
|
||||
bool _task_should_exit; /**< if true, mavlink task should exit */
|
||||
|
||||
orb_advert_t *get_mavlink_log_pub() { return &_mavlink_log_pub; }
|
||||
|
||||
/**
|
||||
@@ -453,6 +451,8 @@ public:
|
||||
|
||||
int get_socket_fd() { return _socket_fd; };
|
||||
|
||||
bool _task_should_exit{false}; /**< Mavlink task should exit iff true. */
|
||||
|
||||
#ifdef __PX4_POSIX
|
||||
const in_addr query_netmask_addr(const int socket_fd, const ifreq &ifreq);
|
||||
|
||||
@@ -553,7 +553,7 @@ private:
|
||||
bool _wait_to_transmit{false}; /**< Wait to transmit until received messages. */
|
||||
bool _received_messages{false}; /**< Whether we've received valid mavlink messages. */
|
||||
|
||||
unsigned _main_loop_delay; /**< mainloop delay, depends on data rate */
|
||||
unsigned _main_loop_delay{1000}; /**< mainloop delay, depends on data rate */
|
||||
|
||||
List<MavlinkOrbSubscription *> _subscriptions;
|
||||
List<MavlinkStream *> _streams;
|
||||
@@ -567,18 +567,18 @@ private:
|
||||
|
||||
mavlink_channel_t _channel{MAVLINK_COMM_0};
|
||||
|
||||
ringbuffer::RingBuffer _logbuffer;
|
||||
ringbuffer::RingBuffer _logbuffer{5, sizeof(mavlink_log_s)};
|
||||
|
||||
pthread_t _receive_thread;
|
||||
pthread_t _receive_thread {};
|
||||
|
||||
bool _forwarding_on;
|
||||
bool _ftp_on;
|
||||
bool _forwarding_on{false};
|
||||
bool _ftp_on{false};
|
||||
|
||||
int _uart_fd;
|
||||
int _uart_fd{-1};
|
||||
|
||||
int _baudrate;
|
||||
int _datarate; ///< data rate for normal streams (attitude, position, etc.)
|
||||
float _rate_mult;
|
||||
int _baudrate{57600};
|
||||
int _datarate{1000}; ///< data rate for normal streams (attitude, position, etc.)
|
||||
float _rate_mult{1.0f};
|
||||
|
||||
bool _radio_status_available{false};
|
||||
bool _radio_status_critical{false};
|
||||
@@ -589,15 +589,16 @@ private:
|
||||
* logic will send parameters from the current index
|
||||
* to len - 1, the end of the param list.
|
||||
*/
|
||||
unsigned int _mavlink_param_queue_index;
|
||||
unsigned int _mavlink_param_queue_index{0};
|
||||
|
||||
bool mavlink_link_termination_allowed;
|
||||
bool mavlink_link_termination_allowed{false};
|
||||
|
||||
char *_subscribe_to_stream;
|
||||
float _subscribe_to_stream_rate; ///< rate of stream to subscribe to (0=disable, -1=unlimited, -2=default)
|
||||
bool _udp_initialised;
|
||||
char *_subscribe_to_stream{nullptr};
|
||||
float _subscribe_to_stream_rate{0.0f}; ///< rate of stream to subscribe to (0=disable, -1=unlimited, -2=default)
|
||||
bool _udp_initialised{false};
|
||||
|
||||
FLOW_CONTROL_MODE _flow_control_mode{Mavlink::FLOW_CONTROL_OFF};
|
||||
|
||||
enum FLOW_CONTROL_MODE _flow_control_mode;
|
||||
uint64_t _last_write_success_time;
|
||||
uint64_t _last_write_try_time;
|
||||
uint64_t _mavlink_start_time;
|
||||
|
||||
Reference in New Issue
Block a user