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

Commit a272ba5

Browse files
Fix stuck passive joints (#237) (#238)
(cherry picked from commit 5dba0f9) Co-authored-by: Johannes Huemer <[email protected]>
1 parent 057f0b8 commit a272ba5

File tree

1 file changed

+9
-2
lines changed

1 file changed

+9
-2
lines changed

gazebo_ros2_control/src/gazebo_system.cpp

+9-2
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,9 @@ class gazebo_ros2_control::GazeboSystemPrivate
5959
/// \brief vector with the control method defined in the URDF for each joint.
6060
std::vector<GazeboSystemInterface::ControlMethod> joint_control_methods_;
6161

62+
/// \brief vector with indication for actuated joints (vs. passive joints)
63+
std::vector<bool> is_joint_actuated_;
64+
6265
/// \brief handles to the joints from within Gazebo
6366
std::vector<gazebo::physics::JointPtr> sim_joints_;
6467

@@ -144,6 +147,7 @@ void GazeboSystem::registerJoints(
144147

145148
this->dataPtr->joint_names_.resize(this->dataPtr->n_dof_);
146149
this->dataPtr->joint_control_methods_.resize(this->dataPtr->n_dof_);
150+
this->dataPtr->is_joint_actuated_.resize(this->dataPtr->n_dof_);
147151
this->dataPtr->joint_position_.resize(this->dataPtr->n_dof_);
148152
this->dataPtr->joint_velocity_.resize(this->dataPtr->n_dof_);
149153
this->dataPtr->joint_effort_.resize(this->dataPtr->n_dof_);
@@ -293,6 +297,9 @@ void GazeboSystem::registerJoints(
293297
this->dataPtr->sim_joints_[j]->SetForce(0, initial_effort);
294298
}
295299
}
300+
301+
// check if joint is actuated (has command interfaces) or passive
302+
this->dataPtr->is_joint_actuated_[j] = (joint_info.command_interfaces.size() > 0);
296303
}
297304
}
298305

@@ -594,8 +601,8 @@ hardware_interface::return_type GazeboSystem::write(
594601
this->dataPtr->sim_joints_[j]->SetVelocity(0, this->dataPtr->joint_velocity_cmd_[j]);
595602
} else if (this->dataPtr->joint_control_methods_[j] & EFFORT) { // NOLINT
596603
this->dataPtr->sim_joints_[j]->SetForce(0, this->dataPtr->joint_effort_cmd_[j]);
597-
} else {
598-
// Fallback case is a velocity command of zero
604+
} else if (this->dataPtr->is_joint_actuated_[j]) {
605+
// Fallback case is a velocity command of zero (only for actuated joints)
599606
this->dataPtr->sim_joints_[j]->SetVelocity(0, 0.0);
600607
}
601608
}

0 commit comments

Comments
 (0)