diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp index d6dbe9a53f..0efc490326 100644 --- a/src/drivers/hil/hil.cpp +++ b/src/drivers/hil/hil.cpp @@ -348,9 +348,9 @@ HIL::task_main() actuator_outputs_s outputs; memset(&outputs, 0, sizeof(outputs)); /* advertise the mixed control outputs */ - //int dummy; - _t_outputs = orb_advertise(ORB_ID(actuator_outputs), - &outputs); + int dummy; + _t_outputs = orb_advertise_multi(ORB_ID(actuator_outputs), + &outputs, &dummy, ORB_PRIO_LOW); px4_pollfd_struct_t fds[2]; fds[0].fd = _t_actuators; diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 94ec3ced23..e4403fd221 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -310,9 +310,6 @@ void Simulator::updateSamples() struct mag_report mag; memset(&mag, 0 ,sizeof(mag)); - // subscribe to topics - _actuator_outputs_sub = orb_subscribe(ORB_ID(actuator_outputs)); - // try to setup udp socket for communcation with simulator memset((char *)&_myaddr, 0, sizeof(_myaddr)); _myaddr.sin_family = AF_INET; @@ -381,6 +378,9 @@ void Simulator::updateSamples() send_controls(); } + // subscribe to topics + _actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs), 0); + // got data from simulator, now activate the sending thread pthread_create(&sender_thread, &sender_thread_attr, Simulator::sending_trampoline, NULL); pthread_attr_destroy(&sender_thread_attr);