diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h index 67d4a20c1e..18b7248117 100644 --- a/src/modules/simulator/simulator.h +++ b/src/modules/simulator/simulator.h @@ -363,8 +363,6 @@ private: // uORB subscription handlers int _actuator_outputs_sub{-1}; - int _manual_sub{-1}; - int _vehicle_attitude_sub{-1}; int _vehicle_status_sub{-1}; // hil map_ref data diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 91023819be..d78882dc2c 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -802,8 +802,8 @@ void Simulator::poll_for_MAVLink_messages() #endif - // subscribe to topics - // only subscribe to the first actuator_outputs to fill a single HIL_ACTUATOR_CONTROLS + // Subscribe to topics. + // Only subscribe to the first actuator_outputs to fill a single HIL_ACTUATOR_CONTROLS. _actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs), 0); _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); @@ -873,6 +873,9 @@ void Simulator::poll_for_MAVLink_messages() #endif } + + orb_unsubscribe(_actuator_outputs_sub); + orb_unsubscribe(_vehicle_status_sub); }