Skip to content

Commit

Permalink
Harden behavior if a joint is not found in the model (#325)
Browse files Browse the repository at this point in the history
* Don't crash if a joint does not exist
  • Loading branch information
christophfroehlich authored Jun 10, 2024
1 parent ec1b958 commit 5d2d5eb
Showing 1 changed file with 16 additions and 0 deletions.
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

0 comments on commit 5d2d5eb

Please sign in to comment.