forked from Archive/PX4-Autopilot
mavlink: Compile warning fixes
This commit is contained in:
parent
e7212df5e8
commit
c60561b705
|
@ -149,10 +149,7 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
|
|||
instance = Mavlink::get_instance(6);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* no valid instance, bail */
|
||||
if (!instance) {
|
||||
default:
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -211,9 +208,9 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
|
|||
static void usage(void);
|
||||
|
||||
Mavlink::Mavlink() :
|
||||
next(nullptr),
|
||||
_device_name(DEFAULT_DEVICE_NAME),
|
||||
_task_should_exit(false),
|
||||
next(nullptr),
|
||||
_mavlink_fd(-1),
|
||||
_task_running(false),
|
||||
_hil_enabled(false),
|
||||
|
@ -234,7 +231,6 @@ Mavlink::Mavlink() :
|
|||
_subscribe_to_stream_rate(0.0f),
|
||||
_flow_control_enabled(true),
|
||||
_message_buffer({}),
|
||||
|
||||
/* performance counters */
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "mavlink"))
|
||||
{
|
||||
|
@ -2030,14 +2026,14 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
if (_subscribe_to_stream != nullptr) {
|
||||
if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) {
|
||||
if (_subscribe_to_stream_rate > 0.0f) {
|
||||
warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, _subscribe_to_stream_rate);
|
||||
warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, (double)_subscribe_to_stream_rate);
|
||||
|
||||
} else {
|
||||
warnx("stream %s on device %s disabled", _subscribe_to_stream, _device_name);
|
||||
}
|
||||
|
||||
} else {
|
||||
warnx("stream %s not found", _subscribe_to_stream, _device_name);
|
||||
warnx("stream %s on device %s not found", _subscribe_to_stream, _device_name);
|
||||
}
|
||||
|
||||
delete _subscribe_to_stream;
|
||||
|
@ -2243,7 +2239,6 @@ Mavlink::stream(int argc, char *argv[])
|
|||
const char *device_name = DEFAULT_DEVICE_NAME;
|
||||
float rate = -1.0f;
|
||||
const char *stream_name = nullptr;
|
||||
int ch;
|
||||
|
||||
argc -= 2;
|
||||
argv += 2;
|
||||
|
@ -2280,7 +2275,7 @@ Mavlink::stream(int argc, char *argv[])
|
|||
i++;
|
||||
}
|
||||
|
||||
if (!err_flag && rate >= 0.0 && stream_name != nullptr) {
|
||||
if (!err_flag && rate >= 0.0f && stream_name != nullptr) {
|
||||
Mavlink *inst = get_instance_for_device(device_name);
|
||||
|
||||
if (inst != nullptr) {
|
||||
|
|
|
@ -221,8 +221,6 @@ private:
|
|||
int _mavlink_fd;
|
||||
bool _task_running;
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
||||
/* states */
|
||||
bool _hil_enabled; /**< Hardware In the Loop mode */
|
||||
bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
|
||||
|
@ -282,7 +280,7 @@ private:
|
|||
|
||||
pthread_mutex_t _message_buffer_mutex;
|
||||
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
||||
/**
|
||||
* Send one parameter.
|
||||
|
|
|
@ -63,7 +63,7 @@ MavlinkOrbSubscription::~MavlinkOrbSubscription()
|
|||
free(_data);
|
||||
}
|
||||
|
||||
const orb_id_t
|
||||
orb_id_t
|
||||
MavlinkOrbSubscription::get_topic()
|
||||
{
|
||||
return _topic;
|
||||
|
|
|
@ -63,7 +63,7 @@ public:
|
|||
*/
|
||||
bool is_published();
|
||||
void *get_data();
|
||||
const orb_id_t get_topic();
|
||||
orb_id_t get_topic();
|
||||
|
||||
private:
|
||||
const orb_id_t _topic; /*< topic metadata */
|
||||
|
|
|
@ -932,6 +932,8 @@ void *MavlinkReceiver::start_helper(void *context)
|
|||
rcv->receive_thread(NULL);
|
||||
|
||||
delete rcv;
|
||||
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
pthread_t
|
||||
|
|
|
@ -81,5 +81,9 @@ MavlinkStream::update(const hrt_abstime t)
|
|||
/* interval expired, send message */
|
||||
send(t);
|
||||
_last_sent = (t / _interval) * _interval;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
|
|
@ -63,9 +63,13 @@ public:
|
|||
MavlinkStream *next;
|
||||
|
||||
MavlinkStream();
|
||||
~MavlinkStream();
|
||||
virtual ~MavlinkStream();
|
||||
void set_interval(const unsigned int interval);
|
||||
void set_channel(mavlink_channel_t channel);
|
||||
|
||||
/**
|
||||
* @return 0 if updated / sent, -1 if unchanged
|
||||
*/
|
||||
int update(const hrt_abstime t);
|
||||
virtual MavlinkStream *new_instance() = 0;
|
||||
virtual void subscribe(Mavlink *mavlink) = 0;
|
||||
|
|
Loading…
Reference in New Issue