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

Kinematics interface with KDL implementation #1

Merged

Conversation

pac48
Copy link
Collaborator

@pac48 pac48 commented Jun 15, 2022

Add kinematics interface with a KDL implementation

The proposed interface defines 5 public methods: initialize, update_robot_state, convert_cartesian_deltas_to_joint_deltas, calculate_segment_transform, and convert_joint_deltas_to_cartesian_deltas. These methods are sufficient to do basic end effector Cartesian control, but more methods would be needed if we wanted to also do forward and inverse dynamics.

The KDL implementation assumes a URDF has been loaded to the robot_description parameter.

One potential issue is that Eigen is allocating memory for its operations.

I would appreciate feedback anyone has (design pattern and naming conventions)

@pac48 pac48 changed the title Kinematics interface with kdl implementation Kinematics interface with KDL implementation Jun 15, 2022
@dignakov
Copy link

I didn't say anything at the meeting, but I think this package is a great addition.

I do have one question/comment. There is already a place where the joint states are stored. What would be the reason for keeping a second set of state inside the kinematic interface? Could it not be a bit more functional where the joint positions, velocities, etc are passed into the functions?

@pac48
Copy link
Collaborator Author

pac48 commented Jun 16, 2022

I didn't say anything at the meeting, but I think this package is a great addition.

I do have one question/comment. There is already a place where the joint states are stored. What would be the reason for keeping a second set of state inside the kinematic interface? Could it not be a bit more functional where the joint positions, velocities, etc are passed into the functions?

That is a good point. If the user is require to pass the robot state in all of the other functions, (convert_cartesian_deltas_to_joint_deltas, calculate_segment_transform, and convert_joint_deltas_to_cartesian_deltas), then update_robot_state can be removed completely and the interface is almost stateless. The interface can still be in two state of course: initialized/uninitialized.

I guess the only real benefit to keeping the robot state internally is that the datatypes are different for each plugin. The values come in as vectors of doubles, but will need be copied to whatever type the kinematics interface uses. I am not sure that really matters that much.

@pac48
Copy link
Collaborator Author

pac48 commented Jun 19, 2022

I updated the interface to be stateless. Now each method requires you pass the joint positions in.

@pac48 pac48 requested a review from destogl June 23, 2022 15:05
Copy link
Member

@bmagyar bmagyar left a comment

Choose a reason for hiding this comment

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

more to come tomorrow morning

kdl_plugin/package.xml Outdated Show resolved Hide resolved
kdl_plugin/package.xml Outdated Show resolved Hide resolved
kdl_plugin/kdl_plugin.xml Outdated Show resolved Hide resolved
kinematics_interface/src/kinematics_interface_base.cpp Outdated Show resolved Hide resolved
kinematics_interface/package.xml Show resolved Hide resolved
kdl_plugin/package.xml Outdated Show resolved Hide resolved
kdl_plugin/CMakeLists.txt Outdated Show resolved Hide resolved
@pac48 pac48 requested a review from bmagyar July 5, 2022 13:01
@bmagyar bmagyar merged commit 6a26597 into ros-controls:master Jul 5, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants