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

Fix #247 - explicitly declare position_proportional_gain parameter (backport #248) #251

Merged
merged 1 commit into from
Mar 15, 2024
Merged
Changes from all 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
17 changes: 8 additions & 9 deletions gz_ros2_control/src/gz_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,15 +204,14 @@ bool GazeboSimSystem::initSim(
this->dataPtr->joints_.resize(this->dataPtr->n_dof_);

constexpr double default_gain = 0.1;
if (!this->nh_->get_parameter_or(
"position_proportional_gain",
this->dataPtr->position_proportional_gain_, default_gain))
{
RCLCPP_WARN_STREAM(
this->nh_->get_logger(),
"The position_proportional_gain parameter was not defined, defaulting to: " <<
default_gain);
}

this->dataPtr->position_proportional_gain_ = this->nh_->declare_parameter<double>(
"position_proportional_gain", default_gain);

RCLCPP_INFO_STREAM(
this->nh_->get_logger(),
"The position_proportional_gain has been set to: " <<
this->dataPtr->position_proportional_gain_);

if (this->dataPtr->n_dof_ == 0) {
RCLCPP_ERROR_STREAM(this->nh_->get_logger(), "There is no joint available");
Expand Down
Loading