aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp68
-rw-r--r--src/modules/mavlink/mavlink_receiver.h2
2 files changed, 22 insertions, 48 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index b4fe65fd2..0762b76f2 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -88,8 +88,6 @@ static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f;
MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_mavlink(parent),
- _manual_sub(-1),
-
_global_pos_pub(-1),
_local_pos_pub(-1),
_attitude_pub(-1),
@@ -247,6 +245,7 @@ MavlinkReceiver::handle_message_optical_flow(mavlink_message_t *msg)
memset(&f, 0, sizeof(f));
f.timestamp = hrt_absolute_time();
+ f.flow_timestamp = flow.time_usec;
f.flow_raw_x = flow.flow_x;
f.flow_raw_y = flow.flow_y;
f.flow_comp_x_m = flow.flow_comp_m_x;
@@ -417,47 +416,20 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
mavlink_manual_control_t man;
mavlink_msg_manual_control_decode(msg, &man);
- /* rc channels */
- {
- struct rc_channels_s rc;
- memset(&rc, 0, sizeof(rc));
-
- rc.timestamp = hrt_absolute_time();
- rc.chan_count = 4;
+ struct manual_control_setpoint_s manual;
+ memset(&manual, 0, sizeof(manual));
- rc.chan[0].scaled = man.x / 1000.0f;
- rc.chan[1].scaled = man.y / 1000.0f;
- rc.chan[2].scaled = man.r / 1000.0f;
- rc.chan[3].scaled = man.z / 1000.0f;
+ manual.timestamp = hrt_absolute_time();
+ manual.roll = man.x / 1000.0f;
+ manual.pitch = man.y / 1000.0f;
+ manual.yaw = man.r / 1000.0f;
+ manual.throttle = man.z / 1000.0f;
- if (_rc_pub < 0) {
- _rc_pub = orb_advertise(ORB_ID(rc_channels), &rc);
-
- } else {
- orb_publish(ORB_ID(rc_channels), _rc_pub, &rc);
- }
- }
-
- /* manual control */
- {
- struct manual_control_setpoint_s manual;
- memset(&manual, 0, sizeof(manual));
+ if (_manual_pub < 0) {
+ _manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
- /* get a copy first, to prevent altering values that are not sent by the mavlink command */
- orb_copy(ORB_ID(manual_control_setpoint), _manual_sub, &manual);
-
- manual.timestamp = hrt_absolute_time();
- manual.roll = man.x / 1000.0f;
- manual.pitch = man.y / 1000.0f;
- manual.yaw = man.r / 1000.0f;
- manual.throttle = man.z / 1000.0f;
-
- if (_manual_pub < 0) {
- _manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
-
- } else {
- orb_publish(ORB_ID(manual_control_setpoint), _manual_pub, &manual);
- }
+ } else {
+ orb_publish(ORB_ID(manual_control_setpoint), _manual_pub, &manual);
}
}
@@ -768,7 +740,6 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
memset(&hil_global_pos, 0, sizeof(hil_global_pos));
hil_global_pos.timestamp = timestamp;
- hil_global_pos.global_valid = true;
hil_global_pos.lat = hil_state.lat;
hil_global_pos.lon = hil_state.lon;
hil_global_pos.alt = hil_state.alt / 1000.0f;
@@ -776,6 +747,8 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
hil_global_pos.vel_e = hil_state.vy / 100.0f;
hil_global_pos.vel_d = hil_state.vz / 100.0f;
hil_global_pos.yaw = hil_attitude.yaw;
+ hil_global_pos.eph = 2.0f;
+ hil_global_pos.epv = 4.0f;
if (_global_pos_pub < 0) {
_global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos);
@@ -787,19 +760,22 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
/* local position */
{
+ double lat = hil_state.lat * 1e-7;
+ double lon = hil_state.lon * 1e-7;
+
if (!_hil_local_proj_inited) {
_hil_local_proj_inited = true;
_hil_local_alt0 = hil_state.alt / 1000.0f;
- map_projection_init(hil_state.lat, hil_state.lon);
+ map_projection_init(&_hil_local_proj_ref, hil_state.lat, hil_state.lon);
hil_local_pos.ref_timestamp = timestamp;
- hil_local_pos.ref_lat = hil_state.lat;
- hil_local_pos.ref_lon = hil_state.lon;
+ hil_local_pos.ref_lat = lat;
+ hil_local_pos.ref_lon = lon;
hil_local_pos.ref_alt = _hil_local_alt0;
}
float x;
float y;
- map_projection_project(hil_state.lat * 1e-7, hil_state.lon * 1e-7, &x, &y);
+ map_projection_project(&_hil_local_proj_ref, lat, lon, &x, &y);
hil_local_pos.timestamp = timestamp;
hil_local_pos.xy_valid = true;
hil_local_pos.z_valid = true;
@@ -887,8 +863,6 @@ MavlinkReceiver::receive_thread(void *arg)
sprintf(thread_name, "mavlink_rcv_if%d", _mavlink->get_instance_id());
prctl(PR_SET_NAME, thread_name, getpid());
- _manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
-
struct pollfd fds[1];
fds[0].fd = uart_fd;
fds[0].events = POLLIN;
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 8ccb2a035..9ab84b58a 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -138,9 +138,9 @@ private:
orb_advert_t _telemetry_status_pub;
orb_advert_t _rc_pub;
orb_advert_t _manual_pub;
- int _manual_sub;
int _hil_frames;
uint64_t _old_timestamp;
bool _hil_local_proj_inited;
float _hil_local_alt0;
+ struct map_projection_reference_s _hil_local_proj_ref;
};