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

Harden behavior if a joint is not found in the model #325

Merged
merged 3 commits into from
Jun 10, 2024
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
16 changes: 16 additions & 0 deletions gz_ros2_control/src/gz_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -224,6 +224,14 @@ bool GazeboSimSystem::initSim(
auto & joint_info = hardware_info.joints[j];
std::string joint_name = this->dataPtr->joints_[j].name = joint_info.name;

auto it_joint = enableJoints.find(joint_name);
if (it_joint == enableJoints.end()) {
RCLCPP_WARN_STREAM(
this->nh_->get_logger(), "Skipping joint in the URDF named '" << joint_name <<
"' which is not in the gazebo model.");
continue;
}

sim::Entity simjoint = enableJoints[joint_name];
this->dataPtr->joints_[j].sim_joint = simjoint;

Expand Down Expand Up @@ -501,6 +509,10 @@ hardware_interface::return_type GazeboSimSystem::read(
const rclcpp::Duration & /*period*/)
{
for (unsigned int i = 0; i < this->dataPtr->joints_.size(); ++i) {
if (this->dataPtr->joints_[i].sim_joint == sim::kNullEntity) {
continue;
}

// Get the joint velocity
const auto * jointVelocity =
this->dataPtr->ecm->Component<sim::components::JointVelocity>(
Expand Down Expand Up @@ -593,6 +605,10 @@ hardware_interface::return_type GazeboSimSystem::write(
const rclcpp::Duration & /*period*/)
{
for (unsigned int i = 0; i < this->dataPtr->joints_.size(); ++i) {
if (this->dataPtr->joints_[i].sim_joint == sim::kNullEntity) {
continue;
}

if (this->dataPtr->joints_[i].joint_control_method & VELOCITY) {
if (!this->dataPtr->ecm->Component<sim::components::JointVelocityCmd>(
this->dataPtr->joints_[i].sim_joint))
Expand Down