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
Show file tree
Hide file tree
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
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,8 @@ class AdmittanceRule

/// Configure admittance rule memory using number of joints.
controller_interface::return_type configure(
const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node, const size_t num_joint);
const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node, const size_t num_joint,
const std::string & robot_description);

/// Reset all values back to default
controller_interface::return_type reset(const size_t num_joints);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "admittance_controller/admittance_rule.hpp"

#include <memory>
#include <string>
#include <vector>

#include "rclcpp/duration.hpp"
Expand All @@ -33,7 +34,8 @@ constexpr auto NUM_CARTESIAN_DOF = 6; // (3 translation + 3 rotation)

/// Configure admittance rule memory for num joints and load kinematics interface
controller_interface::return_type AdmittanceRule::configure(
const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node, const size_t num_joints)
const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node, const size_t num_joints,
const std::string & robot_description)
{
num_joints_ = num_joints;

Expand All @@ -51,7 +53,7 @@ controller_interface::return_type AdmittanceRule::configure(
kinematics_ = std::unique_ptr<kinematics_interface::KinematicsInterface>(
kinematics_loader_->createUnmanagedInstance(parameters_.kinematics.plugin_name));
if (!kinematics_->initialize(
node->get_node_parameters_interface(), parameters_.kinematics.tip))
node->get_node_parameters_interface(), parameters_.kinematics.tip, robot_description))
Copy link
Member

@destogl destogl Jul 24, 2024

Choose a reason for hiding this comment

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

Suggested change
node->get_node_parameters_interface(), parameters_.kinematics.tip, robot_description))
node->get_node_parameters_interface(), "kinematics", robot_description))

Propose to set here param_base_name so that we search for the parameters under controller interface.kinematics. As we are doing in JointLimiters

{
return controller_interface::return_type::ERROR;
}
Expand Down
10 changes: 9 additions & 1 deletion admittance_controller/src/admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,9 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
semantic_components::ForceTorqueSensor(admittance_->parameters_.ft_sensor.name));

// configure admittance rule
if (admittance_->configure(get_node(), num_joints_) == controller_interface::return_type::ERROR)
if (
admittance_->configure(get_node(), num_joints_, urdf_) ==
controller_interface::return_type::ERROR)
{
return controller_interface::CallbackReturn::ERROR;
}
Expand Down Expand Up @@ -394,6 +396,12 @@ controller_interface::return_type AdmittanceController::update_and_write_command
return controller_interface::return_type::ERROR;
}

if (period.seconds() > 5.0) {
RCLCPP_WARN(
get_node()->get_logger(), "Large dt, skipping!");
return controller_interface::return_type::OK;
}

// update input reference from chainable interfaces
read_state_reference_interfaces(reference_);

Expand Down