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

Pass the robot_description as an arg in initialize() with fallback to using node's parameters #66

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 @@ -42,7 +42,8 @@ class KinematicsInterface
*/
virtual bool initialize(
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
const std::string & end_effector_name) = 0;
const std::string & end_effector_name,
const std::string & robot_description = "") = 0;
Comment on lines +45 to +46
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.

Let's be crazy here and just replace "end_effector_name" with "param_base_name" to know where to search for the parameters. And make robot_description mandatory. To have backwards compatibility, I propose a new method with the following signature:

virtual bool initialize(
    const std::string & robot_description,
    std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
    const std::string & param_base_name = "kinematics",
    ) = 0;

Then we read `end_effector` from the parameters by provided `parameters_interface`.

Copy link
Member

Choose a reason for hiding this comment

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

I think the word we are looking for is namespace, see below ;)

virtual bool initialize(
    const std::string & robot_description,
    std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
    const std::string & param_namespace = "kinematics",
    ) = 0;

Copy link
Member

Choose a reason for hiding this comment

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

Yes exactly! This is the right way to do it. I want to avoid making the robot_description an optional arg.


/**
* \brief Convert Cartesian delta-x to joint delta-theta, using the Jacobian.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,8 @@ class KinematicsInterfaceKDL : public kinematics_interface::KinematicsInterface
public:
bool initialize(
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
const std::string & end_effector_name) override;
const std::string & end_effector_name,
const std::string & robot_description = "") override;

bool convert_cartesian_deltas_to_joint_deltas(
const Eigen::VectorXd & joint_pos, const Eigen::Matrix<double, 6, 1> & delta_x,
Expand Down
26 changes: 18 additions & 8 deletions kinematics_interface_kdl/src/kinematics_interface_kdl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,19 +22,29 @@ rclcpp::Logger LOGGER = rclcpp::get_logger("kinematics_interface_kdl");

bool KinematicsInterfaceKDL::initialize(
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
const std::string & end_effector_name)
const std::string & end_effector_name,
const std::string & robot_description)
{
// track initialization plugin
initialized = true;

// get robot description
auto robot_param = rclcpp::Parameter();
if (!parameters_interface->get_parameter("robot_description", robot_param))
std::string robot_description_local;
if (robot_description.empty())
{
RCLCPP_ERROR(LOGGER, "parameter robot_description not set");
return false;
// If the robot_description input argument is empty, try to get the
// robot_description from the node's parameters.
auto robot_param = rclcpp::Parameter();
if (!parameters_interface->get_parameter("robot_description", robot_param))
{
RCLCPP_ERROR(LOGGER, "parameter robot_description not set in kinematics_interface_kdl");
return false;
}
robot_description_local = robot_param.as_string();
}
else
{
robot_description_local = robot_description;
}
auto robot_description = robot_param.as_string();
// get alpha damping term
auto alpha_param = rclcpp::Parameter("alpha", 0.000005);
if (parameters_interface->has_parameter("alpha"))
Expand All @@ -44,7 +54,7 @@ bool KinematicsInterfaceKDL::initialize(
alpha = alpha_param.as_double();
// create kinematic chain
KDL::Tree robot_tree;
kdl_parser::treeFromString(robot_description, robot_tree);
kdl_parser::treeFromString(robot_description_local, robot_tree);
root_name_ = robot_tree.getRootSegment()->first;
if (!robot_tree.getChain(root_name_, end_effector_name, chain_))
{
Expand Down
Loading