forked from Archive/PX4-Autopilot
Clean up mavlink module
Deal with all mavlink module compiler warnings. No critical errors found
This commit is contained in:
parent
65c952e134
commit
d9e3c9423e
|
@ -258,7 +258,16 @@ private:
|
|||
MavlinkOrbSubscription *status_sub;
|
||||
MavlinkOrbSubscription *pos_sp_triplet_sub;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamHeartbeat(MavlinkStreamHeartbeat &);
|
||||
MavlinkStreamHeartbeat& operator = (const MavlinkStreamHeartbeat &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamHeartbeat() : MavlinkStream(),
|
||||
status_sub(nullptr),
|
||||
pos_sp_triplet_sub(nullptr)
|
||||
{}
|
||||
|
||||
void subscribe(Mavlink *mavlink)
|
||||
{
|
||||
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
|
||||
|
@ -322,7 +331,15 @@ public:
|
|||
private:
|
||||
MavlinkOrbSubscription *status_sub;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamSysStatus(MavlinkStreamSysStatus &);
|
||||
MavlinkStreamSysStatus& operator = (const MavlinkStreamSysStatus &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamSysStatus() : MavlinkStream(),
|
||||
status_sub(nullptr)
|
||||
{}
|
||||
|
||||
void subscribe(Mavlink *mavlink)
|
||||
{
|
||||
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
|
||||
|
@ -384,8 +401,13 @@ private:
|
|||
uint64_t mag_timestamp;
|
||||
uint64_t baro_timestamp;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamHighresIMU(MavlinkStreamHighresIMU &);
|
||||
MavlinkStreamHighresIMU& operator = (const MavlinkStreamHighresIMU &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamHighresIMU() : MavlinkStream(),
|
||||
sensor_sub(nullptr),
|
||||
sensor_time(0),
|
||||
accel_timestamp(0),
|
||||
gyro_timestamp(0),
|
||||
|
@ -469,8 +491,14 @@ private:
|
|||
MavlinkOrbSubscription *att_sub;
|
||||
uint64_t att_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamAttitude(MavlinkStreamAttitude &);
|
||||
MavlinkStreamAttitude& operator = (const MavlinkStreamAttitude &);
|
||||
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamAttitude() : MavlinkStream(),
|
||||
att_sub(nullptr),
|
||||
att_time(0)
|
||||
{}
|
||||
|
||||
|
@ -520,8 +548,13 @@ private:
|
|||
MavlinkOrbSubscription *att_sub;
|
||||
uint64_t att_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamAttitudeQuaternion(MavlinkStreamAttitudeQuaternion &);
|
||||
MavlinkStreamAttitudeQuaternion& operator = (const MavlinkStreamAttitudeQuaternion &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamAttitudeQuaternion() : MavlinkStream(),
|
||||
att_sub(nullptr),
|
||||
att_time(0)
|
||||
{}
|
||||
|
||||
|
@ -589,12 +622,21 @@ private:
|
|||
MavlinkOrbSubscription *airspeed_sub;
|
||||
uint64_t airspeed_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &);
|
||||
MavlinkStreamVFRHUD& operator = (const MavlinkStreamVFRHUD &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamVFRHUD() : MavlinkStream(),
|
||||
att_sub(nullptr),
|
||||
att_time(0),
|
||||
pos_sub(nullptr),
|
||||
pos_time(0),
|
||||
armed_sub(nullptr),
|
||||
armed_time(0),
|
||||
act_sub(nullptr),
|
||||
act_time(0),
|
||||
airspeed_sub(nullptr),
|
||||
airspeed_time(0)
|
||||
{}
|
||||
|
||||
|
@ -665,8 +707,13 @@ private:
|
|||
MavlinkOrbSubscription *gps_sub;
|
||||
uint64_t gps_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamGPSRawInt(MavlinkStreamGPSRawInt &);
|
||||
MavlinkStreamGPSRawInt& operator = (const MavlinkStreamGPSRawInt &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamGPSRawInt() : MavlinkStream(),
|
||||
gps_sub(nullptr),
|
||||
gps_time(0)
|
||||
{}
|
||||
|
||||
|
@ -726,9 +773,15 @@ private:
|
|||
MavlinkOrbSubscription *home_sub;
|
||||
uint64_t home_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamGlobalPositionInt(MavlinkStreamGlobalPositionInt &);
|
||||
MavlinkStreamGlobalPositionInt& operator = (const MavlinkStreamGlobalPositionInt &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamGlobalPositionInt() : MavlinkStream(),
|
||||
pos_sub(nullptr),
|
||||
pos_time(0),
|
||||
home_sub(nullptr),
|
||||
home_time(0)
|
||||
{}
|
||||
|
||||
|
@ -789,8 +842,13 @@ private:
|
|||
MavlinkOrbSubscription *pos_sub;
|
||||
uint64_t pos_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamLocalPositionNED(MavlinkStreamLocalPositionNED &);
|
||||
MavlinkStreamLocalPositionNED& operator = (const MavlinkStreamLocalPositionNED &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamLocalPositionNED() : MavlinkStream(),
|
||||
pos_sub(nullptr),
|
||||
pos_time(0)
|
||||
{}
|
||||
|
||||
|
@ -845,8 +903,13 @@ private:
|
|||
MavlinkOrbSubscription *pos_sub;
|
||||
uint64_t pos_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamViconPositionEstimate(MavlinkStreamViconPositionEstimate &);
|
||||
MavlinkStreamViconPositionEstimate& operator = (const MavlinkStreamViconPositionEstimate &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamViconPositionEstimate() : MavlinkStream(),
|
||||
pos_sub(nullptr),
|
||||
pos_time(0)
|
||||
{}
|
||||
|
||||
|
@ -899,7 +962,15 @@ public:
|
|||
private:
|
||||
MavlinkOrbSubscription *home_sub;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamGPSGlobalOrigin(MavlinkStreamGPSGlobalOrigin &);
|
||||
MavlinkStreamGPSGlobalOrigin& operator = (const MavlinkStreamGPSGlobalOrigin &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamGPSGlobalOrigin() : MavlinkStream(),
|
||||
home_sub(nullptr)
|
||||
{}
|
||||
|
||||
void subscribe(Mavlink *mavlink)
|
||||
{
|
||||
home_sub = mavlink->add_orb_subscription(ORB_ID(home_position));
|
||||
|
@ -962,8 +1033,13 @@ private:
|
|||
MavlinkOrbSubscription *act_sub;
|
||||
uint64_t act_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamServoOutputRaw(MavlinkStreamServoOutputRaw &);
|
||||
MavlinkStreamServoOutputRaw& operator = (const MavlinkStreamServoOutputRaw &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamServoOutputRaw() : MavlinkStream(),
|
||||
act_sub(nullptr),
|
||||
act_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1033,10 +1109,17 @@ private:
|
|||
MavlinkOrbSubscription *act_sub;
|
||||
uint64_t act_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamHILControls(MavlinkStreamHILControls &);
|
||||
MavlinkStreamHILControls& operator = (const MavlinkStreamHILControls &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamHILControls() : MavlinkStream(),
|
||||
status_sub(nullptr),
|
||||
status_time(0),
|
||||
pos_sp_triplet_sub(nullptr),
|
||||
pos_sp_triplet_time(0),
|
||||
act_sub(nullptr),
|
||||
act_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1159,7 +1242,15 @@ public:
|
|||
private:
|
||||
MavlinkOrbSubscription *pos_sp_triplet_sub;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &);
|
||||
MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamGlobalPositionSetpointInt() : MavlinkStream(),
|
||||
pos_sp_triplet_sub(nullptr)
|
||||
{}
|
||||
|
||||
void subscribe(Mavlink *mavlink)
|
||||
{
|
||||
pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet));
|
||||
|
@ -1208,8 +1299,13 @@ private:
|
|||
MavlinkOrbSubscription *pos_sp_sub;
|
||||
uint64_t pos_sp_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamLocalPositionSetpoint(MavlinkStreamLocalPositionSetpoint &);
|
||||
MavlinkStreamLocalPositionSetpoint& operator = (const MavlinkStreamLocalPositionSetpoint &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(),
|
||||
pos_sp_sub(nullptr),
|
||||
pos_sp_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1261,8 +1357,13 @@ private:
|
|||
MavlinkOrbSubscription *att_sp_sub;
|
||||
uint64_t att_sp_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &);
|
||||
MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(),
|
||||
att_sp_sub(nullptr),
|
||||
att_sp_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1314,8 +1415,13 @@ private:
|
|||
MavlinkOrbSubscription *att_rates_sp_sub;
|
||||
uint64_t att_rates_sp_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &);
|
||||
MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(),
|
||||
att_rates_sp_sub(nullptr),
|
||||
att_rates_sp_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1367,8 +1473,13 @@ private:
|
|||
MavlinkOrbSubscription *rc_sub;
|
||||
uint64_t rc_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamRCChannelsRaw(MavlinkStreamRCChannelsRaw &);
|
||||
MavlinkStreamRCChannelsRaw& operator = (const MavlinkStreamRCChannelsRaw &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(),
|
||||
rc_sub(nullptr),
|
||||
rc_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1456,8 +1567,13 @@ private:
|
|||
MavlinkOrbSubscription *manual_sub;
|
||||
uint64_t manual_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamManualControl(MavlinkStreamManualControl &);
|
||||
MavlinkStreamManualControl& operator = (const MavlinkStreamManualControl &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamManualControl() : MavlinkStream(),
|
||||
manual_sub(nullptr),
|
||||
manual_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1510,8 +1626,13 @@ private:
|
|||
MavlinkOrbSubscription *flow_sub;
|
||||
uint64_t flow_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamOpticalFlow(MavlinkStreamOpticalFlow &);
|
||||
MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamOpticalFlow() : MavlinkStream(),
|
||||
flow_sub(nullptr),
|
||||
flow_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1563,8 +1684,13 @@ private:
|
|||
MavlinkOrbSubscription *att_ctrl_sub;
|
||||
uint64_t att_ctrl_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamAttitudeControls(MavlinkStreamAttitudeControls &);
|
||||
MavlinkStreamAttitudeControls& operator = (const MavlinkStreamAttitudeControls &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamAttitudeControls() : MavlinkStream(),
|
||||
att_ctrl_sub(nullptr),
|
||||
att_ctrl_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1626,8 +1752,13 @@ private:
|
|||
MavlinkOrbSubscription *debug_sub;
|
||||
uint64_t debug_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamNamedValueFloat(MavlinkStreamNamedValueFloat &);
|
||||
MavlinkStreamNamedValueFloat& operator = (const MavlinkStreamNamedValueFloat &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamNamedValueFloat() : MavlinkStream(),
|
||||
debug_sub(nullptr),
|
||||
debug_time(0)
|
||||
{}
|
||||
|
||||
|
@ -1678,7 +1809,15 @@ public:
|
|||
private:
|
||||
MavlinkOrbSubscription *status_sub;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamCameraCapture(MavlinkStreamCameraCapture &);
|
||||
MavlinkStreamCameraCapture& operator = (const MavlinkStreamCameraCapture &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamCameraCapture() : MavlinkStream(),
|
||||
status_sub(nullptr)
|
||||
{}
|
||||
|
||||
void subscribe(Mavlink *mavlink)
|
||||
{
|
||||
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
|
||||
|
@ -1729,8 +1868,13 @@ private:
|
|||
MavlinkOrbSubscription *range_sub;
|
||||
uint64_t range_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamDistanceSensor(MavlinkStreamDistanceSensor &);
|
||||
MavlinkStreamDistanceSensor& operator = (const MavlinkStreamDistanceSensor &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamDistanceSensor() : MavlinkStream(),
|
||||
range_sub(nullptr),
|
||||
range_time(0)
|
||||
{}
|
||||
|
||||
|
|
Loading…
Reference in New Issue