Skip to content

Commit

Permalink
Set right initial velocity (#81)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>

Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored Aug 19, 2022
1 parent d0b7d86 commit 5056d40
Showing 1 changed file with 1 addition and 7 deletions.
8 changes: 1 addition & 7 deletions ign_ros2_control/src/ign_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -282,16 +282,10 @@ bool IgnitionSystem::initSim(
}
// independently of existence of command interface set initial value if defined
if (!std::isnan(initial_position)) {
const auto * jointPositions =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointPosition>(
this->dataPtr->joints_[j].sim_joint);
this->dataPtr->joints_[j].joint_position = initial_position;
}
if (!std::isnan(initial_velocity)) {
const auto * jointVelocity =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocity>(
this->dataPtr->joints_[j].sim_joint);
this->dataPtr->joints_[j].joint_velocity = jointVelocity->Data()[0];
this->dataPtr->joints_[j].joint_velocity = initial_velocity;
}
}
}
Expand Down

0 comments on commit 5056d40

Please sign in to comment.