diff --git a/universal_robot_description/launch/load.launch b/universal_robot_description/launch/load.launch new file mode 100644 index 0000000000000000000000000000000000000000..bbf729a0d38bffb6ae22687691e6d5c41db50b44 --- /dev/null +++ b/universal_robot_description/launch/load.launch @@ -0,0 +1,3 @@ +<launch> + <param name="robot_description" command="$(find xacro)/xacro.py '$(find universal_robot_description)/urdf/robot.urdf.xacro'" /> +</launch> \ No newline at end of file diff --git a/universal_robot_description/launch/test.launch b/universal_robot_description/launch/test.launch index 5065037ee1e747de283eeaa7bf59875147b23ad9..dc6e07b83ecf7bb9e2245d0112c2e947f48778e7 100644 --- a/universal_robot_description/launch/test.launch +++ b/universal_robot_description/launch/test.launch @@ -1,7 +1,7 @@ <launch> - <param name="robot_description" textfile="$(find universal_robot_description)/urdf/robot.xml" /> - <param name="use_gui" value="true"/> - <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node> - <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" /> - <node name="rviz" pkg="rviz" type="rviz" args="-d $(find urdf_tutorial)/urdf.vcg" /> + <include file="$(find universal_robot_description)/launch/load.launch" /> + <param name="use_gui" value="true"/> + <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node> + <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" /> + <node name="rviz" pkg="rviz" type="rviz" args="-d $(find urdf_tutorial)/urdf.vcg" /> </launch> diff --git a/universal_robot_description/urdf/robot.urdf.xacro b/universal_robot_description/urdf/robot.urdf.xacro new file mode 100644 index 0000000000000000000000000000000000000000..95f04c6ff6a8d3e2610618935a32eb8c8d30e089 --- /dev/null +++ b/universal_robot_description/urdf/robot.urdf.xacro @@ -0,0 +1,137 @@ +<?xml version="1.0"?> +<robot name="universal_robot"> + + <property name="pi" value="3.14" /> + + <property name="shoulder_height" value="0.1" /> + <property name="shoulder_offset" value="0.1" /> + <property name="upper_arm_length" value="0.5" /> + <property name="forearm_length" value="0.5" /> + <property name="wrist_1_length" value="0.1" /> + <property name="wrist_2_length" value="0.1" /> + <property name="wrist_3_length" value="0.1" /> + + + <link name="base_link" /> + + <joint name="shoulder_pan_joint" type="revolute"> + <parent link="base_link" /> + <child link = "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" /> + <limit lower="-${pi}" upper="${pi}" effort="10.0" velocity="1.0"/> + </joint> + + <link name="shoulder_link"> + <visual> + <geometry> + <cylinder length="${shoulder_height}" radius="0.1"/> + </geometry> + <origin xyz="0.0 0.0 ${-shoulder_height/2.0}" rpy="0.0 0.0 0.0" /> + </visual> + </link> + + <joint name="shoulder_lift_joint" type="revolute"> + <parent link="shoulder_link" /> + <child link = "upper_arm_link" /> + <origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 0.0 0.0" /> + <axis xyz="0.0 1.0 0.0" /> + <limit lower="-${pi}" upper="${pi}" effort="10.0" velocity="1.0"/> + </joint> + + <link name="upper_arm_link"> + <visual> + <geometry> + <cylinder length="${upper_arm_length}" radius="0.05"/> + </geometry> + <origin xyz="0.0 0.0 ${upper_arm_length/2.0}" rpy="0.0 0.0 0.0" /> + </visual> + </link> + + <joint name="elbow_joint" type="revolute"> + <parent link="upper_arm_link" /> + <child link = "forearm_link" /> + <origin xyz="0.0 ${-shoulder_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" /> + <axis xyz="0.0 -1.0 0.0" /> + <limit lower="-${pi}" upper="${pi}" effort="10.0" velocity="1.0"/> + </joint> + + <link name="forearm_link"> + <visual> + <geometry> + <cylinder length="${forearm_length}" radius="0.05"/> + </geometry> + <origin xyz="0.0 0.0 ${forearm_length/2.0}" rpy="0.0 0.0 0.0" /> + </visual> + </link> + + <joint name="wrist_1_joint" type="revolute"> + <parent link="forearm_link" /> + <child link = "wrist_1_link" /> + <origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 0.0 0.0" /> + <axis xyz="0.0 1.0 0.0" /> + <limit lower="-${pi}" upper="${pi}" effort="10.0" velocity="1.0"/> + </joint> + + <link name="wrist_1_link"> + <visual> + <geometry> + <cylinder length="${wrist_1_length}" radius="0.05"/> + </geometry> + <origin xyz="0.0 ${wrist_1_length/2.0} 0.0" rpy="-${pi/2.0} 0.0 0.0" /> + </visual> + </link> + + <joint name="wrist_2_joint" type="revolute"> + <parent link="wrist_1_link" /> + <child link = "wrist_2_link" /> + <origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" /> + <axis xyz="0.0 0.0 1.0" /> + <limit lower="-${pi}" upper="${pi}" effort="10.0" velocity="1.0"/> + </joint> + + <link name="wrist_2_link"> + <visual> + <geometry> + <cylinder length="${wrist_2_length}" radius="0.05"/> + </geometry> + <origin xyz="0.0 0.0 ${wrist_2_length/2.0}" rpy="0.0 0.0 0.0" /> + </visual> + </link> + + <joint name="wrist_3_joint" type="revolute"> + <parent link="wrist_2_link" /> + <child link = "wrist_3_link" /> + <origin xyz="0.0 0.0 ${wrist_3_length}" rpy="0.0 0.0 0.0" /> + <axis xyz="0.0 1.0 0.0" /> + <limit lower="-${pi}" upper="${pi}" effort="10.0" velocity="1.0"/> + </joint> + + <link name="wrist_3_link"> + <visual> + <geometry> + <cylinder length="${wrist_3_length}" radius="0.05"/> + </geometry> + <origin xyz="0.0 ${wrist_3_length/2.0} 0.0" rpy="${-pi/2.0} 0.0 0.0" /> + </visual> + </link> + + <joint name="ee_fixed_joint" type="fixed"> + <parent link="wrist_3_link" /> + <child link = "ee_link" /> + <origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" /> + </joint> + + <link name="ee_link"> + <visual> + <geometry> + <cylinder length="0.01" radius="0.06"/> + </geometry> + <origin xyz="0.0 0.0 0.0" rpy="0.0 ${-pi/2.0} 0.0" /> + </visual> + </link> + +</robot> + + + diff --git a/universal_robot_description/urdf/robot.xml b/universal_robot_description/urdf/robot.xml deleted file mode 100644 index f819ebff0a357fb1c5b0861d15316908a357ad6f..0000000000000000000000000000000000000000 --- a/universal_robot_description/urdf/robot.xml +++ /dev/null @@ -1,54 +0,0 @@ -<?xml version="1.0"?> -<robot name="universal_robot"> - <link name="base_link" /> - - <joint name="shoulder_pan_joint" type="revolute"> - <parent link="base_link" /> - <child link = "shoulder_link" /> - <origin xyz="0.0 0.0 0.10" rpy="0.0 0.0 0.0" /> - <axis xyz="0.0 0.0 1.0" /> - <limit lower="-3.14" upper="3.14" effort="10.0" velocity="1.0"/> - </joint> - - <link name="shoulder_link"> - <visual> - <geometry> - <cylinder length="0.20" radius="0.1"/> - </geometry> - </visual> - </link> - - <joint name="shoulder_lift_joint" type="revolute"> - <parent link="shoulder_link" /> - <child link = "upper_arm_link" /> - <axis xyz="0.0 1.0 0.0" /> - <limit lower="-3.14" upper="3.14" effort="10.0" velocity="1.0"/> - </joint> - - <link name="upper_arm_link"> - <visual> - <geometry> - <cylinder length="0.50" radius="0.05"/> - </geometry> - <origin xyz="0.0 0.20 0.25" rpy="0.0 0.0 0.0" /> - </visual> - </link> - - <joint name="elbow_joint" type="revolute"> - <parent link="upper_arm_link" /> - <child link = "forearm_link" /> - <origin xyz="0.0 0.0 0.50" rpy="0.0 0.0 0.0" /> - <axis xyz="0.0 -1.0 0.0" /> - <limit lower="-3.14" upper="3.14" effort="10.0" velocity="1.0"/> - </joint> - - <link name="forearm_link"> - <visual> - <geometry> - <cylinder length="0.50" radius="0.05"/> - </geometry> - <origin xyz="0.0 0.0 0.25" rpy="0.0 0.0 0.0" /> - </visual> - </link> - -</robot> \ No newline at end of file