Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix stuck passive joints (backport #184) #205

Merged
merged 1 commit into from
Dec 16, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 8 additions & 2 deletions gz_ros2_control/src/gz_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,9 @@ struct jointData
/// \brief Current cmd joint effort
double joint_effort_cmd;

/// \brief flag if joint is actuated (has command interfaces) or passive
bool is_actuated;

/// \brief handles to the joints from within Gazebo
sim::Entity sim_joint;

Expand Down Expand Up @@ -388,6 +391,9 @@ bool GazeboSimSystem::initSim(
this->dataPtr->joints_[j].joint_velocity = initial_velocity;
}
}

// check if joint is actuated (has command interfaces) or passive
this->dataPtr->joints_[j].is_actuated = (joint_info.command_interfaces.size() > 0);
}

registerSensors(hardware_info);
Expand Down Expand Up @@ -652,8 +658,8 @@ hardware_interface::return_type GazeboSimSystem::write(
*jointEffortCmd = sim::components::JointForceCmd(
{this->dataPtr->joints_[i].joint_effort_cmd});
}
} else {
// Fallback case is a velocity command of zero
} else if (this->dataPtr->joints_[i].is_actuated) {
// Fallback case is a velocity command of zero (only for actuated joints)
double target_vel = 0.0;
auto vel =
this->dataPtr->ecm->Component<sim::components::JointVelocityCmd>(
Expand Down
Loading