Skip to content

Commit

Permalink
Changing base_link to ur_base_link in the description and making
Browse files Browse the repository at this point in the history
base_link a dummy link to better support MoveIt.
  • Loading branch information
kphawkins committed Jul 9, 2014
1 parent 37db3fc commit d735627
Show file tree
Hide file tree
Showing 11 changed files with 47 additions and 17 deletions.
2 changes: 1 addition & 1 deletion ur10_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
Expand Up @@ -5,4 +5,4 @@ moveit_setup_assistant_config:
SRDF:
relative_path: config/ur10.srdf
CONFIG:
generated_timestamp: 1395339352
generated_timestamp: 1404841877
2 changes: 1 addition & 1 deletion ur10_moveit_config/config/fake_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,4 +6,4 @@ controller_list:
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
- wrist_3_joint
8 changes: 1 addition & 7 deletions ur10_moveit_config/config/kinematics.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,4 @@ manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3

manipulator_new:
kinematics_solver: ur_kinematics/UR10KinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
kinematics_solver_attempts: 3
2 changes: 1 addition & 1 deletion ur10_moveit_config/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<package>

<name>ur10_moveit_config</name>
<version>1.0.2</version>
<version>1.0.3</version>
<description>
An automatically generated package with all the configuration and launch files for using the ur10 with the MoveIt Motion Planning Framework
</description>
Expand Down
2 changes: 1 addition & 1 deletion ur5_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
Expand Up @@ -5,4 +5,4 @@ moveit_setup_assistant_config:
SRDF:
relative_path: config/ur5.srdf
CONFIG:
generated_timestamp: 1395340824
generated_timestamp: 1404842691
2 changes: 1 addition & 1 deletion ur5_moveit_config/config/ur5.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
<!--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="fixed_base" type="fixed" parent_frame="world" child_link="base_link" />
<!--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="base_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="ur_base_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
Expand Down
2 changes: 1 addition & 1 deletion ur5_moveit_config/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<package>

<name>ur5_moveit_config</name>
<version>1.0.2</version>
<version>1.0.3</version>
<description>
An automatically generated package with all the configuration and launch files for using the ur5 with the MoveIt Motion Planning Framework
</description>
Expand Down
11 changes: 10 additions & 1 deletion ur_description/urdf/ur10.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,15 @@
<xacro:macro name="ur10_robot" params="prefix">

<link name="${prefix}base_link" >
</link>

<joint name="${prefix}base_link_joint" type="fixed">
<parent link="${prefix}base_link" />
<child link = "${prefix}ur_base_link" />
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>

<link name="${prefix}ur_base_link" >
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" />
Expand All @@ -73,7 +82,7 @@
</link>

<joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" />
<parent link="${prefix}ur_base_link" />
<child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" />
Expand Down
11 changes: 10 additions & 1 deletion ur_description/urdf/ur10_joint_limited.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,15 @@
<xacro:macro name="ur10_robot" params="prefix">

<link name="${prefix}base_link" >
</link>

<joint name="${prefix}base_link_joint" type="fixed">
<parent link="${prefix}base_link" />
<child link = "${prefix}ur_base_link" />
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>

<link name="${prefix}ur_base_link" >
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" />
Expand All @@ -73,7 +82,7 @@
</link>

<joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" />
<parent link="${prefix}ur_base_link" />
<child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" />
Expand Down
11 changes: 10 additions & 1 deletion ur_description/urdf/ur5.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,15 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<xacro:macro name="ur5_robot" params="prefix">

<link name="${prefix}base_link" >
</link>

<joint name="${prefix}base_link_joint" type="fixed">
<parent link="${prefix}base_link" />
<child link = "${prefix}ur_base_link" />
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>

<link name="${prefix}ur_base_link" >
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" />
Expand All @@ -71,7 +80,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
</link>

<joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" />
<parent link="${prefix}ur_base_link" />
<child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0 0 1" />
Expand Down
11 changes: 10 additions & 1 deletion ur_description/urdf/ur5_joint_limited.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,15 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<xacro:macro name="ur5_robot" params="prefix">

<link name="${prefix}base_link" >
</link>

<joint name="${prefix}base_link_joint" type="fixed">
<parent link="${prefix}base_link" />
<child link = "${prefix}ur_base_link" />
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>

<link name="${prefix}ur_base_link" >
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" />
Expand All @@ -71,7 +80,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
</link>

<joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" />
<parent link="${prefix}ur_base_link" />
<child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0 0 1" />
Expand Down

0 comments on commit d735627

Please sign in to comment.