aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink.c
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-07-08 10:31:32 +0200
committerJulian Oes <julian@oes.ch>2013-07-08 10:31:32 +0200
commit88389ea2554c6f56a4fdd86cdd86a1e7b6affc21 (patch)
tree3ef98ded43e5f3a2cdc30a836a3a7329fe5757bb /src/modules/mavlink/mavlink.c
parent76346bfe19c816491a6982abfa10f48cd9d258f6 (diff)
parentcf2dbdf9a1ae06c7d0e0a7963916a3709a1bc075 (diff)
downloadpx4-firmware-88389ea2554c6f56a4fdd86cdd86a1e7b6affc21.tar.gz
px4-firmware-88389ea2554c6f56a4fdd86cdd86a1e7b6affc21.tar.bz2
px4-firmware-88389ea2554c6f56a4fdd86cdd86a1e7b6affc21.zip
Merge branch 'master' into new_state_machine
compiling again Conflicts: src/modules/fixedwing_att_control/fixedwing_att_control_att.c src/modules/fixedwing_att_control/fixedwing_att_control_rate.c src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c src/modules/mavlink/orb_listener.c src/modules/multirotor_att_control/multirotor_attitude_control.c src/modules/multirotor_att_control/multirotor_rate_control.c src/modules/systemlib/pid/pid.c src/modules/systemlib/pid/pid.h src/modules/uORB/objects_common.cpp
Diffstat (limited to 'src/modules/mavlink/mavlink.c')
-rw-r--r--src/modules/mavlink/mavlink.c15
1 files changed, 6 insertions, 9 deletions
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 15ba8860d..f6c371c7c 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 */
@@ -708,6 +700,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);
@@ -719,10 +713,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();
}
@@ -781,7 +778,7 @@ int mavlink_main(int argc, char *argv[])
errx(0, "mavlink already running\n");
thread_should_exit = false;
- mavlink_task = task_spawn("mavlink",
+ mavlink_task = task_spawn_cmd("mavlink",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,