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

Allow users to set various cartesian path service parameters #58

Conversation

amalnanavati
Copy link
Contributor

Description

The PR adds various parameters that allow users to control the behavior of cartesian planning. This includes:

  • Allow users to change the avoid_collisions, jump_threshold, prismatic_jump_threshold, and revolute_jump_threshold attributes of the cartesian path service call.
  • Allow users to specify what fraction of the path must be completed in order to accept the solution.
  • Allow users to set the max_step from _plan_async(…)
  • Allow users to access the robot’s end effector name and base link name.

Note that unfortunately, MoveIt2’s ROS interface does not currently support revolute or prismatic jump thresholds.

Testing

  • Launch the simulated panda arm: ros2 launch panda_moveit_config ex_fake_control.launch.py
  • Test max_step:
    • Default movement: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True, verify it succeeds
    • Reset: ros2 run pymoveit2 ex_joint_goal.py --ros-args -p joint_positions:="[0.0, -0.7853981633974483, 0.0, -2.356194490192345, 0.0, 1.5707963267948966, 0.7853981633974483]"
    • Invalid parameter: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_max_step:=0.0, verify it fails
    • Reset
    • Largest max_step: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_max_step:=0.3, verify it succeeds
    • Reset
  • Text cartesian_jump_threshold:
    • Small jump threshold: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_jump_threshold:=0.001, verify that the planning/execution call succeeds but the arm does not actually move.
    • Reset
    • Medium jump threshold: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_jump_threshold:=1.0, verify that it gets almost to the goal but not quite.
    • Reset
    • Large jump threshold: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_jump_threshold:=2.0, verify that it gets to the goal.
    • Reset
  • Test cartesian_fraction_threshold:
    • High threshold that can be reached: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_fraction_threshold:=1.0, verify it succeeds
    • Reset
    • High threshold that cannot be reached: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_jump_threshold:=1.0 -p cartesian_fraction_threshold:=1.0, verify it fails
    • Reset
    • Impossible threshold: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_fraction_threshold:=1.1, verify it fails
    • Reset
  • Test cartesian_avoid_collisions:
    • Test without a collision object: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_avoid_collisions:=True, verify it succeeds
    • Reset
    • Add a collision object: ros2 run pymoveit2 ex_collision_primitive.py --ros-args -p shape:="sphere" -p position:="[0.573, 0.000, 0.488]" -p dimensions:="[0.04]"
    • Test with a collision object: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_avoid_collisions:=True, verify it stops before the collision
    • Reset
    • Test without avoiding collisions: ros2 run pymoveit2 ex_pose_goal.py --ros-args -p position:="[0.573, 0.000, 0.488]" -p quat_xyzw:="[1.000, -0.000, 0.001, -0.000]" -p cartesian:=True -p cartesian_avoid_collisions:=False, verify it goes all the way to the goal, ignoring the collision.

Copy link
Owner

@AndrejOrsula AndrejOrsula left a comment

Choose a reason for hiding this comment

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

Awesome! Thank you very much for your contribution @amalnanavati!

pymoveit2/moveit2.py Show resolved Hide resolved
@AndrejOrsula AndrejOrsula merged commit 3f87e3b into AndrejOrsula:devel Apr 4, 2024
2 checks passed
@amalnanavati amalnanavati deleted the amaln/cartesian_avoid_collision branch April 23, 2024 17:13
AndrejOrsula pushed a commit that referenced this pull request May 10, 2024
* Added ability to have cartesian planning calls avoid collisions

* Fix bad merge

* Allow users to set cartesian jump threshold

* Allow users to set cartesian max step

* Pass frame_id into the cartesian planning service

* Add ability to specify a required fraction for a cartesian plan to succeed

* Allowed users to get end effector name and base link name

* Add revolute and prismatic jump thresholds

* Formatting

* Added test cases
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.

2 participants