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

Use the urdf_ to set the robot_description in admittance controller #1094

Closed
Changes from 1 commit
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
6 changes: 6 additions & 0 deletions admittance_controller/src/admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -283,6 +283,12 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
force_torque_sensor_ = std::make_unique<semantic_components::ForceTorqueSensor>(
semantic_components::ForceTorqueSensor(admittance_->parameters_.ft_sensor.name));

// The AdmittanceRule / kinematics_interface::KinematicsInterfaceKDL requires
// the robot_description as a parameter. The controller manager stores the
// robot description in the urdf_ variable.
get_node()->declare_parameter("robot_description", rclcpp::PARAMETER_STRING);
get_node()->set_parameter(rclcpp::Parameter("robot_description", urdf_));

// configure admittance rule
if (admittance_->configure(get_node(), num_joints_) == controller_interface::return_type::ERROR)
{
Expand Down
Loading