mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-19 03:59:05 +08:00
Move variable initializations to header file that were no longer in the correct order in the constructor list.
This commit is contained in:
parent
8a6a5cc310
commit
6762f09490
@ -132,10 +132,6 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
||||
_debug_array_pub(nullptr),
|
||||
_gps_inject_data_pub(nullptr),
|
||||
_command_ack_pub(nullptr),
|
||||
_control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
|
||||
_actuator_armed_sub(orb_subscribe(ORB_ID(actuator_armed))),
|
||||
_vehicle_attitude_sub(orb_subscribe(ORB_ID(vehicle_attitude))),
|
||||
_global_ref_timestamp(0),
|
||||
_hil_frames(0),
|
||||
_old_timestamp(0),
|
||||
_hil_local_proj_inited(0),
|
||||
|
||||
@ -253,12 +253,13 @@ private:
|
||||
|
||||
static const int _gps_inject_data_queue_size = 6;
|
||||
|
||||
int _actuator_armed_sub;
|
||||
int _control_mode_sub;
|
||||
int _hil_frames;
|
||||
int _vehicle_attitude_sub;
|
||||
int _actuator_armed_sub{orb_subscribe(ORB_ID(actuator_armed))};
|
||||
int _control_mode_sub{orb_subscribe(ORB_ID(vehicle_control_mode))};
|
||||
int _vehicle_attitude_sub{orb_subscribe(ORB_ID(vehicle_attitude))};
|
||||
|
||||
uint64_t _global_ref_timestamp;
|
||||
int _hil_frames;
|
||||
|
||||
uint64_t _global_ref_timestamp{0};
|
||||
uint64_t _old_timestamp;
|
||||
|
||||
bool _hil_local_proj_inited;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user