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

Add hold_joints parameter #251

Merged
Merged
Show file tree
Hide file tree
Changes from 4 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
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
11 changes: 11 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,11 @@ 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 std::exception & e) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Include exception

RCLCPP_ERROR(impl_->model_nh_->get_logger(), "%s", e.what());
}
if (!gazeboSystem->initSim(
node_ros2,
impl_->parent_model_,
Expand Down
17 changes: 16 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,18 @@ bool GazeboSystem::initSim(
return false;
}

try {
this->dataPtr->hold_joints_ = this->nh_->get_parameter("hold_joints").as_bool();
} catch (const std::exception & e) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Include exception

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: " << 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 +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]) {
} 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
Loading