Skip to content
Snippets Groups Projects
Commit 2e7d38f5 authored by Florian Walch's avatar Florian Walch
Browse files

MoveIt: Fix gripper control, allow to use without gripper as well

parent 3f695940
No related branches found
No related tags found
No related merge requests found
Showing
with 206 additions and 11 deletions
......@@ -8,6 +8,9 @@
* Updated joint limits from URDF
* Removed `home` poses
* Fixed fake execution
* Add `load_gripper` argument (default: `true`) to `panda_moveit.launch`
* Conditionally load controllers/SRDFs based on `load_gripper`
* Add gripper controller configuration (requires running `franka_gripper_node`)
* Added `mimic` tag for gripper fingers to URDF
## 0.3.0 - 2018-02-22
......
<?xml version="1.0" ?>
<launch>
<arg name="robot_ip" default="robot.franka.de" />
<arg name="load_gripper" default="true" />
<include file="$(find franka_control)/launch/franka_control.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="load_gripper" value="$(arg load_gripper)" />
<arg name="load_gripper" value="false" />
</include>
<include file="$(find panda_moveit_config)/launch/panda_moveit.launch">
<arg name="load_gripper" value="false" />
</include>
<node name="move_to_start" pkg="franka_example_controllers" type="move_to_start.py" output="screen" required="true" />
</launch>
......@@ -3,7 +3,7 @@ moveit_setup_assistant_config:
package: franka_description
relative_path: robots/panda_arm_hand.urdf.xacro
SRDF:
relative_path: config/panda_arm_hand.srdf
relative_path: config/panda_arm_hand.srdf.xacro
CONFIG:
author_name: Franka Emika GmbH
author_email: info@franka.de
......
<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:macro name="hand">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="hand">
<link name="panda_hand" />
<link name="panda_leftfinger" />
<link name="panda_rightfinger" />
<joint name="panda_finger_joint1" />
<passive_joint name="panda_finger_joint2" />
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="panda_hand" link2="panda_leftfinger" reason="Adjacent" />
<disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent" />
<disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default" />
</xacro:macro>
</robot>
<?xml version='1.0' encoding='utf-8'?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:include filename="$(find panda_moveit_config)/config/panda_arm.xacro" />
<xacro:panda_arm />
</robot>
<?xml version="1.0" ?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="panda">
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:macro name="panda_arm">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="panda_arm">
<link name="panda_link0" />
<link name="panda_link1" />
<link name="panda_link2" />
<link name="panda_link3" />
<link name="panda_link4" />
<link name="panda_link5" />
<link name="panda_link6" />
<link name="panda_link7" />
<link name="panda_link8" />
<joint name="panda_joint1" />
<joint name="panda_joint2" />
<joint name="panda_joint3" />
<joint name="panda_joint4" />
<joint name="panda_joint5" />
<joint name="panda_joint6" />
<joint name="panda_joint7" />
<joint name="panda_joint8" />
<chain base_link="panda_link0" tip_link="panda_link8" />
</group>
<group name="panda_arm_hand">
<link name="panda_link0" />
<link name="panda_link1" />
<link name="panda_link2" />
......@@ -39,7 +16,6 @@
<link name="panda_link6" />
<link name="panda_link7" />
<link name="panda_link8" />
<link name="panda_hand" />
<joint name="panda_joint1" />
<joint name="panda_joint2" />
<joint name="panda_joint3" />
......@@ -48,50 +24,20 @@
<joint name="panda_joint6" />
<joint name="panda_joint7" />
<joint name="panda_joint8" />
<joint name="panda_hand_joint" />
<chain base_link="panda_link0" tip_link="panda_hand" />
</group>
<group name="hand">
<link name="panda_hand" />
<link name="panda_leftfinger" />
<link name="panda_rightfinger" />
<joint name="panda_finger_joint1" />
<joint name="panda_finger_joint2" />
<chain base_link="panda_link0" tip_link="panda_link8" />
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="ready" group="panda_arm">
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="-0.785" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="-2.356" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="1.571" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<group_state name="ready" group="panda_arm_hand">
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="-0.785" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="-2.356" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="1.571" />
<joint name="panda_joint7" value="0.785" />
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="-0.785" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="-2.356" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="1.571" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="hand" parent_link="panda_hand" group="hand" parent_group="panda_arm_hand" />
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="panda_hand" link2="panda_leftfinger" reason="Adjacent" />
<disable_collisions link1="panda_hand" link2="panda_link3" reason="Never" />
<disable_collisions link1="panda_hand" link2="panda_link4" reason="Never" />
<disable_collisions link1="panda_hand" link2="panda_link5" reason="Default" />
<disable_collisions link1="panda_hand" link2="panda_link6" reason="Never" />
<disable_collisions link1="panda_hand" link2="panda_link7" reason="Adjacent" />
<disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent" />
<disable_collisions link1="panda_leftfinger" link2="panda_link3" reason="Never" />
<disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never" />
<disable_collisions link1="panda_leftfinger" link2="panda_link6" reason="Never" />
<disable_collisions link1="panda_leftfinger" link2="panda_link7" reason="Never" />
<disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default" />
<disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent" />
<disable_collisions link1="panda_link0" link2="panda_link2" reason="Never" />
<disable_collisions link1="panda_link0" link2="panda_link3" reason="Never" />
......@@ -106,14 +52,11 @@
<disable_collisions link1="panda_link3" link2="panda_link5" reason="Never" />
<disable_collisions link1="panda_link3" link2="panda_link6" reason="Never" />
<disable_collisions link1="panda_link3" link2="panda_link7" reason="Never" />
<disable_collisions link1="panda_link3" link2="panda_rightfinger" reason="Never" />
<disable_collisions link1="panda_link4" link2="panda_link5" reason="Adjacent" />
<disable_collisions link1="panda_link4" link2="panda_link6" reason="Never" />
<disable_collisions link1="panda_link4" link2="panda_link7" reason="Never" />
<disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never" />
<disable_collisions link1="panda_link5" link2="panda_link6" reason="Adjacent" />
<disable_collisions link1="panda_link5" link2="panda_link7" reason="Default" />
<disable_collisions link1="panda_link6" link2="panda_link7" reason="Adjacent" />
<disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never" />
<disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never" />
</xacro:macro>
</robot>
<?xml version='1.0' encoding='utf-8'?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:include filename="$(find panda_moveit_config)/config/panda_arm.xacro" />
<xacro:include filename="$(find panda_moveit_config)/config/hand.xacro" />
<xacro:panda_arm />
<xacro:hand />
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="panda_arm_hand">
<group name="panda_arm" />
<group name="hand" />
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="ready" group="panda_arm_hand">
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="-0.785" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="-2.356" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="1.571" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="hand" parent_link="panda_hand" group="hand" parent_group="panda_arm_hand" />
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="panda_hand" link2="panda_link3" reason="Never" />
<disable_collisions link1="panda_hand" link2="panda_link4" reason="Never" />
<disable_collisions link1="panda_hand" link2="panda_link5" reason="Default" />
<disable_collisions link1="panda_hand" link2="panda_link6" reason="Never" />
<disable_collisions link1="panda_hand" link2="panda_link7" reason="Adjacent" />
<disable_collisions link1="panda_leftfinger" link2="panda_link3" reason="Never" />
<disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never" />
<disable_collisions link1="panda_leftfinger" link2="panda_link6" reason="Never" />
<disable_collisions link1="panda_leftfinger" link2="panda_link7" reason="Never" />
<disable_collisions link1="panda_link3" link2="panda_rightfinger" reason="Never" />
<disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never" />
<disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never" />
<disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never" />
</robot>
controller_list:
- name: position_joint_trajectory_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
controller_list:
- name: position_joint_trajectory_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
- name: franka_gripper
action_ns: gripper_action
type: GripperCommand
parallel: true
joints:
- panda_finger_joint1
- panda_finger_joint2
<launch>
<include file="$(find panda_moveit_config)/launch/planning_context.launch" />
<arg name="load_gripper" default="true" />
<include file="$(find panda_moveit_config)/launch/planning_context.launch">
<arg name="load_gripper" value="$(arg load_gripper)" />
</include>
<!-- GDB Debug Option -->
<arg name="debug" default="false" />
......@@ -27,7 +31,8 @@
<!-- Trajectory Execution Functionality -->
<include ns="move_group" file="$(find panda_moveit_config)/launch/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_manage_controllers" value="true" />
<arg name="moveit_controller_manager" value="panda" unless="$(arg fake_execution)"/>
<arg name="moveit_controller_manager" value="panda" if="$(eval not arg('fake_execution') and not arg('load_gripper'))"/>
<arg name="moveit_controller_manager" value="panda_gripper" if="$(eval not arg('fake_execution') and arg('load_gripper'))"/>
<arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/>
</include>
......
<launch>
<arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
<rosparam file="$(find panda_moveit_config)/config/panda_gripper_controllers.yaml"/>
</launch>
......@@ -2,7 +2,11 @@
<launch>
<!-- Valid values: "position", "effort" -->
<arg name="controller" default="position" />
<arg name="load_gripper" default="true" />
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="$(arg controller)_joint_trajectory_controller"/>
<include file="$(find panda_moveit_config)/launch/move_group.launch" />
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="position_joint_trajectory_controller"/>
<include file="$(find panda_moveit_config)/launch/move_group.launch">
<arg name="load_gripper" value="$(arg load_gripper)" />
</include>
</launch>
<launch>
<arg name="moveit_controller_manager" default="moveit_ros_control_interface::MoveItMultiControllerManager" />
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
<arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
<rosparam file="$(find panda_moveit_config)/config/panda_controllers.yaml"/>
</launch>
<launch>
<arg name="load_gripper" default="true" />
<!-- By default we do not overwrite the URDF. Change the following to true to change the default behavior -->
<arg name="load_robot_description" default="false"/>
......@@ -6,10 +8,12 @@
<arg name="robot_description" default="robot_description"/>
<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'"/>
<param if="$(eval arg('load_robot_description') and arg('load_gripper'))" name="$(arg robot_description)" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'"/>
<param if="$(eval arg('load_robot_description') and not arg('load_gripper'))" name="$(arg robot_description)" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm.urdf.xacro'"/>
<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find panda_moveit_config)/config/panda_arm_hand.srdf" />
<param name="$(arg robot_description)_semantic" command="$(find xacro)/xacro --inorder '$(find panda_moveit_config)/config/panda_arm_hand.srdf.xacro'" if="$(arg load_gripper)" />
<param name="$(arg robot_description)_semantic" command="$(find xacro)/xacro --inorder '$(find panda_moveit_config)/config/panda_arm.srdf.xacro'" unless="$(arg load_gripper)" />
<!-- Load updated joint limits (override information from URDF) -->
<group ns="$(arg robot_description)_planning">
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment