@@ -463,29 +463,26 @@ MujocoSystemInterface::MujocoSystemInterface() = default;
463463
464464MujocoSystemInterface::~MujocoSystemInterface ()
465465{
466- // Stop camera rendering loop (if not already stopped in on_deactivate)
466+ // Stop camera rendering loop
467467 if (cameras_)
468468 {
469469 cameras_->close ();
470470 }
471471
472- // Stop lidar sensor loop (if not already stopped in on_deactivate)
472+ // Stop lidar sensor loop
473473 if (lidar_sensors_)
474474 {
475475 lidar_sensors_->close ();
476476 }
477477
478- // Stop ROS executor
478+ // Stop ROS
479479 if (executor_)
480480 {
481481 executor_->cancel ();
482- if (executor_thread_.joinable ())
483- {
484- executor_thread_.join ();
485- }
482+ executor_thread_.join ();
486483 }
487484
488- // If sim_ is created and running, clean shut it down (if not already stopped in on_deactivate)
485+ // If sim_ is created and running, clean shut it down
489486 if (sim_)
490487 {
491488 sim_->exitrequest .store (true );
@@ -502,21 +499,17 @@ MujocoSystemInterface::~MujocoSystemInterface()
502499 }
503500
504501 // Cleanup data and the model, if they haven't been
505- // Only cleanup after all threads are stopped to avoid race conditions
506502 if (mj_data_)
507503 {
508504 mj_deleteData (mj_data_);
509- mj_data_ = nullptr ;
510505 }
511506 if (mj_data_control_)
512507 {
513508 mj_deleteData (mj_data_control_);
514- mj_data_control_ = nullptr ;
515509 }
516510 if (mj_model_)
517511 {
518512 mj_deleteModel (mj_model_);
519- mj_model_ = nullptr ;
520513 }
521514}
522515
@@ -953,42 +946,7 @@ MujocoSystemInterface::on_deactivate(const rclcpp_lifecycle::State& /*previous_s
953946{
954947 RCLCPP_INFO (get_logger (), " Deactivating MuJoCo hardware interface and shutting down Simulate..." );
955948
956- // Stop ROS executor first (it may be publishing clock or accessing resources)
957- if (executor_)
958- {
959- executor_->cancel ();
960- if (executor_thread_.joinable ())
961- {
962- executor_thread_.join ();
963- }
964- }
965-
966- // Stop camera and lidar rendering loops before ROS context becomes invalid
967- if (cameras_)
968- {
969- cameras_->close ();
970- }
971-
972- if (lidar_sensors_)
973- {
974- lidar_sensors_->close ();
975- }
976-
977- // Stop physics and UI threads before ROS context becomes invalid
978- if (sim_)
979- {
980- sim_->exitrequest .store (true );
981- sim_->run = false ;
982-
983- if (physics_thread_.joinable ())
984- {
985- physics_thread_.join ();
986- }
987- if (ui_thread_.joinable ())
988- {
989- ui_thread_.join ();
990- }
991- }
949+ // TODO: Should we shut mujoco things down here or in the destructor?
992950
993951 return hardware_interface::CallbackReturn::SUCCESS;
994952}
@@ -1675,7 +1633,7 @@ void MujocoSystemInterface::PhysicsLoop()
16751633 mjtNum syncSim = 0 ;
16761634
16771635 // run until asked to exit
1678- while (sim_ && !sim_->exitrequest .load ())
1636+ while (!sim_->exitrequest .load ())
16791637 {
16801638 // sleep for 1 ms or yield, to let main thread run
16811639 // yield results in busy wait - which has better timing but kills battery life
@@ -1689,21 +1647,9 @@ void MujocoSystemInterface::PhysicsLoop()
16891647 }
16901648
16911649 {
1692- // Safety check: ensure sim_ and sim_mutex_ are still valid
1693- if (!sim_ || !sim_mutex_)
1694- {
1695- break ;
1696- }
1697-
16981650 // lock the sim mutex during the update
16991651 const std::unique_lock<std::recursive_mutex> lock (*sim_mutex_);
17001652
1701- // Double-check after acquiring lock (sim_ might be deleted during shutdown)
1702- if (!sim_ || !mj_model_ || !mj_data_)
1703- {
1704- break ;
1705- }
1706-
17071653 // run only if model is present
17081654 if (mj_model_)
17091655 {
@@ -1835,12 +1781,6 @@ void MujocoSystemInterface::PhysicsLoop()
18351781
18361782void MujocoSystemInterface::publish_clock ()
18371783{
1838- // Safety check: ensure mj_data_ is still valid (may be deleted during shutdown)
1839- if (!mj_data_ || !clock_realtime_publisher_)
1840- {
1841- return ;
1842- }
1843-
18441784 auto sim_time = mj_data_->time ;
18451785 int32_t sim_time_sec = static_cast <int32_t >(std::floor (sim_time));
18461786 uint32_t sim_time_nanosec = static_cast <uint32_t >((sim_time - sim_time_sec) * 1e9 );
0 commit comments