Skip to content

Commit bbcea68

Browse files
committed
Pass the robot_description as an arg in initialize() with fallback
1 parent c8e4791 commit bbcea68

File tree

3 files changed

+22
-10
lines changed

3 files changed

+22
-10
lines changed

kinematics_interface/include/kinematics_interface/kinematics_interface.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,8 @@ class KinematicsInterface
4242
*/
4343
virtual bool initialize(
4444
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
45-
const std::string & end_effector_name) = 0;
45+
const std::string & end_effector_name,
46+
const std::string & robot_description = "") = 0;
4647

4748
/**
4849
* \brief Convert Cartesian delta-x to joint delta-theta, using the Jacobian.

kinematics_interface_kdl/include/kinematics_interface_kdl/kinematics_interface_kdl.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,8 @@ class KinematicsInterfaceKDL : public kinematics_interface::KinematicsInterface
4141
public:
4242
bool initialize(
4343
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
44-
const std::string & end_effector_name) override;
44+
const std::string & end_effector_name,
45+
const std::string & robot_description = "") override;
4546

4647
bool convert_cartesian_deltas_to_joint_deltas(
4748
const Eigen::VectorXd & joint_pos, const Eigen::Matrix<double, 6, 1> & delta_x,

kinematics_interface_kdl/src/kinematics_interface_kdl.cpp

Lines changed: 18 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -22,19 +22,29 @@ rclcpp::Logger LOGGER = rclcpp::get_logger("kinematics_interface_kdl");
2222

2323
bool KinematicsInterfaceKDL::initialize(
2424
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
25-
const std::string & end_effector_name)
25+
const std::string & end_effector_name,
26+
const std::string & robot_description)
2627
{
2728
// track initialization plugin
2829
initialized = true;
2930

30-
// get robot description
31-
auto robot_param = rclcpp::Parameter();
32-
if (!parameters_interface->get_parameter("robot_description", robot_param))
31+
std::string robot_description_local;
32+
if (robot_description.empty())
3333
{
34-
RCLCPP_ERROR(LOGGER, "parameter robot_description not set");
35-
return false;
34+
// If the robot_description input argument is empty, try to get the
35+
// robot_description from the node's parameters.
36+
auto robot_param = rclcpp::Parameter();
37+
if (!parameters_interface->get_parameter("robot_description", robot_param))
38+
{
39+
RCLCPP_ERROR(LOGGER, "parameter robot_description not set in kinematics_interface_kdl");
40+
return false;
41+
}
42+
robot_description_local = robot_param.as_string();
43+
}
44+
else
45+
{
46+
robot_description_local = robot_description;
3647
}
37-
auto robot_description = robot_param.as_string();
3848
// get alpha damping term
3949
auto alpha_param = rclcpp::Parameter("alpha", 0.000005);
4050
if (parameters_interface->has_parameter("alpha"))
@@ -44,7 +54,7 @@ bool KinematicsInterfaceKDL::initialize(
4454
alpha = alpha_param.as_double();
4555
// create kinematic chain
4656
KDL::Tree robot_tree;
47-
kdl_parser::treeFromString(robot_description, robot_tree);
57+
kdl_parser::treeFromString(robot_description_local, robot_tree);
4858
root_name_ = robot_tree.getRootSegment()->first;
4959
if (!robot_tree.getChain(root_name_, end_effector_name, chain_))
5060
{

0 commit comments

Comments
 (0)