Skip to content
Snippets Groups Projects
Commit d735627e authored by Kelsey's avatar Kelsey
Browse files

Changing base_link to ur_base_link in the description and making

base_link a dummy link to better support MoveIt.
parent 37db3fc6
Branches
Tags
No related merge requests found
...@@ -5,4 +5,4 @@ moveit_setup_assistant_config: ...@@ -5,4 +5,4 @@ moveit_setup_assistant_config:
SRDF: SRDF:
relative_path: config/ur10.srdf relative_path: config/ur10.srdf
CONFIG: CONFIG:
generated_timestamp: 1395339352 generated_timestamp: 1404841877
\ No newline at end of file \ No newline at end of file
...@@ -6,4 +6,4 @@ controller_list: ...@@ -6,4 +6,4 @@ controller_list:
- elbow_joint - elbow_joint
- wrist_1_joint - wrist_1_joint
- wrist_2_joint - wrist_2_joint
- wrist_3_joint - wrist_3_joint
\ No newline at end of file
...@@ -2,10 +2,4 @@ manipulator: ...@@ -2,10 +2,4 @@ manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005 kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005 kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3 kinematics_solver_attempts: 3
\ No newline at end of file
manipulator_new:
kinematics_solver: ur_kinematics/UR10KinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
<package> <package>
<name>ur10_moveit_config</name> <name>ur10_moveit_config</name>
<version>1.0.2</version> <version>1.0.3</version>
<description> <description>
An automatically generated package with all the configuration and launch files for using the ur10 with the MoveIt Motion Planning Framework An automatically generated package with all the configuration and launch files for using the ur10 with the MoveIt Motion Planning Framework
</description> </description>
......
...@@ -5,4 +5,4 @@ moveit_setup_assistant_config: ...@@ -5,4 +5,4 @@ moveit_setup_assistant_config:
SRDF: SRDF:
relative_path: config/ur5.srdf relative_path: config/ur5.srdf
CONFIG: CONFIG:
generated_timestamp: 1395340824 generated_timestamp: 1404842691
\ No newline at end of file \ No newline at end of file
...@@ -34,7 +34,7 @@ ...@@ -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: 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" /> <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: 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="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="wrist_1_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" /> <disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
......
<package> <package>
<name>ur5_moveit_config</name> <name>ur5_moveit_config</name>
<version>1.0.2</version> <version>1.0.3</version>
<description> <description>
An automatically generated package with all the configuration and launch files for using the ur5 with the MoveIt Motion Planning Framework An automatically generated package with all the configuration and launch files for using the ur5 with the MoveIt Motion Planning Framework
</description> </description>
......
...@@ -51,6 +51,15 @@ ...@@ -51,6 +51,15 @@
<xacro:macro name="ur10_robot" params="prefix"> <xacro:macro name="ur10_robot" params="prefix">
<link name="${prefix}base_link" > <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> <visual>
<geometry> <geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" /> <mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" />
...@@ -73,7 +82,7 @@ ...@@ -73,7 +82,7 @@
</link> </link>
<joint name="${prefix}shoulder_pan_joint" type="revolute"> <joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" /> <parent link="${prefix}ur_base_link" />
<child link = "${prefix}shoulder_link" /> <child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" /> <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" /> <axis xyz="0.0 0.0 1.0" />
......
...@@ -51,6 +51,15 @@ ...@@ -51,6 +51,15 @@
<xacro:macro name="ur10_robot" params="prefix"> <xacro:macro name="ur10_robot" params="prefix">
<link name="${prefix}base_link" > <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> <visual>
<geometry> <geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" /> <mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" />
...@@ -73,7 +82,7 @@ ...@@ -73,7 +82,7 @@
</link> </link>
<joint name="${prefix}shoulder_pan_joint" type="revolute"> <joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" /> <parent link="${prefix}ur_base_link" />
<child link = "${prefix}shoulder_link" /> <child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" /> <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" /> <axis xyz="0.0 0.0 1.0" />
......
...@@ -52,6 +52,15 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -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"> <xacro:macro name="ur5_robot" params="prefix">
<link name="${prefix}base_link" > <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> <visual>
<geometry> <geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" /> <mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" />
...@@ -71,7 +80,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -71,7 +80,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
</link> </link>
<joint name="${prefix}shoulder_pan_joint" type="revolute"> <joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" /> <parent link="${prefix}ur_base_link" />
<child link = "${prefix}shoulder_link" /> <child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" /> <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0 0 1" /> <axis xyz="0 0 1" />
......
...@@ -52,6 +52,15 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -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"> <xacro:macro name="ur5_robot" params="prefix">
<link name="${prefix}base_link" > <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> <visual>
<geometry> <geometry>
<mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" /> <mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" />
...@@ -71,7 +80,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, ...@@ -71,7 +80,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
</link> </link>
<joint name="${prefix}shoulder_pan_joint" type="revolute"> <joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" /> <parent link="${prefix}ur_base_link" />
<child link = "${prefix}shoulder_link" /> <child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" /> <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0 0 1" /> <axis xyz="0 0 1" />
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment