forked from Archive/PX4-Autopilot
Enable stricter compile mode and ensure the most relevant bits are initialized. Needs more work to avoid the remaining warnings
This commit is contained in:
parent
b0b6ee0644
commit
1ac2b307e4
|
@ -40,9 +40,12 @@
|
||||||
|
|
||||||
#include "mavlink_commands.h"
|
#include "mavlink_commands.h"
|
||||||
|
|
||||||
MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel), _cmd_time(0)
|
MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) :
|
||||||
|
_cmd_sub(mavlink->add_orb_subscription(ORB_ID(vehicle_command))),
|
||||||
|
_cmd{},
|
||||||
|
_channel(channel),
|
||||||
|
_cmd_time(0)
|
||||||
{
|
{
|
||||||
_cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
|
|
|
@ -50,16 +50,20 @@ MavlinkFTP::getServer()
|
||||||
return _server;
|
return _server;
|
||||||
}
|
}
|
||||||
|
|
||||||
MavlinkFTP::MavlinkFTP()
|
MavlinkFTP::MavlinkFTP() :
|
||||||
|
_session_fds{},
|
||||||
|
_workBufs{},
|
||||||
|
_workFree{},
|
||||||
|
_lock{}
|
||||||
{
|
{
|
||||||
// initialise the request freelist
|
// initialise the request freelist
|
||||||
dq_init(&_workFree);
|
dq_init(&_workFree);
|
||||||
sem_init(&_lock, 0, 1);
|
sem_init(&_lock, 0, 1);
|
||||||
|
|
||||||
// initialize session list
|
// initialize session list
|
||||||
for (size_t i=0; i<kMaxSession; i++) {
|
for (size_t i=0; i<kMaxSession; i++) {
|
||||||
_session_fds[i] = -1;
|
_session_fds[i] = -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// drop work entries onto the free list
|
// drop work entries onto the free list
|
||||||
for (unsigned i = 0; i < kRequestQueueSize; i++) {
|
for (unsigned i = 0; i < kRequestQueueSize; i++) {
|
||||||
|
|
|
@ -216,6 +216,7 @@ Mavlink::Mavlink() :
|
||||||
_device_name(DEFAULT_DEVICE_NAME),
|
_device_name(DEFAULT_DEVICE_NAME),
|
||||||
_task_should_exit(false),
|
_task_should_exit(false),
|
||||||
next(nullptr),
|
next(nullptr),
|
||||||
|
_instance_id(0),
|
||||||
_mavlink_fd(-1),
|
_mavlink_fd(-1),
|
||||||
_task_running(false),
|
_task_running(false),
|
||||||
_hil_enabled(false),
|
_hil_enabled(false),
|
||||||
|
@ -230,17 +231,24 @@ Mavlink::Mavlink() :
|
||||||
_mission_pub(-1),
|
_mission_pub(-1),
|
||||||
_mission_result_sub(-1),
|
_mission_result_sub(-1),
|
||||||
_mode(MAVLINK_MODE_NORMAL),
|
_mode(MAVLINK_MODE_NORMAL),
|
||||||
|
_channel(MAVLINK_COMM_0),
|
||||||
|
_logbuffer{},
|
||||||
_total_counter(0),
|
_total_counter(0),
|
||||||
|
_receive_thread{},
|
||||||
_verbose(false),
|
_verbose(false),
|
||||||
_forwarding_on(false),
|
_forwarding_on(false),
|
||||||
_passing_on(false),
|
_passing_on(false),
|
||||||
_ftp_on(false),
|
_ftp_on(false),
|
||||||
_uart_fd(-1),
|
_uart_fd(-1),
|
||||||
|
_baudrate(57600),
|
||||||
|
_datarate(10000),
|
||||||
_mavlink_param_queue_index(0),
|
_mavlink_param_queue_index(0),
|
||||||
|
mavlink_link_termination_allowed(false),
|
||||||
_subscribe_to_stream(nullptr),
|
_subscribe_to_stream(nullptr),
|
||||||
_subscribe_to_stream_rate(0.0f),
|
_subscribe_to_stream_rate(0.0f),
|
||||||
_flow_control_enabled(true),
|
_flow_control_enabled(true),
|
||||||
_message_buffer({}),
|
_message_buffer{},
|
||||||
|
_message_buffer_mutex{},
|
||||||
_param_initialized(false),
|
_param_initialized(false),
|
||||||
_param_system_id(0),
|
_param_system_id(0),
|
||||||
_param_component_id(0),
|
_param_component_id(0),
|
||||||
|
|
|
@ -372,4 +372,8 @@ private:
|
||||||
* Main mavlink task.
|
* Main mavlink task.
|
||||||
*/
|
*/
|
||||||
int task_main(int argc, char *argv[]);
|
int task_main(int argc, char *argv[]);
|
||||||
|
|
||||||
|
/* do not allow copying this class */
|
||||||
|
Mavlink(const Mavlink&);
|
||||||
|
Mavlink operator=(const Mavlink&);
|
||||||
};
|
};
|
||||||
|
|
|
@ -174,4 +174,8 @@ private:
|
||||||
|
|
||||||
mavlink_channel_t _channel;
|
mavlink_channel_t _channel;
|
||||||
uint8_t _comp_id;
|
uint8_t _comp_id;
|
||||||
|
|
||||||
|
/* do not allow copying this class */
|
||||||
|
MavlinkMissionManager(const MavlinkMissionManager&);
|
||||||
|
MavlinkMissionManager operator=(const MavlinkMissionManager&);
|
||||||
};
|
};
|
||||||
|
|
|
@ -82,6 +82,10 @@ private:
|
||||||
const orb_id_t _topic; ///< topic metadata
|
const orb_id_t _topic; ///< topic metadata
|
||||||
int _fd; ///< subscription handle
|
int _fd; ///< subscription handle
|
||||||
bool _published; ///< topic was ever published
|
bool _published; ///< topic was ever published
|
||||||
|
|
||||||
|
/* do not allow copying this class */
|
||||||
|
MavlinkOrbSubscription(const MavlinkOrbSubscription&);
|
||||||
|
MavlinkOrbSubscription operator=(const MavlinkOrbSubscription&);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -86,7 +86,9 @@ static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f;
|
||||||
|
|
||||||
MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
||||||
_mavlink(parent),
|
_mavlink(parent),
|
||||||
|
status{},
|
||||||
|
hil_local_pos{},
|
||||||
|
_control_mode{},
|
||||||
_global_pos_pub(-1),
|
_global_pos_pub(-1),
|
||||||
_local_pos_pub(-1),
|
_local_pos_pub(-1),
|
||||||
_attitude_pub(-1),
|
_attitude_pub(-1),
|
||||||
|
@ -111,15 +113,13 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
||||||
_manual_pub(-1),
|
_manual_pub(-1),
|
||||||
_telemetry_heartbeat_time(0),
|
_telemetry_heartbeat_time(0),
|
||||||
_radio_status_available(false),
|
_radio_status_available(false),
|
||||||
_control_mode_sub(-1),
|
_control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
|
||||||
_hil_frames(0),
|
_hil_frames(0),
|
||||||
_old_timestamp(0),
|
_old_timestamp(0),
|
||||||
_hil_local_proj_inited(0),
|
_hil_local_proj_inited(0),
|
||||||
_hil_local_alt0(0.0)
|
_hil_local_alt0(0.0f),
|
||||||
|
_hil_local_proj_ref{}
|
||||||
{
|
{
|
||||||
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
|
|
||||||
memset(&hil_local_pos, 0, sizeof(hil_local_pos));
|
|
||||||
memset(&_control_mode, 0, sizeof(_control_mode));
|
|
||||||
|
|
||||||
// make sure the FTP server is started
|
// make sure the FTP server is started
|
||||||
(void)MavlinkFTP::getServer();
|
(void)MavlinkFTP::getServer();
|
||||||
|
|
|
@ -156,4 +156,8 @@ private:
|
||||||
bool _hil_local_proj_inited;
|
bool _hil_local_proj_inited;
|
||||||
float _hil_local_alt0;
|
float _hil_local_alt0;
|
||||||
struct map_projection_reference_s _hil_local_proj_ref;
|
struct map_projection_reference_s _hil_local_proj_ref;
|
||||||
|
|
||||||
|
/* do not allow copying this class */
|
||||||
|
MavlinkReceiver(const MavlinkReceiver&);
|
||||||
|
MavlinkReceiver operator=(const MavlinkReceiver&);
|
||||||
};
|
};
|
||||||
|
|
|
@ -77,6 +77,10 @@ protected:
|
||||||
|
|
||||||
private:
|
private:
|
||||||
hrt_abstime _last_sent;
|
hrt_abstime _last_sent;
|
||||||
|
|
||||||
|
/* do not allow top copying this class */
|
||||||
|
MavlinkStream(const MavlinkStream&);
|
||||||
|
MavlinkStream& operator=(const MavlinkStream&);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -52,3 +52,5 @@ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
|
||||||
MAXOPTIMIZATION = -Os
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
||||||
MODULE_STACKSIZE = 1024
|
MODULE_STACKSIZE = 1024
|
||||||
|
|
||||||
|
EXTRACXXFLAGS = -Weffc++
|
||||||
|
|
Loading…
Reference in New Issue