Skip to content
This repository was archived by the owner on Oct 17, 2025. It is now read-only.

Commit f37068c

Browse files
Override gazebo reset method (#413)
1 parent cbf2992 commit f37068c

File tree

2 files changed

+6
-0
lines changed

2 files changed

+6
-0
lines changed

gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,7 @@ class GazeboRosControlPlugin : public gazebo::ModelPlugin
5757

5858
// Overloaded Gazebo entry point
5959
void Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf) override;
60+
void Reset() override;
6061

6162
private:
6263
/// Private data pointer

gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -430,6 +430,11 @@ void GazeboRosControlPrivate::Update()
430430
}
431431

432432
// Called on world reset
433+
void GazeboRosControlPlugin::Reset()
434+
{
435+
impl_->Reset();
436+
}
437+
433438
void GazeboRosControlPrivate::Reset()
434439
{
435440
// Reset timing variables to not pass negative update periods to controllers on world reset

0 commit comments

Comments
 (0)