aboutsummaryrefslogtreecommitdiff
path: root/apps/mavlink
diff options
context:
space:
mode:
authorJulian Oes <joes@student.ethz.ch>2013-02-06 12:41:05 -0800
committerJulian Oes <joes@student.ethz.ch>2013-02-06 12:41:05 -0800
commitfc4be3e7280db480b67b7c6cec11e35481969bbb (patch)
tree90f760ad4022a3ad568a815e3a89e29cd4e47d48 /apps/mavlink
parenta79ad17f09ac69bf2a19a4f617fa1df16bcaa6be (diff)
downloadpx4-firmware-fc4be3e7280db480b67b7c6cec11e35481969bbb.tar.gz
px4-firmware-fc4be3e7280db480b67b7c6cec11e35481969bbb.tar.bz2
px4-firmware-fc4be3e7280db480b67b7c6cec11e35481969bbb.zip
Changed gps position topic mostly to SI units and float, removed counters and added specifig timestamps
Diffstat (limited to 'apps/mavlink')
-rw-r--r--apps/mavlink/mavlink_receiver.c24
-rw-r--r--apps/mavlink/orb_listener.c10
2 files changed, 17 insertions, 17 deletions
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index 86732d07c..b3b4b1e0b 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -387,22 +387,22 @@ handle_message(mavlink_message_t *msg)
static uint64_t old_timestamp = 0;
/* gps */
- hil_gps.timestamp = gps.time_usec;
- hil_gps.counter = hil_counter++;
+ hil_gps.timestamp_position = gps.time_usec;
+// hil_gps.counter = hil_counter++;
hil_gps.time_gps_usec = gps.time_usec;
hil_gps.lat = gps.lat;
hil_gps.lon = gps.lon;
hil_gps.alt = gps.alt;
- hil_gps.counter_pos_valid = hil_counter++;
- hil_gps.eph = gps.eph;
- hil_gps.epv = gps.epv;
- hil_gps.s_variance = 100;
- hil_gps.p_variance = 100;
- hil_gps.vel = gps.vel;
- hil_gps.vel_n = gps.vel / 100.0f * cosf(gps.cog / M_RAD_TO_DEG_F / 100.0f);
- hil_gps.vel_e = gps.vel / 100.0f * sinf(gps.cog / M_RAD_TO_DEG_F / 100.0f);
- hil_gps.vel_d = 0.0f;
- hil_gps.cog = gps.cog;
+// hil_gps.counter_pos_valid = hil_counter++;
+ hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
+ hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
+ hil_gps.s_variance_m_s = 100; // XXX 100 m/s variance?
+ hil_gps.p_variance_m = 100; // XXX 100 m variance?
+ hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
+ hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
+ hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
+ hil_gps.vel_d_m_s = 0.0f;
+ hil_gps.cog_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f; // from deg*100 to rad
hil_gps.fix_type = gps.fix_type;
hil_gps.satellites_visible = gps.satellites_visible;
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index 18da70f61..9f85d5801 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -231,15 +231,15 @@ l_vehicle_gps_position(struct listener *l)
/* GPS position */
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
- gps.timestamp,
+ gps.timestamp_position,
gps.fix_type,
gps.lat,
gps.lon,
gps.alt,
- gps.eph,
- gps.epv,
- gps.vel,
- gps.cog,
+ (uint16_t)(gps.eph_m * 1e2f), // from m to cm
+ (uint16_t)(gps.epv_m * 1e2f), // from m to cm
+ (uint16_t)(gps.vel_m_s * 1e2f), // from m/s to cm/s
+ (uint16_t)(gps.cog_rad * M_RAD_TO_DEG_F * 1e2f), // from rad to deg * 100
gps.satellites_visible);
if (gps.satellite_info_available && (gps_counter % 4 == 0)) {