aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-08-22 18:05:30 +0200
committerAnton Babushkin <anton.babushkin@me.com>2013-08-22 18:05:30 +0200
commit41fac46ff08787d9b2e4d902045d65c205389abd (patch)
tree0a534e17650b591382d645ba61ea744fad547e2a
parentbb91484b2648800923a135be28924119a1382ba6 (diff)
downloadpx4-firmware-41fac46ff08787d9b2e4d902045d65c205389abd.tar.gz
px4-firmware-41fac46ff08787d9b2e4d902045d65c205389abd.tar.bz2
px4-firmware-41fac46ff08787d9b2e4d902045d65c205389abd.zip
mavlink VFR_HUD message fixed, minor fixes and cleanup
-rw-r--r--src/modules/commander/commander.cpp4
-rw-r--r--src/modules/mavlink/orb_listener.c10
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c2
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h18
4 files changed, 17 insertions, 17 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 04e6dd2cb..4580c57bc 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -825,9 +825,9 @@ int commander_thread_main(int argc, char *argv[])
status.condition_landed = local_position.landed;
status_changed = true;
if (status.condition_landed) {
- mavlink_log_info(mavlink_fd, "[cmd] LANDED");
+ mavlink_log_critical(mavlink_fd, "[cmd] LANDED");
} else {
- mavlink_log_info(mavlink_fd, "[cmd] IN AIR");
+ mavlink_log_critical(mavlink_fd, "[cmd] IN AIR");
}
}
}
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 2a260861d..97cf571e5 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -637,12 +637,12 @@ l_airspeed(const struct listener *l)
orb_copy(ORB_ID(airspeed), mavlink_subs.airspeed_sub, &airspeed);
float groundspeed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy);
- float throttle = actuators_0.control_effective[3] * (UINT16_MAX - 1);
- float alt = global_pos.alt;
- float climb = global_pos.vz;
+ uint16_t heading = (att.yaw + M_PI_F) / M_PI_F * 180.0f;
+ uint16_t throttle = actuators_0.control_effective[3] * (UINT16_MAX - 1);
+ float alt = global_pos.relative_alt;
+ float climb = -global_pos.vz;
- mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed,
- ((att.yaw + M_PI_F) / M_PI_F) * 180.0f, throttle, alt, climb);
+ mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed, heading, throttle, alt, climb);
}
static void *
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 3466841c4..d35755b4f 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -610,7 +610,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (local_pos.v_xy_valid) {
global_pos.vx = local_pos.vx;
global_pos.vy = local_pos.vy;
- global_pos.hdg = atan2f(local_pos.vy, local_pos.vx);
+ global_pos.hdg = atan2f(local_pos.vy, local_pos.vx); // TODO is it correct?
}
if (local_pos.z_valid) {
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index f036c7223..822c323cf 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -62,17 +62,17 @@
struct vehicle_global_position_s
{
uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
- uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
+ uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
bool valid; /**< true if position satisfies validity criteria of estimator */
- int32_t lat; /**< Latitude in 1E7 degrees LOGME */
- int32_t lon; /**< Longitude in 1E7 degrees LOGME */
- float alt; /**< Altitude in meters LOGME */
- float relative_alt; /**< Altitude above home position in meters, LOGME */
- float vx; /**< Ground X Speed (Latitude), m/s in ENU LOGME */
- float vy; /**< Ground Y Speed (Longitude), m/s in ENU LOGME */
- float vz; /**< Ground Z Speed (Altitude), m/s in ENU LOGME */
- float hdg; /**< Compass heading in radians -PI..+PI. */
+ int32_t lat; /**< Latitude in 1E7 degrees */
+ int32_t lon; /**< Longitude in 1E7 degrees */
+ float alt; /**< Altitude in meters */
+ float relative_alt; /**< Altitude above home position in meters, */
+ float vx; /**< Ground X velocity, m/s in NED */
+ float vy; /**< Ground Y velocity, m/s in NED */
+ float vz; /**< Ground Z velocity, m/s in NED */
+ float hdg; /**< Compass heading in radians -PI..+PI. */
};