aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp4
-rw-r--r--src/modules/mavlink/mavlink_main.h12
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp3
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp4
-rw-r--r--src/modules/mavlink/mavlink_stream.cpp4
5 files changed, 12 insertions, 15 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 43acee96f..026a4d6c9 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -474,7 +474,7 @@ Mavlink::get_instance_id()
return _instance_id;
}
-const mavlink_channel_t
+mavlink_channel_t
Mavlink::get_channel()
{
return _channel;
@@ -2109,7 +2109,7 @@ Mavlink::task_main(int argc, char *argv[])
write_ptr = (uint8_t*)&msg;
// Pull a single message from the buffer
- int read_count = available;
+ size_t read_count = available;
if (read_count > sizeof(mavlink_message_t)) {
read_count = sizeof(mavlink_message_t);
}
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 5f4117ae5..f94036a17 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -213,15 +213,15 @@ public:
*/
int enable_flow_control(bool enabled);
- const mavlink_channel_t get_channel();
+ mavlink_channel_t get_channel();
- void configure_stream_threadsafe(const char *stream_name, const float rate);
+ void configure_stream_threadsafe(const char *stream_name, float rate);
bool _task_should_exit; /**< if true, mavlink task should exit */
int get_mavlink_fd() { return _mavlink_fd; }
- MavlinkStream * get_streams() { return _streams; } const
+ MavlinkStream * get_streams() const { return _streams; }
/* Functions for waiting to start transmission until message received. */
@@ -311,15 +311,15 @@ private:
pthread_mutex_t _message_buffer_mutex;
- perf_counter_t _loop_perf; /**< loop performance counter */
- perf_counter_t _txerr_perf; /**< TX error counter */
-
bool _param_initialized;
param_t _param_system_id;
param_t _param_component_id;
param_t _param_system_type;
param_t _param_use_hil_gps;
+ perf_counter_t _loop_perf; /**< loop performance counter */
+ perf_counter_t _txerr_perf; /**< TX error counter */
+
/**
* Send one parameter.
*
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index e1ebc16cc..667be87b7 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -45,7 +45,6 @@
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
-#include <uORB/topics/rc_channels.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
@@ -678,7 +677,7 @@ protected:
cm_uint16_from_m_float(gps.epv),
gps.vel_m_s * 100.0f,
_wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f,
- gps.satellites_visible);
+ gps.satellites_used);
}
}
};
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index bb977d277..6d361052c 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -741,7 +741,6 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg)
hil_gps.timestamp_variance = timestamp;
hil_gps.s_variance_m_s = 5.0f;
- hil_gps.p_variance_m = hil_gps.eph * hil_gps.eph;
hil_gps.timestamp_velocity = timestamp;
hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
@@ -751,9 +750,8 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg)
hil_gps.vel_ned_valid = true;
hil_gps.cog_rad = _wrap_pi(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
- hil_gps.timestamp_satellites = timestamp;
hil_gps.fix_type = gps.fix_type;
- hil_gps.satellites_visible = gps.satellites_visible;
+ hil_gps.satellites_used = gps.satellites_visible; //TODO: rename mavlink_hil_gps_t sats visible to used?
if (_gps_pub < 0) {
_gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps);
diff --git a/src/modules/mavlink/mavlink_stream.cpp b/src/modules/mavlink/mavlink_stream.cpp
index ed6776e5c..7279206db 100644
--- a/src/modules/mavlink/mavlink_stream.cpp
+++ b/src/modules/mavlink/mavlink_stream.cpp
@@ -44,10 +44,10 @@
#include "mavlink_main.h"
MavlinkStream::MavlinkStream() :
- _last_sent(0),
+ next(nullptr),
_channel(MAVLINK_COMM_0),
_interval(1000000),
- next(nullptr)
+ _last_sent(0)
{
}