Skip to content

Commit

Permalink
Merge branch 'master' into fix_docs
Browse files Browse the repository at this point in the history
  • Loading branch information
ahcorde authored Jan 1, 2024
2 parents 16f0e36 + 7682dce commit f03a03b
Show file tree
Hide file tree
Showing 3 changed files with 52 additions and 1 deletion.
1 change: 1 addition & 0 deletions doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -155,6 +155,7 @@ The *gazebo_ros2_control* ``<plugin>`` tag also has the following optional child
* ``<robot_param>``: The location of the ``robot_description`` (URDF) on the parameter server, defaults to ``robot_description``
* ``<robot_param_node>``: Name of the node where the ``robot_param`` is located, defaults to ``robot_state_publisher``
* ``<parameters>``: YAML file with the configuration of the controllers
* ``<hold_joints>``: if set to true (default), it will hold the joints' position if their interface was not claimed, e.g., the controller hasn't been activated yet.

Default gazebo_ros2_control Behavior
-----------------------------------------------------------
Expand Down
23 changes: 23 additions & 0 deletions gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,12 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element
} else {
impl_->robot_description_node_ = "robot_state_publisher"; // default
}
// Hold joints if no control mode is active?
bool hold_joints = true; // default
if (sdf->HasElement("hold_joints")) {
hold_joints =
sdf->GetElement("hold_joints")->Get<bool>();
}

// There's currently no direct way to set parameters to the plugin's node
// So we have to parse the plugin file manually and set it to the node's context.
Expand Down Expand Up @@ -306,6 +312,23 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element
RCLCPP_DEBUG(
impl_->model_nh_->get_logger(), "Loaded hardware interface %s!",
robot_hw_sim_type_str_.c_str());
try {
node_ros2->declare_parameter("hold_joints", rclcpp::ParameterValue(hold_joints));
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException & e) {
RCLCPP_ERROR(
impl_->model_nh_->get_logger(), "Parameter 'hold_joints' has already been declared, %s",
e.what());
} catch (const rclcpp::exceptions::InvalidParametersException & e) {
RCLCPP_ERROR(
impl_->model_nh_->get_logger(), "Parameter 'hold_joints' has invalid name, %s", e.what());
} catch (const rclcpp::exceptions::InvalidParameterValueException & e) {
RCLCPP_ERROR(
impl_->model_nh_->get_logger(), "Parameter 'hold_joints' value is invalid, %s", e.what());
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
RCLCPP_ERROR(
impl_->model_nh_->get_logger(), "Parameter 'hold_joints' value has wrong type, %s",
e.what());
}
if (!gazeboSystem->initSim(
node_ros2,
impl_->parent_model_,
Expand Down
29 changes: 28 additions & 1 deletion 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 @@ -128,6 +131,30 @@ bool GazeboSystem::initSim(
return false;
}

try {
this->dataPtr->hold_joints_ = this->nh_->get_parameter("hold_joints").as_bool();
} catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
RCLCPP_ERROR(
this->nh_->get_logger(),
"Parameter 'hold_joints' not initialized, with error %s", ex.what());
RCLCPP_WARN_STREAM(
this->nh_->get_logger(), "Using default value: " << this->dataPtr->hold_joints_);
} catch (rclcpp::exceptions::ParameterNotDeclaredException & ex) {
RCLCPP_ERROR(
this->nh_->get_logger(),
"Parameter 'hold_joints' not declared, with error %s", ex.what());
RCLCPP_WARN_STREAM(
this->nh_->get_logger(), "Using default value: " << this->dataPtr->hold_joints_);
} catch (rclcpp::ParameterTypeException & ex) {
RCLCPP_ERROR(
this->nh_->get_logger(),
"Parameter 'hold_joints' has wrong type: %s", ex.what());
RCLCPP_WARN_STREAM(
this->nh_->get_logger(), "Using default value: " << this->dataPtr->hold_joints_);
}
RCLCPP_DEBUG_STREAM(
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 @@ -601,7 +628,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]) {
} 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 f03a03b

Please sign in to comment.