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

Integrate this driver with MoveIt Task constructor #53

Open
karanchahal opened this issue Jul 1, 2024 · 1 comment
Open

Integrate this driver with MoveIt Task constructor #53

karanchahal opened this issue Jul 1, 2024 · 1 comment

Comments

@karanchahal
Copy link

Hello,

Thanks for this package, how would we use this driver and it's low level fuctions like.

driver->set_gripper_position(0xFF);
    while (driver->gripper_is_moving())
    {
      std::this_thread::sleep_for(std::chrono::milliseconds(500));
    }

    std::cout << "Opening the gripper..." << std::endl;
    driver->set_gripper_position(0x00);
    while (driver->gripper_is_moving())
    {
      std::this_thread::sleep_for(std::chrono::milliseconds(500));
    }

    std::cout << "Half closing the gripper..." << std::endl;
    driver->set_gripper_position(0x80);

like set_gripper_position function in the driver, through the move it task constructor interface of

auto move_to = std::make_unique<mtc::stages::MoveTo>("move to", std::make_shared<mtc::solvers::JointInterpolationPlanner>());
    move_to->setGroup(arm_group_name);
    move_to->setGoal({{"gripper_left": 0.75, {"gripper_right": 0.75}}); # this is just doing joint t=interpolation
    task.add(std::move(move_to));

joint interpolation is not a thing in the real robotiq driver, so I guess how would move it task constructor plumb a position control + velocity / force command ?

@ashwinvkNV
Copy link

I don't think you can control the gripper_left and gripper_right independently because the gripper itself cannot control both these joints independently.
You can only send a "POSITION REQUEST". Refer page 42 of this manual

Instead you can control the "finger_joint" mentioned in the urdf through task constructor as shown below.

auto move_to_close = std::make_unique<mtc::stages::MoveTo>("move to", std::make_shared<mtc::solvers::JointInterpolationPlanner>());
    move_to_close->setGroup(arm_group_name);
    move_to_close->setGoal({{"finger_joint", 0.623}});

In order to this you also have to specify a srdf file. I have attached the urdf, srdf, launch and task_constructor files for reference. This was tested on a real life 2F-140. And I was able to open and close the gripper.

robotiq_moveit_task_constructor.zip

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

No branches or pull requests

2 participants