Skip to content
This repository was archived by the owner on May 18, 2025. It is now read-only.

Commit f17adc9

Browse files
christophfroehlichmergify[bot]
authored andcommitted
Add hold_joints parameter (#251)
(cherry picked from commit 7682dce) # Conflicts: # gazebo_ros2_control/src/gazebo_system.cpp
1 parent 6cc95ed commit f17adc9

File tree

3 files changed

+55
-0
lines changed

3 files changed

+55
-0
lines changed

doc/index.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -213,6 +213,7 @@ The *gazebo_ros2_control* ``<plugin>`` tag also has the following optional child
213213
* ``<robot_param>``: The location of the ``robot_description`` (URDF) on the parameter server, defaults to ``robot_description``
214214
* ``<robot_param_node>``: Name of the node where the ``robot_param`` is located, defaults to ``robot_state_publisher``
215215
* ``<parameters>``: YAML file with the configuration of the controllers
216+
* ``<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.
216217

217218
Default gazebo_ros2_control Behavior
218219
-----------------------------------------------------------

gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -184,6 +184,12 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element
184184
} else {
185185
impl_->robot_description_node_ = "robot_state_publisher"; // default
186186
}
187+
// Hold joints if no control mode is active?
188+
bool hold_joints = true; // default
189+
if (sdf->HasElement("hold_joints")) {
190+
hold_joints =
191+
sdf->GetElement("hold_joints")->Get<bool>();
192+
}
187193

188194
// Read urdf from ros parameter server
189195
std::string urdf_string;
@@ -325,6 +331,23 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element
325331
RCLCPP_DEBUG(
326332
impl_->model_nh_->get_logger(), "Loaded hardware interface %s!",
327333
robot_hw_sim_type_str_.c_str());
334+
try {
335+
node_ros2->declare_parameter("hold_joints", rclcpp::ParameterValue(hold_joints));
336+
} catch (const rclcpp::exceptions::ParameterAlreadyDeclaredException & e) {
337+
RCLCPP_ERROR(
338+
impl_->model_nh_->get_logger(), "Parameter 'hold_joints' has already been declared, %s",
339+
e.what());
340+
} catch (const rclcpp::exceptions::InvalidParametersException & e) {
341+
RCLCPP_ERROR(
342+
impl_->model_nh_->get_logger(), "Parameter 'hold_joints' has invalid name, %s", e.what());
343+
} catch (const rclcpp::exceptions::InvalidParameterValueException & e) {
344+
RCLCPP_ERROR(
345+
impl_->model_nh_->get_logger(), "Parameter 'hold_joints' value is invalid, %s", e.what());
346+
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
347+
RCLCPP_ERROR(
348+
impl_->model_nh_->get_logger(), "Parameter 'hold_joints' value has wrong type, %s",
349+
e.what());
350+
}
328351
if (!gazeboSystem->initSim(
329352
node_ros2,
330353
impl_->parent_model_,

gazebo_ros2_control/src/gazebo_system.cpp

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -116,6 +116,9 @@ class gazebo_ros2_control::GazeboSystemPrivate
116116

117117
/// \brief mapping of mimicked joints to index of joint they mimic
118118
std::vector<MimicJoint> mimic_joints_;
119+
120+
// Should hold the joints if no control_mode is active
121+
bool hold_joints_ = true;
119122
};
120123

121124
namespace gazebo_ros2_control
@@ -141,6 +144,30 @@ bool GazeboSystem::initSim(
141144
return false;
142145
}
143146

147+
try {
148+
this->dataPtr->hold_joints_ = this->nh_->get_parameter("hold_joints").as_bool();
149+
} catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
150+
RCLCPP_ERROR(
151+
this->nh_->get_logger(),
152+
"Parameter 'hold_joints' not initialized, with error %s", ex.what());
153+
RCLCPP_WARN_STREAM(
154+
this->nh_->get_logger(), "Using default value: " << this->dataPtr->hold_joints_);
155+
} catch (rclcpp::exceptions::ParameterNotDeclaredException & ex) {
156+
RCLCPP_ERROR(
157+
this->nh_->get_logger(),
158+
"Parameter 'hold_joints' not declared, with error %s", ex.what());
159+
RCLCPP_WARN_STREAM(
160+
this->nh_->get_logger(), "Using default value: " << this->dataPtr->hold_joints_);
161+
} catch (rclcpp::ParameterTypeException & ex) {
162+
RCLCPP_ERROR(
163+
this->nh_->get_logger(),
164+
"Parameter 'hold_joints' has wrong type: %s", ex.what());
165+
RCLCPP_WARN_STREAM(
166+
this->nh_->get_logger(), "Using default value: " << this->dataPtr->hold_joints_);
167+
}
168+
RCLCPP_DEBUG_STREAM(
169+
this->nh_->get_logger(), "hold_joints (system): " << this->dataPtr->hold_joints_ << std::endl);
170+
144171
registerJoints(hardware_info, parent_model);
145172
registerSensors(hardware_info, parent_model);
146173

@@ -745,6 +772,7 @@ hardware_interface::return_type GazeboSystem::write(
745772

746773
} else if (this->dataPtr->joint_control_methods_[j] & EFFORT) {
747774
this->dataPtr->sim_joints_[j]->SetForce(0, this->dataPtr->joint_effort_cmd_[j]);
775+
<<<<<<< HEAD
748776

749777
} else if (this->dataPtr->joint_control_methods_[j] & VELOCITY_PID) {
750778
double vel_goal = this->dataPtr->joint_velocity_cmd_[j];
@@ -758,6 +786,9 @@ hardware_interface::return_type GazeboSystem::write(
758786
double cmd = this->dataPtr->pos_pid[j].computeCommand(pos_goal - pos, dt);
759787
this->dataPtr->sim_joints_[j]->SetForce(0, cmd);
760788
} else if (this->dataPtr->is_joint_actuated_[j]) {
789+
=======
790+
} else if (this->dataPtr->is_joint_actuated_[j] && this->dataPtr->hold_joints_) {
791+
>>>>>>> 7682dce (Add `hold_joints` parameter (#251))
761792
// Fallback case is a velocity command of zero (only for actuated joints)
762793
this->dataPtr->sim_joints_[j]->SetVelocity(0, 0.0);
763794
}

0 commit comments

Comments
 (0)