diff --git a/universal_robot_description/urdf/robot.urdf.xacro b/universal_robot_description/urdf/robot.urdf.xacro index 2d755cdc403fb5d2575d11aae35ffe711f42f608..c86f517671a351d72777dc0eb61bb97bbb3aaf8f 100644 --- a/universal_robot_description/urdf/robot.urdf.xacro +++ b/universal_robot_description/urdf/robot.urdf.xacro @@ -53,7 +53,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, <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"/> + <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <dynamics damping="0.1" friction="0.1"/> </joint> @@ -82,7 +82,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, <child link = "upper_arm_link" /> <origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" /> <axis xyz="0.0 1.0 0.0" /> - <limit lower="-${pi}" upper="${pi}" effort="10.0" velocity="1.0"/> + <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <dynamics damping="0.1" friction="0.1"/> </joint> @@ -111,7 +111,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, <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"/> + <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <dynamics damping="0.1" friction="0.1"/> </joint> @@ -140,7 +140,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, <child link = "wrist_1_link" /> <origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" /> <axis xyz="0.0 1.0 0.0" /> - <limit lower="-${pi}" upper="${pi}" effort="10.0" velocity="1.0"/> + <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <dynamics damping="0.1" friction="0.1"/> </joint> @@ -149,13 +149,13 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, <geometry> <cylinder length="${wrist_1_length}" radius="${wrist_radius}"/> </geometry> - <origin xyz="0.0 ${wrist_1_length/2.0} 0.0" rpy="-${pi/2.0} 0.0 0.0" /> + <origin xyz="0.0 ${wrist_1_length/2.0} 0.0" rpy="${-pi/2.0} 0.0 0.0" /> </visual> <collision> <geometry> <cylinder length="${wrist_1_length}" radius="${wrist_radius}"/> </geometry> - <origin xyz="0.0 ${wrist_1_length/2.0} 0.0" rpy="-${pi/2.0} 0.0 0.0" /> + <origin xyz="0.0 ${wrist_1_length/2.0} 0.0" rpy="${-pi/2.0} 0.0 0.0" /> </collision> <inertial> <mass value="${wrist_1_mass}" /> @@ -169,7 +169,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, <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"/> + <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <dynamics damping="0.1" friction="0.1"/> </joint> @@ -198,7 +198,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, <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"/> + <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="1.0"/> <dynamics damping="0.1" friction="0.1"/> </joint>