Skip to content

Commit

Permalink
Reset Gazebo with initial joint positions and velocities (#241) (#244)
Browse files Browse the repository at this point in the history
(cherry picked from commit c5b0b90)

Co-authored-by: Ruddick Lawrence <[email protected]>
  • Loading branch information
mergify[bot] and mrjogo authored Feb 26, 2024
1 parent 700be8e commit 6b3f282
Showing 1 changed file with 9 additions and 0 deletions.
9 changes: 9 additions & 0 deletions gz_ros2_control/src/gz_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
#include <gz/sim/components/JointPositionReset.hh>
#include <gz/sim/components/JointVelocity.hh>
#include <gz/sim/components/JointVelocityCmd.hh>
#include <gz/sim/components/JointVelocityReset.hh>
#include <gz/sim/components/LinearAcceleration.hh>
#include <gz/sim/components/Name.hh>
#include <gz/sim/components/ParentEntity.hh>
Expand All @@ -48,8 +49,10 @@
#include <ignition/gazebo/components/JointForce.hh>
#include <ignition/gazebo/components/JointForceCmd.hh>
#include <ignition/gazebo/components/JointPosition.hh>
#include <ignition/gazebo/components/JointPositionReset.hh>
#include <ignition/gazebo/components/JointVelocity.hh>
#include <ignition/gazebo/components/JointVelocityCmd.hh>
#include <ignition/gazebo/components/JointVelocityReset.hh>
#include <ignition/gazebo/components/LinearAcceleration.hh>
#include <ignition/gazebo/components/Name.hh>
#include <ignition/gazebo/components/ParentEntity.hh>
Expand Down Expand Up @@ -397,9 +400,15 @@ bool GazeboSimSystem::initSim(
// independently of existence of command interface set initial value if defined
if (!std::isnan(initial_position)) {
this->dataPtr->joints_[j].joint_position = initial_position;
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[j].sim_joint,
sim::components::JointPositionReset({initial_position}));
}
if (!std::isnan(initial_velocity)) {
this->dataPtr->joints_[j].joint_velocity = initial_velocity;
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[j].sim_joint,
sim::components::JointVelocityReset({initial_velocity}));
}
}

Expand Down

0 comments on commit 6b3f282

Please sign in to comment.