aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_main.cpp
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-05-21 14:21:47 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-05-21 14:21:47 +0200
commitc60561b705ddb557ce9b50cc3e41f36018708ef4 (patch)
tree210ed5a74d749141fe5066dccac8d83bfbc49c98 /src/modules/mavlink/mavlink_main.cpp
parente7212df5e8b783df8e3f65db3a649804e81e2ee9 (diff)
downloadpx4-firmware-c60561b705ddb557ce9b50cc3e41f36018708ef4.tar.gz
px4-firmware-c60561b705ddb557ce9b50cc3e41f36018708ef4.tar.bz2
px4-firmware-c60561b705ddb557ce9b50cc3e41f36018708ef4.zip
mavlink: Compile warning fixes
Diffstat (limited to 'src/modules/mavlink/mavlink_main.cpp')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp15
1 files changed, 5 insertions, 10 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 6c97bfca7..28dd97fca 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -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) {