Skip to content

Commit

Permalink
move variable to GazeboSystemPrivate
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 31, 2023
1 parent 5b7b7f1 commit 8f76ed8
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -88,9 +88,6 @@ class GazeboSystem : public GazeboSystemInterface

/// \brief Private data class
std::unique_ptr<GazeboSystemPrivate> dataPtr;

// Should hold the joints if no control_mode is active
bool hold_joints_ = true;
};

} // namespace gazebo_ros2_control
Expand Down
11 changes: 7 additions & 4 deletions gazebo_ros2_control/src/gazebo_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,9 @@ class gazebo_ros2_control::GazeboSystemPrivate

/// \brief mapping of mimicked joints to index of joint they mimic
std::vector<MimicJoint> mimic_joints_;

// Should hold the joints if no control_mode is active
bool hold_joints_ = true;
};

namespace gazebo_ros2_control
Expand All @@ -129,16 +132,16 @@ bool GazeboSystem::initSim(
}

try {
hold_joints_ = this->nh_->get_parameter("hold_joints").as_bool();
this->dataPtr->hold_joints_ = this->nh_->get_parameter("hold_joints").as_bool();
} catch (const std::exception & e) {
RCLCPP_WARN(
this->nh_->get_logger(),
"Parameter 'hold_joints' not found, with error %s", e.what());
RCLCPP_WARN_STREAM(
this->nh_->get_logger(), "Using default value: " << hold_joints_);
this->nh_->get_logger(), "Using default value: " << this->dataPtr->hold_joints_);
}
RCLCPP_DEBUG_STREAM(
this->nh_->get_logger(), "hold_joints (system): " << hold_joints_ << std::endl);
this->nh_->get_logger(), "hold_joints (system): " << this->dataPtr->hold_joints_ << std::endl);

registerJoints(hardware_info, parent_model);
registerSensors(hardware_info, parent_model);
Expand Down Expand Up @@ -613,7 +616,7 @@ hardware_interface::return_type GazeboSystem::write(
this->dataPtr->sim_joints_[j]->SetVelocity(0, this->dataPtr->joint_velocity_cmd_[j]);
} else if (this->dataPtr->joint_control_methods_[j] & EFFORT) { // NOLINT
this->dataPtr->sim_joints_[j]->SetForce(0, this->dataPtr->joint_effort_cmd_[j]);
} else if (this->dataPtr->is_joint_actuated_[j] && hold_joints_) {
} else if (this->dataPtr->is_joint_actuated_[j] && this->dataPtr->hold_joints_) {
// Fallback case is a velocity command of zero (only for actuated joints)
this->dataPtr->sim_joints_[j]->SetVelocity(0, 0.0);
}
Expand Down

0 comments on commit 8f76ed8

Please sign in to comment.