aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/orb_listener.c
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink/orb_listener.c')
-rw-r--r--src/modules/mavlink/orb_listener.c21
1 files changed, 21 insertions, 0 deletions
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index cec2fdc43..0e0ce2723 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 navigation_capabilities_s nav_cap;
struct vehicle_status_s v_status;
struct rc_channels_s rc;
struct rc_input_values rc_raw;
@@ -122,6 +123,7 @@ static void l_optical_flow(const struct listener *l);
static void l_vehicle_rates_setpoint(const struct listener *l);
static void l_home(const struct listener *l);
static void l_airspeed(const struct listener *l);
+static void l_nav_cap(const struct listener *l);
static const struct listener listeners[] = {
{l_sensor_combined, &mavlink_subs.sensor_sub, 0},
@@ -148,6 +150,7 @@ static const struct listener listeners[] = {
{l_vehicle_rates_setpoint, &mavlink_subs.rates_setpoint_sub, 0},
{l_home, &mavlink_subs.home_sub, 0},
{l_airspeed, &mavlink_subs.airspeed_sub, 0},
+ {l_nav_cap, &mavlink_subs.navigation_capabilities_sub, 0},
};
static const unsigned n_listeners = sizeof(listeners) / sizeof(listeners[0]);
@@ -691,6 +694,19 @@ l_airspeed(const struct listener *l)
mavlink_msg_vfr_hud_send(MAVLINK_COMM_0, airspeed.true_airspeed_m_s, groundspeed, heading, throttle, alt, climb);
}
+void
+l_nav_cap(const struct listener *l)
+{
+
+ orb_copy(ORB_ID(navigation_capabilities), mavlink_subs.navigation_capabilities_sub, &nav_cap);
+
+ mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
+ hrt_absolute_time() / 1000,
+ "turn dist",
+ nav_cap.turn_distance);
+
+}
+
static void *
uorb_receive_thread(void *arg)
{
@@ -837,6 +853,11 @@ uorb_receive_start(void)
mavlink_subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
orb_set_interval(mavlink_subs.airspeed_sub, 200); /* 5Hz updates */
+ /* --- NAVIGATION CAPABILITIES --- */
+ mavlink_subs.navigation_capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
+ orb_set_interval(mavlink_subs.navigation_capabilities_sub, 500); /* 2Hz updates */
+ nav_cap.turn_distance = 0.0f;
+
/* start the listener loop */
pthread_attr_t uorb_attr;
pthread_attr_init(&uorb_attr);