Skip to content

Commit

Permalink
Small fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass committed Mar 5, 2024
1 parent cd82ff1 commit 1972fa7
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions ign_ros2_control/src/ign_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -680,7 +680,7 @@ hardware_interface::return_type IgnitionSystem::write(
this->dataPtr->joints_[i].sim_joint,
ignition::gazebo::components::JointVelocityReset({targetVel}));
} else if (!vel->Data().empty()) {
vel->Data()[0] = target_vel;
vel->Data()[0] = targetVel;
}
} else if (this->dataPtr->joints_[i].joint_control_method & EFFORT) {
if (!this->dataPtr->ecm->Component<ignition::gazebo::components::JointForceCmd>(
Expand All @@ -701,13 +701,13 @@ hardware_interface::return_type IgnitionSystem::write(
// Fallback case is a velocity command of zero (only for actuated joints)
double target_vel = 0.0;
auto vel =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocityCmd>(
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocityReset>(
this->dataPtr->joints_[i].sim_joint);

if (vel == nullptr) {
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[i].sim_joint,
ignition::gazebo::components::JointVelocityCmd({target_vel}));
ignition::gazebo::components::JointVelocityReset({target_vel}));
} else if (!vel->Data().empty()) {
vel->Data()[0] = target_vel;
}
Expand Down

0 comments on commit 1972fa7

Please sign in to comment.