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

Noetic devel update #26

Closed
wants to merge 8 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
47 changes: 47 additions & 0 deletions config/hand.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0" encoding="UTF-8"?>
<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"/>
</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="open" group="hand">
<joint name="panda_finger_joint1" value="0.04"/>
<joint name="panda_finger_joint2" value="0.04"/>
</group_state>
<group_state name="close" group="hand">
<joint name="panda_finger_joint1" value="0"/>
<joint name="panda_finger_joint2" value="0"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
<passive_joint name="panda_finger_joint2"/>
<!--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_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="Default"/>
<disable_collisions link1="panda_hand" link2="panda_link8" reason="Adjacent"/>
<disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link5" reason="Default"/>
<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_link8" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default"/>
<disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never"/>
<disable_collisions link1="panda_link5" link2="panda_rightfinger" reason="Default"/>
<disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never"/>
<disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never"/>
<disable_collisions link1="panda_link8" link2="panda_rightfinger" reason="Never"/>
</xacro:macro>
</robot>
97 changes: 0 additions & 97 deletions config/panda.srdf

This file was deleted.

23 changes: 23 additions & 0 deletions config/panda.srdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?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 />

<xacro:arg name="hand" default="false" />

<!--Add the hand if people request it-->
<xacro:if value="$(arg hand)">
<xacro:include filename="$(find panda_moveit_config)/config/hand.xacro" />
<xacro:hand />
</xacro:if>

<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<xacro:if value="$(arg hand)">
<end_effector name="hand" parent_link="panda_link8" group="hand"/>
</xacro:if>

</robot>
70 changes: 70 additions & 0 deletions config/panda_arm.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
<?xml version="1.0" encoding="UTF-8"?>
<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">
<joint name="virtual_joint"/>
<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"/>
</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.7855"/>
</group_state>
<group_state name="extended" group="panda_arm">
<joint name="panda_joint1" value="0"/>
<joint name="panda_joint2" value="-0.3927"/>
<joint name="panda_joint3" value="0"/>
<joint name="panda_joint4" value="-0.7855"/>
<joint name="panda_joint5" value="0"/>
<joint name="panda_joint6" value="3.142"/>
<joint name="panda_joint7" value="-0.785"/>
</group_state>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="panda_link0"/>
<!--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_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"/>
<disable_collisions link1="panda_link0" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link1" link2="panda_link2" reason="Adjacent"/>
<disable_collisions link1="panda_link1" link2="panda_link3" reason="Default"/>
<disable_collisions link1="panda_link1" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link2" link2="panda_link3" reason="Adjacent"/>
<disable_collisions link1="panda_link2" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link3" link2="panda_link4" reason="Adjacent"/>
<disable_collisions link1="panda_link3" link2="panda_link6" 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_link8" 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_link7" link2="panda_link8" reason="Adjacent"/>
<!-- Fix self-collisions
NOTE: The code below fixes self-collisions that are introduced because the
collision geometries provided by Franka are too course (see
https://github.com/ros-planning/panda_moveit_config/issues/72#issuecomment-768472329
for more information).
-->
<disable_collisions link1="panda_link5" link2="panda_link8" reason="Default" />
<disable_collisions link1="panda_link6" link2="panda_link8" reason="Default"/>
</xacro:macro>
</robot>
20 changes: 20 additions & 0 deletions config/panda_gripper_moveit_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
controller_list:
- name: position_joint_trajectory_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
- name: franka_gripper
action_ns: gripper_action
type: GripperCommand
default: true
joints:
- panda_finger_joint1
- panda_finger_joint2
13 changes: 13 additions & 0 deletions config/panda_moveit_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
controller_list:
- name: position_joint_trajectory_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
55 changes: 1 addition & 54 deletions config/ros_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -17,57 +17,4 @@ hardware_interface:
- panda_joint6
- panda_joint7
- panda_finger_joint1
sim_control_mode: 1 # 0: position, 1: velocity
# Publish all joint states
# Creates the /joint_states topic necessary in ROS
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
controller_list:
[]
position_joint_trajectory_controller:
type: position_controllers/JointTrajectoryController
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
gains:
panda_joint1:
p: 100
d: 1
i: 1
i_clamp: 1
panda_joint2:
p: 100
d: 1
i: 1
i_clamp: 1
panda_joint3:
p: 100
d: 1
i: 1
i_clamp: 1
panda_joint4:
p: 100
d: 1
i: 1
i_clamp: 1
panda_joint5:
p: 100
d: 1
i: 1
i_clamp: 1
panda_joint6:
p: 100
d: 1
i: 1
i_clamp: 1
panda_joint7:
p: 100
d: 1
i: 1
i_clamp: 1
sim_control_mode: 1 # 0: position, 1: velocity
23 changes: 0 additions & 23 deletions config/sensors_3d.yaml

This file was deleted.

Loading