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

Include panda arm hand #35

Merged
merged 9 commits into from
Aug 23, 2024
Merged

Include panda arm hand #35

merged 9 commits into from
Aug 23, 2024

Conversation

sjahr
Copy link
Contributor

@sjahr sjahr commented Aug 22, 2024

Plot twist: adding the hand was not straight forward because Drake does not have a concept of planning groups + the urdf of the moveit_panda_description and the drake_panda_description differ 🎉 This PR introduces the changes necessary to get it working and does some minor clean-ups along the way. @kamiradi

Screenshot from 2024-08-22 09-57-45

911jvj

@sjahr sjahr requested a review from sea-bass August 22, 2024 08:05
src/conversions.cpp Outdated Show resolved Hide resolved
[[nodiscard]] Eigen::VectorXd getJointPositions(const moveit::core::RobotState& moveit_state,
const std::string& group_name, const MultibodyPlant<double>& plant)
{
Eigen::VectorXd joint_positions = Eigen::VectorXd::Zero(plant.num_positions());
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Maybe it would be better to init this with the current plant positions 🤔 What do you think?

Copy link
Member

Choose a reason for hiding this comment

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

I am not sure. We can do it if we see an obvious error later?

for (const auto& joint_model : joint_model_group->getActiveJointModels())
{
const auto& joint_name = joint_model->getName();
const auto& joint_index = plant.GetJointByName(joint_name).ordinal();
Copy link
Contributor Author

Choose a reason for hiding this comment

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

This errors right now if a name that does not exist in the pant is passed to GetJointByName

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Copy link
Member

Choose a reason for hiding this comment

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

Is this where there was a difference between moveit_panda and drake_panda gave you trouble?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

No, moveit panda uses a single actuatable joint for the gripper (1 finger and the other finger is controlled with a joint that mirrors the first finger) and drake just uses two joints for the fingers

src/ktopt_planning_context.cpp Outdated Show resolved Hide resolved
src/conversions.cpp Outdated Show resolved Hide resolved
src/ktopt_planning_context.cpp Outdated Show resolved Hide resolved
Copy link
Member

@kamiradi kamiradi left a comment

Choose a reason for hiding this comment

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

This was super helpful @sjahr :). I felt the function names inside conversions. could be a indicative of the direction of conversion, given that there may be many more helper function that could be added. Other than that LGTM!

Thanks a lot.

src/conversions.cpp Show resolved Hide resolved
for (const auto& joint_model : joint_model_group->getActiveJointModels())
{
const auto& joint_name = joint_model->getName();
const auto& joint_index = plant.GetJointByName(joint_name).ordinal();
Copy link
Member

Choose a reason for hiding this comment

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

Is this where there was a difference between moveit_panda and drake_panda gave you trouble?

[[nodiscard]] Eigen::VectorXd getJointPositions(const moveit::core::RobotState& moveit_state,
const std::string& group_name, const MultibodyPlant<double>& plant)
{
Eigen::VectorXd joint_positions = Eigen::VectorXd::Zero(plant.num_positions());
Copy link
Member

Choose a reason for hiding this comment

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

I am not sure. We can do it if we see an obvious error later?

src/conversions.cpp Outdated Show resolved Hide resolved
CMakeLists.txt Outdated Show resolved Hide resolved
Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>
@sjahr sjahr merged commit 453713c into moveit:main Aug 23, 2024
2 checks passed
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