Skip to content

Commit

Permalink
Fix stuck passive joints
Browse files Browse the repository at this point in the history
  • Loading branch information
huemerj committed Oct 4, 2023
1 parent 1e80f42 commit 4f33033
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion 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,7 +658,7 @@ hardware_interface::return_type GazeboSimSystem::write(
*jointEffortCmd = sim::components::JointForceCmd(
{this->dataPtr->joints_[i].joint_effort_cmd});
}
} else {
} else if (this->dataPtr->joints_[i].is_actuated_) {
// Fallback case is a velocity command of zero
double target_vel = 0.0;
auto vel =
Expand Down

0 comments on commit 4f33033

Please sign in to comment.