Skip to content

Commit

Permalink
Don't crash if a wrong config was detected (#324)
Browse files Browse the repository at this point in the history
(cherry picked from commit ec1b958)
  • Loading branch information
christophfroehlich authored and mergify[bot] committed Jun 10, 2024
1 parent 80e6ad1 commit d51e256
Showing 1 changed file with 9 additions and 0 deletions.
9 changes: 9 additions & 0 deletions gz_ros2_control/src/gz_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -235,6 +235,9 @@ GazeboSimROS2ControlPlugin::GazeboSimROS2ControlPlugin()
GazeboSimROS2ControlPlugin::~GazeboSimROS2ControlPlugin()
{
// Stop controller manager thread
if (!this->dataPtr->controller_manager_) {
return;
}
this->dataPtr->executor_->remove_node(this->dataPtr->controller_manager_);
this->dataPtr->executor_->cancel();
this->dataPtr->thread_executor_spin_.join();
Expand Down Expand Up @@ -514,6 +517,9 @@ void GazeboSimROS2ControlPlugin::PreUpdate(
const sim::UpdateInfo & _info,
sim::EntityComponentManager & /*_ecm*/)
{
if (!this->dataPtr->controller_manager_) {
return;
}
static bool warned{false};
if (!warned) {
rclcpp::Duration gazebo_period(_info.dt);
Expand Down Expand Up @@ -548,6 +554,9 @@ void GazeboSimROS2ControlPlugin::PostUpdate(
const sim::UpdateInfo & _info,
const sim::EntityComponentManager & /*_ecm*/)
{
if (!this->dataPtr->controller_manager_) {
return;
}
// Get the simulation time and period
rclcpp::Time sim_time_ros(std::chrono::duration_cast<std::chrono::nanoseconds>(
_info.simTime).count(), RCL_ROS_TIME);
Expand Down

0 comments on commit d51e256

Please sign in to comment.