diff --git a/CAD_Designs/vl53l7cx.stl b/CAD_Designs/vl53l7cx.stl index 25e693fe915d28329a4502a89bbf711955d054b1..bf40d83b97c8d9fe6d732ee3018a793ab4a66488 100644 Binary files a/CAD_Designs/vl53l7cx.stl and b/CAD_Designs/vl53l7cx.stl differ diff --git a/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/initial_positions.yaml b/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/initial_positions.yaml index f74bbbd9c2eafacaa7a638fb963766611a4b2135..343a1821fd45f45252bd11844ddd02c1ca6f0b2b 100644 --- a/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/initial_positions.yaml +++ b/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/initial_positions.yaml @@ -1,6 +1,7 @@ shoulder_pan_joint: 0.0 shoulder_lift_joint: -1.57 elbow_joint: 0.0 +sensor_joint: 0.0 wrist_1_joint: -1.57 wrist_2_joint: 0.0 wrist_3_joint: 0.0 diff --git a/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/default_kinematics.yaml b/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/default_kinematics.yaml index 3054ec13ec7e955e333cffac74dd9c6afba64aaf..f7da8171f7d844cf763317a37967eca353b78d7d 100644 --- a/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/default_kinematics.yaml +++ b/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/default_kinematics.yaml @@ -22,8 +22,8 @@ kinematics: yaw: 0 sensor: x: -0.30635 - y: 0 - z: 0 + y: 0.0 + z: 0.02 roll: 0 pitch: 0 yaw: 0 diff --git a/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/joint_limits.yaml b/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/joint_limits.yaml index 44be1f4a512c3b6a3ccb4e17022e24dbd4647cfb..fc75bc8a7d114730c8db9cad4950564df409f99f 100644 --- a/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/joint_limits.yaml +++ b/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/joint_limits.yaml @@ -48,6 +48,16 @@ joint_limits: max_position: !degrees 180.0 max_velocity: !degrees 180.0 min_position: !degrees -180.0 + sensor_joint: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 0.0 + max_position: !degrees 0.0 + max_velocity: !degrees 0.0 + min_position: !degrees 0.0 wrist_1_joint: # acceleration limits are not publicly available has_acceleration_limits: false diff --git a/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/physical_parameters.yaml b/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/physical_parameters.yaml index 702527a213422bf6cfb57fbe57b1b2b400ceffec..a099e953668d0037c486474f8e99e3b9f98130bc 100644 --- a/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/physical_parameters.yaml +++ b/workspaces/COLCON_WS/install/ur_description/share/ur_description/config/ur10e/physical_parameters.yaml @@ -3,7 +3,7 @@ offsets: shoulder_offset: 0.1762 # measured from model elbow_offset: 0.0393 # measured from model - sensor_offset: 0.02 # measured from model + sensor_offset: 0.00 # measured from model inertia_parameters: base_mass: 4.0 # This mass might be incorrect diff --git a/workspaces/COLCON_WS/install/ur_description/share/ur_description/meshes/ur10e/collision/vl53l7cx.stl b/workspaces/COLCON_WS/install/ur_description/share/ur_description/meshes/ur10e/collision/vl53l7cx.stl index fdd48bab0718d007f0605c2db77e739fab8f00d3..bf40d83b97c8d9fe6d732ee3018a793ab4a66488 100644 Binary files a/workspaces/COLCON_WS/install/ur_description/share/ur_description/meshes/ur10e/collision/vl53l7cx.stl and b/workspaces/COLCON_WS/install/ur_description/share/ur_description/meshes/ur10e/collision/vl53l7cx.stl differ diff --git a/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/inc/ur_common.xacro b/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/inc/ur_common.xacro index a1d3d902d2f74c810da78394a3bb330a3f6827dd..68594ef81f92da8f8cbd0314b6597bceeb3bffe7 100644 --- a/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/inc/ur_common.xacro +++ b/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/inc/ur_common.xacro @@ -70,6 +70,10 @@ <xacro:property name="elbow_joint_upper_limit" value="${sec_limits['elbow_joint']['max_position']}" scope="parent"/> <xacro:property name="elbow_joint_velocity_limit" value="${sec_limits['elbow_joint']['max_velocity']}" scope="parent"/> <xacro:property name="elbow_joint_effort_limit" value="${sec_limits['elbow_joint']['max_effort']}" scope="parent"/> + <xacro:property name="sensor_joint_lower_limit" value="${sec_limits['sensor_joint']['min_position']}" scope="parent"/> + <xacro:property name="sensor_joint_upper_limit" value="${sec_limits['sensor_joint']['max_position']}" scope="parent"/> + <xacro:property name="sensor_joint_velocity_limit" value="${sec_limits['sensor_joint']['max_velocity']}" scope="parent"/> + <xacro:property name="sensor_joint_effort_limit" value="${sec_limits['sensor_joint']['max_effort']}" scope="parent"/> <xacro:property name="wrist_1_lower_limit" value="${sec_limits['wrist_1_joint']['min_position']}" scope="parent"/> <xacro:property name="wrist_1_upper_limit" value="${sec_limits['wrist_1_joint']['max_position']}" scope="parent"/> <xacro:property name="wrist_1_velocity_limit" value="${sec_limits['wrist_1_joint']['max_velocity']}" scope="parent"/> diff --git a/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/inc/ur_transmissions.xacro b/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/inc/ur_transmissions.xacro index 18a86c355d7fc463b0d87696fce134bf1e298b1a..70e457030e5086b09b5d4fd709a3a6f12dccd782 100644 --- a/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/inc/ur_transmissions.xacro +++ b/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/inc/ur_transmissions.xacro @@ -28,16 +28,6 @@ </actuator> </transmission> - <transmission name="${prefix}elbow_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="${prefix}elbow_joint"> - <hardwareInterface>${hw_interface}</hardwareInterface> - </joint> - <actuator name="${prefix}elbow_motor"> - <mechanicalReduction>1</mechanicalReduction> - </actuator> - </transmission> - <transmission name="${prefix}wrist_1_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${prefix}wrist_1_joint"> diff --git a/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/ur.ros2_control.xacro b/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/ur.ros2_control.xacro index e37b5f898e6e398924b3f4b3f507995bf42b5883..c76d8b5f335ed1281be517a1b6d7b58898095894 100644 --- a/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/ur.ros2_control.xacro +++ b/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/ur.ros2_control.xacro @@ -7,7 +7,7 @@ sim_gazebo:=false sim_ignition:=false headless_mode:=false - initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} + initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,sensor_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} use_tool_communication:=false script_filename output_recipe_filename input_recipe_filename tf_prefix @@ -96,6 +96,16 @@ <state_interface name="velocity"/> <state_interface name="effort"/> </joint> + <joint name="${tf_prefix}sensor_joint"> + <command_interface name="position"/> + <command_interface name="velocity"/> + <state_interface name="position"> + <!-- initial position for the FakeSystem and simulation --> + <param name="initial_value">${initial_positions['sensor_joint']}</param> + </state_interface> + <state_interface name="velocity"/> + <state_interface name="effort"/> + </joint> <joint name="${tf_prefix}wrist_1_joint"> <command_interface name="position"/> <command_interface name="velocity"/> diff --git a/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/ur_macro.xacro b/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/ur_macro.xacro index 061881a05c46c774f07457cb92e36e6a26034751..f3d1cfd427b5f36f0767e3165d8533e83df3103f 100644 --- a/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/ur_macro.xacro +++ b/workspaces/COLCON_WS/install/ur_description/share/ur_description/urdf/ur_macro.xacro @@ -72,7 +72,7 @@ sim_gazebo:=false sim_ignition:=false headless_mode:=false - initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} + initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,sensor_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} use_tool_communication:=false tool_voltage:=0 tool_parity:=0 diff --git a/workspaces/COLCON_WS/log/latest_build b/workspaces/COLCON_WS/log/latest_build index e7d6befd65f0e02f918c038bc9b3eeed6f758f8e..60b5d8923f5f23e87f6fdcc4578b76caa0b43686 120000 --- a/workspaces/COLCON_WS/log/latest_build +++ b/workspaces/COLCON_WS/log/latest_build @@ -1 +1 @@ -build_2025-01-23_13-19-43 \ No newline at end of file +build_2025-01-23_15-31-34 \ No newline at end of file diff --git a/workspaces/COLCON_WS/src/ur_description/config/initial_positions.yaml b/workspaces/COLCON_WS/src/ur_description/config/initial_positions.yaml index f74bbbd9c2eafacaa7a638fb963766611a4b2135..343a1821fd45f45252bd11844ddd02c1ca6f0b2b 100644 --- a/workspaces/COLCON_WS/src/ur_description/config/initial_positions.yaml +++ b/workspaces/COLCON_WS/src/ur_description/config/initial_positions.yaml @@ -1,6 +1,7 @@ shoulder_pan_joint: 0.0 shoulder_lift_joint: -1.57 elbow_joint: 0.0 +sensor_joint: 0.0 wrist_1_joint: -1.57 wrist_2_joint: 0.0 wrist_3_joint: 0.0 diff --git a/workspaces/COLCON_WS/src/ur_description/config/ur10e/default_kinematics.yaml b/workspaces/COLCON_WS/src/ur_description/config/ur10e/default_kinematics.yaml index 3054ec13ec7e955e333cffac74dd9c6afba64aaf..f7da8171f7d844cf763317a37967eca353b78d7d 100644 --- a/workspaces/COLCON_WS/src/ur_description/config/ur10e/default_kinematics.yaml +++ b/workspaces/COLCON_WS/src/ur_description/config/ur10e/default_kinematics.yaml @@ -22,8 +22,8 @@ kinematics: yaw: 0 sensor: x: -0.30635 - y: 0 - z: 0 + y: 0.0 + z: 0.02 roll: 0 pitch: 0 yaw: 0 diff --git a/workspaces/COLCON_WS/src/ur_description/config/ur10e/joint_limits.yaml b/workspaces/COLCON_WS/src/ur_description/config/ur10e/joint_limits.yaml index 44be1f4a512c3b6a3ccb4e17022e24dbd4647cfb..fc75bc8a7d114730c8db9cad4950564df409f99f 100644 --- a/workspaces/COLCON_WS/src/ur_description/config/ur10e/joint_limits.yaml +++ b/workspaces/COLCON_WS/src/ur_description/config/ur10e/joint_limits.yaml @@ -48,6 +48,16 @@ joint_limits: max_position: !degrees 180.0 max_velocity: !degrees 180.0 min_position: !degrees -180.0 + sensor_joint: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 0.0 + max_position: !degrees 0.0 + max_velocity: !degrees 0.0 + min_position: !degrees 0.0 wrist_1_joint: # acceleration limits are not publicly available has_acceleration_limits: false diff --git a/workspaces/COLCON_WS/src/ur_description/config/ur10e/physical_parameters.yaml b/workspaces/COLCON_WS/src/ur_description/config/ur10e/physical_parameters.yaml index 702527a213422bf6cfb57fbe57b1b2b400ceffec..a099e953668d0037c486474f8e99e3b9f98130bc 100644 --- a/workspaces/COLCON_WS/src/ur_description/config/ur10e/physical_parameters.yaml +++ b/workspaces/COLCON_WS/src/ur_description/config/ur10e/physical_parameters.yaml @@ -3,7 +3,7 @@ offsets: shoulder_offset: 0.1762 # measured from model elbow_offset: 0.0393 # measured from model - sensor_offset: 0.02 # measured from model + sensor_offset: 0.00 # measured from model inertia_parameters: base_mass: 4.0 # This mass might be incorrect diff --git a/workspaces/COLCON_WS/src/ur_description/meshes/ur10e/collision/vl53l7cx.stl b/workspaces/COLCON_WS/src/ur_description/meshes/ur10e/collision/vl53l7cx.stl index fdd48bab0718d007f0605c2db77e739fab8f00d3..bf40d83b97c8d9fe6d732ee3018a793ab4a66488 100644 Binary files a/workspaces/COLCON_WS/src/ur_description/meshes/ur10e/collision/vl53l7cx.stl and b/workspaces/COLCON_WS/src/ur_description/meshes/ur10e/collision/vl53l7cx.stl differ diff --git a/workspaces/COLCON_WS/src/ur_description/urdf/inc/ur_common.xacro b/workspaces/COLCON_WS/src/ur_description/urdf/inc/ur_common.xacro index a1d3d902d2f74c810da78394a3bb330a3f6827dd..68594ef81f92da8f8cbd0314b6597bceeb3bffe7 100644 --- a/workspaces/COLCON_WS/src/ur_description/urdf/inc/ur_common.xacro +++ b/workspaces/COLCON_WS/src/ur_description/urdf/inc/ur_common.xacro @@ -70,6 +70,10 @@ <xacro:property name="elbow_joint_upper_limit" value="${sec_limits['elbow_joint']['max_position']}" scope="parent"/> <xacro:property name="elbow_joint_velocity_limit" value="${sec_limits['elbow_joint']['max_velocity']}" scope="parent"/> <xacro:property name="elbow_joint_effort_limit" value="${sec_limits['elbow_joint']['max_effort']}" scope="parent"/> + <xacro:property name="sensor_joint_lower_limit" value="${sec_limits['sensor_joint']['min_position']}" scope="parent"/> + <xacro:property name="sensor_joint_upper_limit" value="${sec_limits['sensor_joint']['max_position']}" scope="parent"/> + <xacro:property name="sensor_joint_velocity_limit" value="${sec_limits['sensor_joint']['max_velocity']}" scope="parent"/> + <xacro:property name="sensor_joint_effort_limit" value="${sec_limits['sensor_joint']['max_effort']}" scope="parent"/> <xacro:property name="wrist_1_lower_limit" value="${sec_limits['wrist_1_joint']['min_position']}" scope="parent"/> <xacro:property name="wrist_1_upper_limit" value="${sec_limits['wrist_1_joint']['max_position']}" scope="parent"/> <xacro:property name="wrist_1_velocity_limit" value="${sec_limits['wrist_1_joint']['max_velocity']}" scope="parent"/> diff --git a/workspaces/COLCON_WS/src/ur_description/urdf/inc/ur_transmissions.xacro b/workspaces/COLCON_WS/src/ur_description/urdf/inc/ur_transmissions.xacro index 18a86c355d7fc463b0d87696fce134bf1e298b1a..70e457030e5086b09b5d4fd709a3a6f12dccd782 100644 --- a/workspaces/COLCON_WS/src/ur_description/urdf/inc/ur_transmissions.xacro +++ b/workspaces/COLCON_WS/src/ur_description/urdf/inc/ur_transmissions.xacro @@ -28,16 +28,6 @@ </actuator> </transmission> - <transmission name="${prefix}elbow_trans"> - <type>transmission_interface/SimpleTransmission</type> - <joint name="${prefix}elbow_joint"> - <hardwareInterface>${hw_interface}</hardwareInterface> - </joint> - <actuator name="${prefix}elbow_motor"> - <mechanicalReduction>1</mechanicalReduction> - </actuator> - </transmission> - <transmission name="${prefix}wrist_1_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${prefix}wrist_1_joint"> diff --git a/workspaces/COLCON_WS/src/ur_description/urdf/ur.ros2_control.xacro b/workspaces/COLCON_WS/src/ur_description/urdf/ur.ros2_control.xacro index e37b5f898e6e398924b3f4b3f507995bf42b5883..c76d8b5f335ed1281be517a1b6d7b58898095894 100644 --- a/workspaces/COLCON_WS/src/ur_description/urdf/ur.ros2_control.xacro +++ b/workspaces/COLCON_WS/src/ur_description/urdf/ur.ros2_control.xacro @@ -7,7 +7,7 @@ sim_gazebo:=false sim_ignition:=false headless_mode:=false - initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} + initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,sensor_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} use_tool_communication:=false script_filename output_recipe_filename input_recipe_filename tf_prefix @@ -96,6 +96,16 @@ <state_interface name="velocity"/> <state_interface name="effort"/> </joint> + <joint name="${tf_prefix}sensor_joint"> + <command_interface name="position"/> + <command_interface name="velocity"/> + <state_interface name="position"> + <!-- initial position for the FakeSystem and simulation --> + <param name="initial_value">${initial_positions['sensor_joint']}</param> + </state_interface> + <state_interface name="velocity"/> + <state_interface name="effort"/> + </joint> <joint name="${tf_prefix}wrist_1_joint"> <command_interface name="position"/> <command_interface name="velocity"/> diff --git a/workspaces/COLCON_WS/src/ur_description/urdf/ur_macro.xacro b/workspaces/COLCON_WS/src/ur_description/urdf/ur_macro.xacro index 061881a05c46c774f07457cb92e36e6a26034751..f3d1cfd427b5f36f0767e3165d8533e83df3103f 100644 --- a/workspaces/COLCON_WS/src/ur_description/urdf/ur_macro.xacro +++ b/workspaces/COLCON_WS/src/ur_description/urdf/ur_macro.xacro @@ -72,7 +72,7 @@ sim_gazebo:=false sim_ignition:=false headless_mode:=false - initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} + initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,sensor_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} use_tool_communication:=false tool_voltage:=0 tool_parity:=0