Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Don't crash if a wrong config was detected (backport #324) #331

Merged
merged 2 commits into from
Jun 10, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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