aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink.c
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink/mavlink.c')
-rw-r--r--src/modules/mavlink/mavlink.c13
1 files changed, 5 insertions, 8 deletions
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index c72a53fee..5b8345e7e 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -144,14 +144,6 @@ set_hil_on_off(bool hil_enabled)
/* Enable HIL */
if (hil_enabled && !mavlink_hil_enabled) {
- /* Advertise topics */
- pub_hil_attitude = orb_advertise(ORB_ID(vehicle_attitude), &hil_attitude);
- pub_hil_global_pos = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos);
-
- /* sensore level hil */
- pub_hil_sensors = orb_advertise(ORB_ID(sensor_combined), &hil_sensors);
- pub_hil_gps = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps);
-
mavlink_hil_enabled = true;
/* ramp up some HIL-related subscriptions */
@@ -714,6 +706,8 @@ int mavlink_thread_main(int argc, char *argv[])
lowspeed_counter++;
+ mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos);
+
/* sleep quarter the time */
usleep(25000);
@@ -725,10 +719,13 @@ int mavlink_thread_main(int argc, char *argv[])
/* send parameters at 20 Hz (if queued for sending) */
mavlink_pm_queued_send();
+ mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos);
/* sleep quarter the time */
usleep(25000);
+ mavlink_waypoint_eventloop(mavlink_missionlib_get_system_timestamp(), &global_pos, &local_pos);
+
if (baudrate > 57600) {
mavlink_pm_queued_send();
}