Skip to content
Snippets Groups Projects
Commit f5901375 authored by bresch's avatar bresch Committed by Lorenz Meier
Browse files

Fix HIL

Revert "pwm_out_sim lazily publish actuator_outputs"

This reverts commit bcad940a.
parent 4e2bf27d
No related branches found
No related tags found
No related merge requests found
......@@ -158,6 +158,9 @@ PWMSim::run()
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
/* advertise the mixed control outputs, insist on the first group output */
_outputs_pub = orb_advertise(ORB_ID(actuator_outputs), &_actuator_outputs);
update_params();
int params_sub = orb_subscribe(ORB_ID(parameter_update));
......@@ -284,8 +287,7 @@ PWMSim::run()
/* and publish for anyone that cares to see */
_actuator_outputs.timestamp = hrt_absolute_time();
int instance;
orb_publish_auto(ORB_ID(actuator_outputs), &_outputs_pub, &_actuator_outputs, &instance, ORB_PRIO_DEFAULT);
orb_publish(ORB_ID(actuator_outputs), _outputs_pub, &_actuator_outputs);
// use first valid timestamp_sample for latency tracking
for (int i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) {
......
......@@ -110,7 +110,7 @@ private:
int _armed_sub{-1};
actuator_outputs_s _actuator_outputs{};
actuator_outputs_s _actuator_outputs = {};
orb_advert_t _outputs_pub{nullptr};
unsigned _num_outputs{0};
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment