From 149c844c43f064e01601f16bc11b0fcafc96d746 Mon Sep 17 00:00:00 2001 From: Shivesh Khaitan Date: Wed, 19 Jun 2019 17:20:09 +0530 Subject: [PATCH 1/3] Fix for multiple video plugins (#898) --- gazebo_plugins/src/gazebo_ros_video.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gazebo_plugins/src/gazebo_ros_video.cpp b/gazebo_plugins/src/gazebo_ros_video.cpp index f634431ce..16abd2627 100644 --- a/gazebo_plugins/src/gazebo_ros_video.cpp +++ b/gazebo_plugins/src/gazebo_ros_video.cpp @@ -200,8 +200,8 @@ void GazeboRosVideo::Load( int width = _sdf->Get("width", 320).first; - impl_->video_visual_ = std::make_shared(_parent->Name() + "::video_visual", - _parent, height, width); + impl_->video_visual_ = std::make_shared(_parent->Name() + "::video_visual::" + + _sdf->Get("name"), _parent, height, width); _parent->GetScene()->AddVisual(impl_->video_visual_); // Subscribe to the image topic From 756898767251cfce3f98d85b01544962639bba11 Mon Sep 17 00:00:00 2001 From: Shivesh Khaitan Date: Thu, 27 Jun 2019 13:14:07 +0530 Subject: [PATCH 2/3] Fix crash on shutdown --- gazebo_plugins/src/gazebo_ros_video.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/gazebo_plugins/src/gazebo_ros_video.cpp b/gazebo_plugins/src/gazebo_ros_video.cpp index 16abd2627..408876761 100644 --- a/gazebo_plugins/src/gazebo_ros_video.cpp +++ b/gazebo_plugins/src/gazebo_ros_video.cpp @@ -186,6 +186,9 @@ GazeboRosVideo::GazeboRosVideo() // Destructor GazeboRosVideo::~GazeboRosVideo() { + if (rclcpp::is_initialized()) { + rclcpp::shutdown(); + } impl_->update_connection_.reset(); impl_->rosnode_.reset(); } From 8f6561de8091e2582bbaaf17dc6d9e529a6ce396 Mon Sep 17 00:00:00 2001 From: Shivesh Khaitan Date: Wed, 10 Jul 2019 20:08:22 +0530 Subject: [PATCH 3/3] Fix gazebo node destructor --- gazebo_plugins/src/gazebo_ros_video.cpp | 3 --- gazebo_ros/src/node.cpp | 1 + 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/gazebo_plugins/src/gazebo_ros_video.cpp b/gazebo_plugins/src/gazebo_ros_video.cpp index 408876761..16abd2627 100644 --- a/gazebo_plugins/src/gazebo_ros_video.cpp +++ b/gazebo_plugins/src/gazebo_ros_video.cpp @@ -186,9 +186,6 @@ GazeboRosVideo::GazeboRosVideo() // Destructor GazeboRosVideo::~GazeboRosVideo() { - if (rclcpp::is_initialized()) { - rclcpp::shutdown(); - } impl_->update_connection_.reset(); impl_->rosnode_.reset(); } diff --git a/gazebo_ros/src/node.cpp b/gazebo_ros/src/node.cpp index caec0161f..582c7aa78 100644 --- a/gazebo_ros/src/node.cpp +++ b/gazebo_ros/src/node.cpp @@ -28,6 +28,7 @@ std::mutex Node::lock_; Node::~Node() { + executor_->remove_node(get_node_base_interface()); } Node::SharedPtr Node::Get(sdf::ElementPtr sdf)