You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
When trying to control the robot however, I noticed that the panda_gripper_center is not automatically set as the end effector of the panda_arm move group. As a result I have to set it using the self.moveit_commander.robot.get_group("panda_arm").set_end_effector_link("panda_gripper_center". After playing around with the moveit_setup_assistant` I came to the following conclusions about using end effectors. Please correct me if I'm wrong.
My conclusion:
An end effector can only be set for a move group that consists of a chain of links.
When in your srdf you set a link as an end effector that is part of the move group itself it gets is set as the end effector by the moveit_commander.
When in the srdf you set a link as the end effector that is not part of the move_group but part of a move_group higher in the chain it is not automatically set. You can, however, control it with the specified link as the end effector after setting it manually in the code using the self.move_group.set_end_effector_link("<YOUR_SPECIFIED_EEF_LINK>").
For move groups containing only links and or joints, you can not set and thus plan w.r.t. an end effector.
Run the roslaunch panda_moveit_config demo.launch.
Run the moveit_commander script below and check the output.
import rospy
import moveit_commander
import sys
# Init service node
rospy.init_node("moveit_planner_server")
# initialize moveit_commander and robot commander
moveit_commander.roscpp_initialize(sys.argv)
# Get robot commander
robot = moveit_commander.RobotCommander(robot_description="robot_description", ns="/")
# Get move_group
move_group = robot.get_group("panda_arm")
print(move_group.get_end_effector_link())
move_group.set_end_effector_link("panda_gripper_center")
print(move_group.get_end_effector_link())
Expected behaviour
For the panda_arm group the panda_gripper_center joint should be set as the end effector. Thus manually setting it using `move_group.set_end_effector_link("panda_gripper_center") is not needed.
Actual behaviour
For the panda_arm group the panda_gripper_center link is not set as the end effector (see print statement 1). I therefore need to manually set it using move_group.set_end_effector_link("panda_gripper_center"). After this is done, the end effector is set to be the panda_gripper_center(see print statement 2). Further, I can now successfully control the robot w.r.t. thepanda_gripepr_center`.
An end effector can only be set for a move group that consists of a chain of links.
That's true: Currently the MoveGroupInterface doesn't support Cartesian targets for kinematic trees that have several tips, because we can only set a single PoseTarget.
When in the srdf you set a link as the end effector that is not part of the move_group but part of a move_group higher in the chain it is not automatically set.
The end-effector link should usually be part of the group you are controlling (and if not, it should be rigidly connected to it). If the group is a chain, the end effector link is set automatically to the last link of the chain.
You can, however, control it with the specified link as the end effector after setting it manually in the code using the self.move_group.set_end_effector_link("<YOUR_SPECIFIED_EEF_LINK>").
That's the expected behavior.
If you want panda_gripper_center to become your end effector link by default, you should extend the chain up to this link.
Description
In order to control the gripper of the
panda_emika_franka robot
, I added an extra virtual link to my the robotsrdf
andurdf
files (See /rickstaa/panda_moveit_config/tree/melodic-devel-panda_autograsp and /rickstaa/franka_ros/tree/melodic-devel-panda_autograsp). This will create the following model:When trying to control the robot however, I noticed that the
panda_gripper_center
is not automatically set as the end effector of thepanda_arm
move group. As a result I have to set it using theself.moveit_commander.robot.get_group("panda_arm").set_end_effector_link("panda_gripper_center". After playing around with the
moveit_setup_assistant` I came to the following conclusions about using end effectors. Please correct me if I'm wrong.My conclusion:
srdf
you set a link as an end effector that is part of the move group itself it gets is set as the end effector by the moveit_commander.srdf
you set a link as the end effector that is not part of the move_group but part of a move_group higher in the chain it is not automatically set. You can, however, control it with the specified link as the end effector after setting it manually in the code using theself.move_group.set_end_effector_link("<YOUR_SPECIFIED_EEF_LINK>")
.Your environment
Steps to reproduce
catkin_ws
.roslaunch panda_moveit_config demo.launch
.Expected behaviour
For the
panda_arm
group thepanda_gripper_center
joint should be set as the end effector. Thus manually setting it using `move_group.set_end_effector_link("panda_gripper_center") is not needed.Actual behaviour
For the
panda_arm
group thepanda_gripper_center
link is not set as the end effector (see print statement 1). I therefore need to manually set it usingmove_group.set_end_effector_link("panda_gripper_center"). After this is done, the end effector is set to be the
panda_gripper_center(see print statement 2). Further, I can now successfully control the robot w.r.t. the
panda_gripepr_center`.Backtrace or Console output
The text was updated successfully, but these errors were encountered: