Gazebo | Ignition | Community
Ask Your Question
0

Has anyone ever used KDL and kdl_parser?

asked 2016-05-18 04:12:30 -0500

gabri89 gravatar image

Hi all,

I'm trying to extrapolate the jacobian and the matrix for the dynamic form of my arm. The arm is in .xacro file, so I tried to follow this tutorial for kdl_parser and this for KDL. But I've some difficulties, I'm not able to understand how to usr kdl_parser. The arm is in a catkin_ws directory, so can I use an external C++ code or I have to use kdl and kdl_parser function in my plugin? What have I to modify in CMakeList and package.xml? (are this two file owned to catkin_ws or to my_arm directory?)

Is there someone who has already use kdl that can help me?

Thank you!

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2018-11-06 07:36:18 -0500

Nurul Karim gravatar image

Easy approach for me was to use parameter server in a launch file

 <param name="robot_description" command="$(find xacro)/xacro.py $(find walking_excavator_urdf)/xacro_manzi/walking_excavator.urdf.xacro" />
 <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -x 0 -y 0 -z 1 -model robot" />

so from xacro/urdf you can directly load in ROS parameter, then use c++ code..

ros::NodeHandle node;
std::string robot_desc_string;
node.param("robot_description", robot_desc_string, std::string());
if (!kdl_parser::treeFromString(robot_desc_string, my_tree)){
  ROS_ERROR("Failed to construct kdl tree");
  return false;
}

This way you can get the tree, can verify with

   unsigned int nj = my_tree.getNrOfJoints();
   unsigned int js = my_tree.getNrOfSegments();
   ROS_INFO("NrOfJoints =%d   ||  NrOfSegments= %d \n", nj,js);
edit flag offensive delete link more
0

answered 2016-05-18 08:52:58 -0500

TwoBid gravatar image

updated 2016-05-19 04:42:38 -0500

Hey Gabri89,

I used KDL a few years ago to solve some inverse calculations. But this only on the ROS side and I guess you want to do that also, referring that you are using the catkin_ws...? In that case I would recommend you to read the catkin tutorial to understand how to include dependencies.

For an approach what should be modified: Link to similar problem

But to answer your main question, the kdl_parser is meant to translate your robot model definition file (urdf) into a kdl tree. This enables kdl to see the robot model as an kinematic chain what is required.

Here is some sample where I used pykdlutils (python). Think in C++ it should look similar: Sample code

Hope it helps you.

edit flag offensive delete link more

Comments

Hi TwoBid, thank you for your answer. Yes I referred to the ROS side. I tried to follow your link for modify dependencies in CmakeList and package of my_robot. Then I tried to make a C++ code link in the example in the kdl_parser tutorial and I've this error : undefined reference to "KDL::Tree::Tree(std::string const&)" ; another error : undefined reference to "kdl_parser::treeFromFile(...)" . Where am I wrong? Thank you!

gabri89 gravatar imagegabri89 ( 2016-05-18 10:34:52 -0500 )edit

Then it's still a problem that your not including your dependencies in the right way or your dependencies does not exist or you have spelling mistake or the package has a different name.

TwoBid gravatar imageTwoBid ( 2016-05-19 01:31:45 -0500 )edit

I try to explain better. I've an arm in gazebo, in the .xacro format. I want to extrapolate the jacobian and some other matrix of this arm using KDL, but I'm not still able to do this. I'm not sure to have installed KDL correctly. If I've KDL, have I to do a c++ file in my catkin_ws? Is there a template to follow? Thank you

gabri89 gravatar imagegabri89 ( 2016-06-02 04:28:07 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-05-18 04:12:30 -0500

Seen: 20,981 times

Last updated: Nov 06 '18