aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-01-24 00:06:10 +0100
committerAnton Babushkin <anton.babushkin@me.com>2014-01-24 00:06:10 +0100
commit58792c5ca6e42bc251dd3c92b0e79217ff5d5403 (patch)
treeea46289f1159857c26ea40f71674a3bbb06cec8e /src/modules/mavlink
parentb3d98e4a19662af44432a0436a1b5de7fb9649c9 (diff)
downloadpx4-firmware-58792c5ca6e42bc251dd3c92b0e79217ff5d5403.tar.gz
px4-firmware-58792c5ca6e42bc251dd3c92b0e79217ff5d5403.tar.bz2
px4-firmware-58792c5ca6e42bc251dd3c92b0e79217ff5d5403.zip
Use double for lat/lon in vehicle_global_position topic, use filed names lat, lon, alt, vel_n, vel_e, vel_d for global positions
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp6
-rw-r--r--src/modules/mavlink/orb_listener.c21
2 files changed, 13 insertions, 14 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 4f9c718d2..7c23488d7 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -638,9 +638,9 @@ handle_message(mavlink_message_t *msg)
hil_global_pos.lat = hil_state.lat;
hil_global_pos.lon = hil_state.lon;
hil_global_pos.alt = hil_state.alt / 1000.0f;
- hil_global_pos.vx = hil_state.vx / 100.0f;
- hil_global_pos.vy = hil_state.vy / 100.0f;
- hil_global_pos.vz = hil_state.vz / 100.0f;
+ hil_global_pos.vel_n = hil_state.vx / 100.0f;
+ hil_global_pos.vel_e = hil_state.vy / 100.0f;
+ hil_global_pos.vel_d = hil_state.vz / 100.0f;
} else {
pub_hil_global_pos = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos);
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 0b8ac6d3d..7f6237535 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -67,6 +67,7 @@ extern bool gcs_link;
struct vehicle_global_position_s global_pos;
struct vehicle_local_position_s local_pos;
+struct home_position_s home;
struct navigation_capabilities_s nav_cap;
struct vehicle_status_s v_status;
struct vehicle_control_mode_s control_mode;
@@ -247,10 +248,10 @@ l_vehicle_attitude(const struct listener *l)
hrt_abstime t = hrt_absolute_time();
if (t >= last_sent_vfr + 100000) {
last_sent_vfr = t;
- float groundspeed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy);
+ float groundspeed = sqrtf(global_pos.vel_n * global_pos.vel_n + global_pos.vel_e * global_pos.vel_e);
uint16_t heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F;
float throttle = armed.armed ? actuators_0.control[3] * 100.0f : 0.0f;
- mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed, heading, throttle, global_pos.alt, -global_pos.vz);
+ mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed, heading, throttle, global_pos.alt, -global_pos.vel_d);
}
/* send quaternion values if it exists */
@@ -380,13 +381,13 @@ l_global_position(const struct listener *l)
mavlink_msg_global_position_int_send(MAVLINK_COMM_0,
global_pos.timestamp / 1000,
- global_pos.lat,
- global_pos.lon,
+ global_pos.lat * 1e7,
+ global_pos.lon * 1e7,
global_pos.alt * 1000.0f,
- global_pos.relative_alt * 1000.0f,
- global_pos.vx * 100.0f,
- global_pos.vy * 100.0f,
- global_pos.vz * 100.0f,
+ (global_pos.alt - home.alt) * 1000.0f,
+ global_pos.vel_n * 100.0f,
+ global_pos.vel_e * 100.0f,
+ global_pos.vel_d * 100.0f,
_wrap_2pi(global_pos.yaw) * M_RAD_TO_DEG_F * 100.0f);
}
@@ -657,11 +658,9 @@ l_optical_flow(const struct listener *l)
void
l_home(const struct listener *l)
{
- struct home_position_s home;
-
orb_copy(ORB_ID(home_position), mavlink_subs.home_sub, &home);
- mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0, (int32_t)(home.lat*1e7d), (int32_t)(home.lon*1e7d), (int32_t)(home.altitude)*1e3f);
+ mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0, (int32_t)(home.lat*1e7d), (int32_t)(home.lon*1e7d), (int32_t)(home.alt)*1e3f);
}
void