@@ -59,6 +59,9 @@ class gazebo_ros2_control::GazeboSystemPrivate
59
59
// / \brief vector with the control method defined in the URDF for each joint.
60
60
std::vector<GazeboSystemInterface::ControlMethod> joint_control_methods_;
61
61
62
+ // / \brief vector with indication for actuated joints (vs. passive joints)
63
+ std::vector<bool > is_joint_actuated_;
64
+
62
65
// / \brief handles to the joints from within Gazebo
63
66
std::vector<gazebo::physics::JointPtr> sim_joints_;
64
67
@@ -144,6 +147,7 @@ void GazeboSystem::registerJoints(
144
147
145
148
this ->dataPtr ->joint_names_ .resize (this ->dataPtr ->n_dof_ );
146
149
this ->dataPtr ->joint_control_methods_ .resize (this ->dataPtr ->n_dof_ );
150
+ this ->dataPtr ->is_joint_actuated_ .resize (this ->dataPtr ->n_dof_ );
147
151
this ->dataPtr ->joint_position_ .resize (this ->dataPtr ->n_dof_ );
148
152
this ->dataPtr ->joint_velocity_ .resize (this ->dataPtr ->n_dof_ );
149
153
this ->dataPtr ->joint_effort_ .resize (this ->dataPtr ->n_dof_ );
@@ -293,6 +297,9 @@ void GazeboSystem::registerJoints(
293
297
this ->dataPtr ->sim_joints_ [j]->SetForce (0 , initial_effort);
294
298
}
295
299
}
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 );
296
303
}
297
304
}
298
305
@@ -594,8 +601,8 @@ hardware_interface::return_type GazeboSystem::write(
594
601
this ->dataPtr ->sim_joints_ [j]->SetVelocity (0 , this ->dataPtr ->joint_velocity_cmd_ [j]);
595
602
} else if (this ->dataPtr ->joint_control_methods_ [j] & EFFORT) { // NOLINT
596
603
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)
599
606
this ->dataPtr ->sim_joints_ [j]->SetVelocity (0 , 0.0 );
600
607
}
601
608
}
0 commit comments