mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-02-11 09:20:40 +00:00
fix: remove spaces from link names to support Jammy
Viz doesn't work when the links have spaces in their names on Jammy ._.
This commit is contained in:
@@ -360,7 +360,7 @@ class SerialRelay(Node):
|
|||||||
self.joint_state.header.stamp = self.get_clock().now().to_msg()
|
self.joint_state.header.stamp = self.get_clock().now().to_msg()
|
||||||
self.joint_state_pub.publish(self.joint_state)
|
self.joint_state_pub.publish(self.joint_state)
|
||||||
|
|
||||||
self.odom_trans.header.stamp = self.get_clock().now().to_msg()
|
# self.odom_trans.header.stamp = self.get_clock().now().to_msg()
|
||||||
self.tf_broadcaster.sendTransform(self.odom_trans)
|
self.tf_broadcaster.sendTransform(self.odom_trans)
|
||||||
else:
|
else:
|
||||||
self.get_logger().info("Invalid angle feedback input format")
|
self.get_logger().info("Invalid angle feedback input format")
|
||||||
|
|||||||
@@ -45,7 +45,7 @@
|
|||||||
<origin xyz="-0.175 0 0" rpy="0 0 0" />
|
<origin xyz="-0.175 0 0" rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<!-- <cylinder radius="0.15" length="0.059" /> -->
|
<!-- <cylinder radius="0.15" length="0.059" /> -->
|
||||||
<mesh filename="package://arm_pkg/urdf/Axis 0 Plate.STL" scale="1 1 1"/>
|
<mesh filename="package://arm_pkg/urdf/Axis_0_Plate.STL" scale="1 1 1"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="Axis_0-material">
|
<material name="Axis_0-material">
|
||||||
<color rgba="0.3515325994898463 0.4735314961384573 0.9301108583738498 1" />
|
<color rgba="0.3515325994898463 0.4735314961384573 0.9301108583738498 1" />
|
||||||
|
|||||||
@@ -19,8 +19,8 @@
|
|||||||
<joint name="Wrist-EF_Roll_Joint"/>
|
<joint name="Wrist-EF_Roll_Joint"/>
|
||||||
</group>
|
</group>
|
||||||
<group name="Hand">
|
<group name="Hand">
|
||||||
<link name="EF Gripper Left"/>
|
<link name="EF_Gripper_Left"/>
|
||||||
<link name="EF Gripper Right"/>
|
<link name="EF_Gripper_Right"/>
|
||||||
</group>
|
</group>
|
||||||
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
|
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
|
||||||
<group_state name="Zero Position" group="astra_arm">
|
<group_state name="Zero Position" group="astra_arm">
|
||||||
@@ -56,39 +56,39 @@
|
|||||||
<joint name="Gripper_Slider_Right" value="-0.0215"/>
|
<joint name="Gripper_Slider_Right" value="-0.0215"/>
|
||||||
</group_state>
|
</group_state>
|
||||||
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
|
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
|
||||||
<end_effector name="Hand" parent_link="End Effector" group="Hand"/>
|
<end_effector name="Hand" parent_link="End_Effector" group="Hand"/>
|
||||||
<!--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="virtual_joint" type="fixed" parent_frame="world" child_link="base_link"/>
|
<virtual_joint name="virtual_joint" 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="Axis 0 Plate" link2="Axis 1 Segment" reason="Adjacent"/>
|
<disable_collisions link1="Axis_0_Plate" link2="Axis_1_Segment" reason="Adjacent"/>
|
||||||
<disable_collisions link1="Axis 0 Plate" link2="Axis 2 Segment" reason="Never"/>
|
<disable_collisions link1="Axis_0_Plate" link2="Axis_2_Segment" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 0 Plate" link2="Diff Carrier" reason="Never"/>
|
<disable_collisions link1="Axis_0_Plate" link2="Diff_Carrier" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 0 Plate" link2="End Effector" reason="Never"/>
|
<disable_collisions link1="Axis_0_Plate" link2="End_Effector" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 0 Plate" link2="Wrist" reason="Never"/>
|
<disable_collisions link1="Axis_0_Plate" link2="Wrist" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 0 Plate" link2="base_link" reason="Adjacent"/>
|
<disable_collisions link1="Axis_0_Plate" link2="base_link" reason="Adjacent"/>
|
||||||
<disable_collisions link1="Axis 1 Segment" link2="Axis 2 Segment" reason="Adjacent"/>
|
<disable_collisions link1="Axis_1_Segment" link2="Axis_2_Segment" reason="Adjacent"/>
|
||||||
<disable_collisions link1="Axis 1 Segment" link2="Diff Carrier" reason="Never"/>
|
<disable_collisions link1="Axis_1_Segment" link2="Diff_Carrier" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 1 Segment" link2="EF Gripper Left" reason="Never"/>
|
<disable_collisions link1="Axis_1_Segment" link2="EF_Gripper_Left" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 1 Segment" link2="EF Gripper Right" reason="Never"/>
|
<disable_collisions link1="Axis_1_Segment" link2="EF_Gripper_Right" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 1 Segment" link2="End Effector" reason="Never"/>
|
<disable_collisions link1="Axis_1_Segment" link2="End_Effector" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 1 Segment" link2="Wrist" reason="Never"/>
|
<disable_collisions link1="Axis_1_Segment" link2="Wrist" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 1 Segment" link2="base_link" reason="Never"/>
|
<disable_collisions link1="Axis_1_Segment" link2="base_link" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 2 Segment" link2="Diff Carrier" reason="Never"/>
|
<disable_collisions link1="Axis_2_Segment" link2="Diff_Carrier" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 2 Segment" link2="EF Gripper Left" reason="Never"/>
|
<disable_collisions link1="Axis_2_Segment" link2="EF_Gripper_Left" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 2 Segment" link2="EF Gripper Right" reason="Never"/>
|
<disable_collisions link1="Axis_2_Segment" link2="EF_Gripper_Right" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 2 Segment" link2="End Effector" reason="Never"/>
|
<disable_collisions link1="Axis_2_Segment" link2="End_Effector" reason="Never"/>
|
||||||
<disable_collisions link1="Axis 2 Segment" link2="Wrist" reason="Adjacent"/>
|
<disable_collisions link1="Axis_2_Segment" link2="Wrist" reason="Adjacent"/>
|
||||||
<disable_collisions link1="Axis 2 Segment" link2="base_link" reason="Never"/>
|
<disable_collisions link1="Axis_2_Segment" link2="base_link" reason="Never"/>
|
||||||
<disable_collisions link1="Diff Carrier" link2="EF Gripper Left" reason="Never"/>
|
<disable_collisions link1="Diff_Carrier" link2="EF_Gripper_Left" reason="Never"/>
|
||||||
<disable_collisions link1="Diff Carrier" link2="EF Gripper Right" reason="Never"/>
|
<disable_collisions link1="Diff_Carrier" link2="EF_Gripper_Right" reason="Never"/>
|
||||||
<disable_collisions link1="Diff Carrier" link2="End Effector" reason="Adjacent"/>
|
<disable_collisions link1="Diff_Carrier" link2="End_Effector" reason="Adjacent"/>
|
||||||
<disable_collisions link1="Diff Carrier" link2="Wrist" reason="Adjacent"/>
|
<disable_collisions link1="Diff_Carrier" link2="Wrist" reason="Adjacent"/>
|
||||||
<disable_collisions link1="Diff Carrier" link2="base_link" reason="Never"/>
|
<disable_collisions link1="Diff_Carrier" link2="base_link" reason="Never"/>
|
||||||
<disable_collisions link1="EF Gripper Left" link2="End Effector" reason="Adjacent"/>
|
<disable_collisions link1="EF_Gripper_Left" link2="End_Effector" reason="Adjacent"/>
|
||||||
<disable_collisions link1="EF Gripper Left" link2="Wrist" reason="Never"/>
|
<disable_collisions link1="EF_Gripper_Left" link2="Wrist" reason="Never"/>
|
||||||
<disable_collisions link1="EF Gripper Right" link2="End Effector" reason="Adjacent"/>
|
<disable_collisions link1="EF_Gripper_Right" link2="End_Effector" reason="Adjacent"/>
|
||||||
<disable_collisions link1="EF Gripper Right" link2="Wrist" reason="Never"/>
|
<disable_collisions link1="EF_Gripper_Right" link2="Wrist" reason="Never"/>
|
||||||
<disable_collisions link1="End Effector" link2="Wrist" reason="Never"/>
|
<disable_collisions link1="End_Effector" link2="Wrist" reason="Never"/>
|
||||||
<disable_collisions link1="End Effector" link2="base_link" reason="Never"/>
|
<disable_collisions link1="End_Effector" link2="base_link" reason="Never"/>
|
||||||
<disable_collisions link1="Wrist" link2="base_link" reason="Never"/>
|
<disable_collisions link1="Wrist" link2="base_link" reason="Never"/>
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
@@ -10,22 +10,22 @@ default_acceleration_scaling_factor: 1
|
|||||||
joint_limits:
|
joint_limits:
|
||||||
Axis_0_Joint:
|
Axis_0_Joint:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 3.141593
|
max_velocity: 31.41593
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 0.5
|
max_acceleration: 0.5
|
||||||
Axis_1_Joint:
|
Axis_1_Joint:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 3.141593
|
max_velocity: 31.41593
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 0.5
|
max_acceleration: 0.5
|
||||||
Axis_2_Joint:
|
Axis_2_Joint:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 3.141593
|
max_velocity: 31.41593
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 0.5
|
max_acceleration: 0.5
|
||||||
Axis_3_Joint:
|
Axis_3_Joint:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 3.141593
|
max_velocity: 31.41593
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 0.5
|
max_acceleration: 0.5
|
||||||
Gripper_Slider_Left:
|
Gripper_Slider_Left:
|
||||||
@@ -40,11 +40,11 @@ joint_limits:
|
|||||||
max_acceleration: 0.5
|
max_acceleration: 0.5
|
||||||
Wrist_Differential_Joint:
|
Wrist_Differential_Joint:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 3.141593
|
max_velocity: 31.41593
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 0.5
|
max_acceleration: 0.5
|
||||||
Wrist-EF_Roll_Joint:
|
Wrist-EF_Roll_Joint:
|
||||||
has_velocity_limits: true
|
has_velocity_limits: true
|
||||||
max_velocity: 3.141593
|
max_velocity: 31.41593
|
||||||
has_acceleration_limits: true
|
has_acceleration_limits: true
|
||||||
max_acceleration: 0.5
|
max_acceleration: 0.5
|
||||||
@@ -1,10 +1,10 @@
|
|||||||
Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
|
Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
|
||||||
base_link,0.026661,-0.017083,-0.072681,0,0,0,1.344,0.0071986,-1.8109E-06,-4.371E-06,0.0087125,1.3418E-07,0.015884,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/base_link.STL,0.89804,0.91765,0.92941,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/base_link.STL,,Turret Assembly-1/Base Plate OLD-2;Turret Assembly-1/Magnet Ring-1;Turret Assembly-1/Bearing Stack Pinch Ring-1;Turret Assembly-1/Ring Gear-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
|
base_link,0.026661,-0.017083,-0.072681,0,0,0,1.344,0.0071986,-1.8109E-06,-4.371E-06,0.0087125,1.3418E-07,0.015884,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/base_link.STL,0.89804,0.91765,0.92941,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/base_link.STL,,Turret Assembly-1/Base Plate OLD-2;Turret Assembly-1/Magnet Ring-1;Turret Assembly-1/Bearing Stack Pinch Ring-1;Turret Assembly-1/Ring Gear-1,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,,
|
||||||
Axis 0 Plate,0.025635,0.047115,0.021109,0,0,0,2.045,0.0097744,2.0744E-07,0.00060246,0.012437,-2.2545E-05,0.00611,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis 0 Plate.STL,0.89804,0.91765,0.92941,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis 0 Plate.STL,,Turret Assembly-1/Pinion Gear Mounting Plate-1;Turret Assembly-1/Motor Adjustment Plate-1;Turret Assembly-1/17HS19-1684S-PG14.step-1;Turret Assembly-1/Spur Gear Retainer-1;Turret Assembly-1/1088A31_Inside-Corner Reinforcing Bracket-1;Turret Assembly-1/1088A31_Inside-Corner Reinforcing Bracket-2;Turret Assembly-1/1088A31_Inside-Corner Reinforcing Bracket-4;Turret Assembly-1/Electrical Box Assembly-1/Clamshell-1;Turret Assembly-1/Electrical Box Assembly-1/Sheet Base-2;Turret Assembly-1/Electrical Box Assembly-1/Cam Slot-2;Turret Assembly-1/Electrical Box Assembly-1/Slot guide-2;Turret Assembly-1/Electrical Box Assembly-1/Slot guide-1;Turret Assembly-1/Electrical Box Assembly-1/Cam Slot-1;Axis 1 Full Assembly-1/Axis 1 Outer Frame-1/ASTRA-01-00-005-2;Axis 1 Full Assembly-1/Axis 1 Outer Frame-1/ASTRA-01-00-005-1;Turret Assembly-1/1088A31_Inside-Corner Reinforcing Bracket-3,Origin_Axis_0_Joint,Axis1,Axis_0_Joint,revolute,0.018772,-0.020734,-0.04971,1.5708,0,3.1115,base_link,0,-1,0,0,0,0,0,,,,,,,,
|
Axis_0_Plate,0.025635,0.047115,0.021109,0,0,0,2.045,0.0097744,2.0744E-07,0.00060246,0.012437,-2.2545E-05,0.00611,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis_0_Plate.STL,0.89804,0.91765,0.92941,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis_0_Plate.STL,,Turret Assembly-1/Pinion Gear Mounting Plate-1;Turret Assembly-1/Motor Adjustment Plate-1;Turret Assembly-1/17HS19-1684S-PG14.step-1;Turret Assembly-1/Spur Gear Retainer-1;Turret Assembly-1/1088A31_Inside-Corner Reinforcing Bracket-1;Turret Assembly-1/1088A31_Inside-Corner Reinforcing Bracket-2;Turret Assembly-1/1088A31_Inside-Corner Reinforcing Bracket-4;Turret Assembly-1/Electrical Box Assembly-1/Clamshell-1;Turret Assembly-1/Electrical Box Assembly-1/Sheet Base-2;Turret Assembly-1/Electrical Box Assembly-1/Cam Slot-2;Turret Assembly-1/Electrical Box Assembly-1/Slot guide-2;Turret Assembly-1/Electrical Box Assembly-1/Slot guide-1;Turret Assembly-1/Electrical Box Assembly-1/Cam Slot-1;Axis 1 Full Assembly-1/Axis 1 Outer Frame-1/ASTRA-01-00-005-2;Axis 1 Full Assembly-1/Axis 1 Outer Frame-1/ASTRA-01-00-005-1;Turret Assembly-1/1088A31_Inside-Corner Reinforcing Bracket-3,Origin_Axis_0_Joint,Axis1,Axis_0_Joint,revolute,0.018772,-0.020734,-0.04971,1.5708,0,3.1115,base_link,0,-1,0,0,0,0,0,,,,,,,,
|
||||||
Axis 1 Segment,0.317731812584795,0.0226837932394467,-2.94234579792906E-05,0,0,0,2.10107115350287,0.00185099460285527,-6.85595125576909E-06,-2.99093842113918E-07,0.00462248035875048,2.91093713403385E-07,0.00297641069201651,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis 1 Segment.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis 1 Segment.STL,,Axis 1 Full Assembly-1/Axis 1 Outer Ring-1/ASTRA-01-01-002-1;Axis 1 Full Assembly-1/Axis 1 Outer Ring-1/ASTRA-01-01-001-1;Axis 1 Full Assembly-1/Axis 1 Outer Ring-1/ASTRA-01-01-002-2;Axis 0-1 Forearm-1/ASTRA-02-00-009-1;Axis 0-1 Forearm-1/2024 Axis 0-1 CF Tube-1;Axis 0-1 Forearm-1/ASTRA-02-00-009-2;ASTRA-02-00-000-2/ASTRA-02-00-006-1;ASTRA-02-00-000-2/ASTRA-02-00-007-2;ASTRA-02-00-000-2/ASTRA-02-00-007-1;ASTRA-02-00-000-2/Encoder Assembly 20 30-1/Encoder Mount 20 30-1;ASTRA-02-00-000-2/Encoder Assembly 20 30-1/Encoder Board V2-1;ASTRA-02-00-000-2/Encoder Assembly 20 30-1/Encoder Board Top 2030-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox Output-1/REV-41-1604.STEP-1/REV-41-1604-1.STEP-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/Cy NEO 550 Adapter Plate Axis 2-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Motor Gearbox Mount-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-2;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-3;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox Output-1/REV-41-1604.STEP-1/REV-41-1604-2.STEP-1,Origin_Axis_1_Joint,Axis2,Axis_1_Joint,revolute,-0.0271654135185528,0.0927245490180083,0.00384109909109076,-3.14159265358977,-0.00524713054608625,1.5707963267949,Axis 0 Plate,0,-1,0,0,0,0,0,,,,,,,,
|
Axis_1_Segment,0.317731812584795,0.0226837932394467,-2.94234579792906E-05,0,0,0,2.10107115350287,0.00185099460285527,-6.85595125576909E-06,-2.99093842113918E-07,0.00462248035875048,2.91093713403385E-07,0.00297641069201651,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis_1_Segment.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis_1_Segment.STL,,Axis 1 Full Assembly-1/Axis 1 Outer Ring-1/ASTRA-01-01-002-1;Axis 1 Full Assembly-1/Axis 1 Outer Ring-1/ASTRA-01-01-001-1;Axis 1 Full Assembly-1/Axis 1 Outer Ring-1/ASTRA-01-01-002-2;Axis 0-1 Forearm-1/ASTRA-02-00-009-1;Axis 0-1 Forearm-1/2024 Axis 0-1 CF Tube-1;Axis 0-1 Forearm-1/ASTRA-02-00-009-2;ASTRA-02-00-000-2/ASTRA-02-00-006-1;ASTRA-02-00-000-2/ASTRA-02-00-007-2;ASTRA-02-00-000-2/ASTRA-02-00-007-1;ASTRA-02-00-000-2/Encoder Assembly 20 30-1/Encoder Mount 20 30-1;ASTRA-02-00-000-2/Encoder Assembly 20 30-1/Encoder Board V2-1;ASTRA-02-00-000-2/Encoder Assembly 20 30-1/Encoder Board Top 2030-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox Output-1/REV-41-1604.STEP-1/REV-41-1604-1.STEP-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/Cy NEO 550 Adapter Plate Axis 2-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Motor Gearbox Mount-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-2;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-3;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550-1;ASTRA-02-00-000-2/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox Output-1/REV-41-1604.STEP-1/REV-41-1604-2.STEP-1,Origin_Axis_1_Joint,Axis2,Axis_1_Joint,revolute,-0.0271654135185528,0.0927245490180083,0.00384109909109076,-3.14159265358977,-0.00524713054608625,1.5707963267949,Axis_0_Plate,0,-1,0,0,0,0,0,,,,,,,,
|
||||||
Axis 2 Segment,0.179701426719665,-0.0176131583689303,5.71147464441535E-05,0,0,0,3.13644489009951,0.00172062005671382,1.49995165753112E-05,3.0146547850231E-07,0.00419573957161135,2.86281305896603E-07,0.00280821030835127,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis 2 Segment.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis 2 Segment.STL,,ASTRA-02-00-000-2/ASTRA-02-00-003-1;ASTRA-02-00-000-2/ASTRA-02-00-004-1;ASTRA-02-00-000-2/ASTRA-02-00-003-2;Axis 1-2 Forearm-1/ASTRA-02-00-009-1;Axis 1-2 Forearm-1/2024 Axis 1-2 CF Tube-1;ASTRA-02-00-000-2/Encoder Assembly 20 30-1/Encoder Board Arm 2030-1;Axis 1-2 Forearm-1/ASTRA-02-00-009-2;ASTRA-03-00-000-1/ASTRA-02-00-006-1;ASTRA-03-00-000-1/ASTRA-02-00-007-1;ASTRA-03-00-000-1/ASTRA-02-00-007-2;ASTRA-03-00-000-1/Encoder Assembly 20 30-1/Encoder Mount 20 30-1;ASTRA-03-00-000-1/Encoder Assembly 20 30-1/Encoder Board V2-1;ASTRA-03-00-000-1/Encoder Assembly 20 30-1/Encoder Board Top 2030-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/Cy NEO 550 Adapter Plate Axis 2-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox Output-1/REV-41-1604.STEP-1/REV-41-1604-2.STEP-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox Output-1/REV-41-1604.STEP-1/REV-41-1604-1.STEP-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-3;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-2;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Motor Gearbox Mount-1,Origin_Axis_2_Joint,Axis3,Axis_2_Joint,revolute,0.470027000000004,0.0126999999999999,0,3.14159265358979,0.000449358059257729,0,Axis 1 Segment,0,-1,0,0,0,0,0,,,,,,,,
|
Axis_2_Segment,0.179701426719665,-0.0176131583689303,5.71147464441535E-05,0,0,0,3.13644489009951,0.00172062005671382,1.49995165753112E-05,3.0146547850231E-07,0.00419573957161135,2.86281305896603E-07,0.00280821030835127,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis_2_Segment.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Axis_2_Segment.STL,,ASTRA-02-00-000-2/ASTRA-02-00-003-1;ASTRA-02-00-000-2/ASTRA-02-00-004-1;ASTRA-02-00-000-2/ASTRA-02-00-003-2;Axis 1-2 Forearm-1/ASTRA-02-00-009-1;Axis 1-2 Forearm-1/2024 Axis 1-2 CF Tube-1;ASTRA-02-00-000-2/Encoder Assembly 20 30-1/Encoder Board Arm 2030-1;Axis 1-2 Forearm-1/ASTRA-02-00-009-2;ASTRA-03-00-000-1/ASTRA-02-00-006-1;ASTRA-03-00-000-1/ASTRA-02-00-007-1;ASTRA-03-00-000-1/ASTRA-02-00-007-2;ASTRA-03-00-000-1/Encoder Assembly 20 30-1/Encoder Mount 20 30-1;ASTRA-03-00-000-1/Encoder Assembly 20 30-1/Encoder Board V2-1;ASTRA-03-00-000-1/Encoder Assembly 20 30-1/Encoder Board Top 2030-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/Cy NEO 550 Adapter Plate Axis 2-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox Output-1/REV-41-1604.STEP-1/REV-41-1604-2.STEP-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox Output-1/REV-41-1604.STEP-1/REV-41-1604-1.STEP-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-3;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-2;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Gearbox 5-1 Stage-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550-1;ASTRA-03-00-000-1/CY NEO 550 Motor & Gearbox Axis 2-1/CY NEO 550 Motor Gearbox Mount-1,Origin_Axis_2_Joint,Axis3,Axis_2_Joint,revolute,0.470027000000004,0.0126999999999999,0,3.14159265358979,0.000449358059257729,0,Axis_1_Segment,0,-1,0,0,0,0,0,,,,,,,,
|
||||||
Wrist,0.0258890113931529,-0.0205223442970055,6.01641698143966E-05,0,0,0,1.95105877103309,0.00117490634970832,8.14355696873965E-06,2.37060433355634E-09,0.0025492938141431,-4.81227026285992E-09,0.00159235737231991,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Wrist.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Wrist.STL,,ASTRA-03-00-000-1/ASTRA-02-00-003-1;ASTRA-03-00-000-1/ASTRA-03-00-004-1;ASTRA-03-00-000-1/ASTRA-02-00-003-2;ASTRA-03-00-000-1/Encoder Assembly 20 30-1/Encoder Board Arm 2030-1;Wrist Interface-1;FULLWristAssembly-1/Servobox-1/ServoBoxTruss-1;FULLWristAssembly-1/Servobox-1/LSS-Public-2/LSS-Public.STEP-1/LSS - Casing_LSS Generic.STEP-1;FULLWristAssembly-1/Servobox-1/LSS-Public-1/LSS-Public.STEP-1/LSS - Casing_LSS Generic.STEP-1;FULLWristAssembly-1/Servobox-1/ServoBoxBottomPlate-1;FULLWristAssembly-1/Servobox-1/GearBoxMountingPlate-1;FULLWristAssembly-1/Servobox-1/ServoBoxTruss-2;FULLWristAssembly-1/Servobox-1/ServoMountingWall-1;FULLWristAssembly-1/Servobox-1/ServoMountingWall-2;FULLWristAssembly-1/Differential Gear box-1/ShaftSupport-2;FULLWristAssembly-1/Differential Gear box-1/ShaftSupport-1;FULLWristAssembly-1/Servobox-1/Modified 266N381 For interface-1;FULLWristAssembly-1/Differential Gear box-1/2664N381_Metal Gear - 20 Degree Pressure Angle-3;FULLWristAssembly-1/TensionBar-1;FULLWristAssembly-1/Servobox-1/ServoHornAdapater-1;FULLWristAssembly-1/Servobox-1/ServoHornAdapater-2;FULLWristAssembly-1/Servobox-1/Modified 266N381 For interface-2;FULLWristAssembly-1/Differential Gear box-1/2664N381_Metal Gear - 20 Degree Pressure Angle-4;FULLWristAssembly-1/TensionBar-2,Origin_Axis_3_Joint,Axis4,Axis_3_Joint,revolute,0.393826999999998,0,0,0,-0.000409495780687665,0,Axis 2 Segment,0,-1,0,0,0,0,0,,,,,,,,
|
Wrist,0.0258890113931529,-0.0205223442970055,6.01641698143966E-05,0,0,0,1.95105877103309,0.00117490634970832,8.14355696873965E-06,2.37060433355634E-09,0.0025492938141431,-4.81227026285992E-09,0.00159235737231991,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Wrist.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Wrist.STL,,ASTRA-03-00-000-1/ASTRA-02-00-003-1;ASTRA-03-00-000-1/ASTRA-03-00-004-1;ASTRA-03-00-000-1/ASTRA-02-00-003-2;ASTRA-03-00-000-1/Encoder Assembly 20 30-1/Encoder Board Arm 2030-1;Wrist Interface-1;FULLWristAssembly-1/Servobox-1/ServoBoxTruss-1;FULLWristAssembly-1/Servobox-1/LSS-Public-2/LSS-Public.STEP-1/LSS - Casing_LSS Generic.STEP-1;FULLWristAssembly-1/Servobox-1/LSS-Public-1/LSS-Public.STEP-1/LSS - Casing_LSS Generic.STEP-1;FULLWristAssembly-1/Servobox-1/ServoBoxBottomPlate-1;FULLWristAssembly-1/Servobox-1/GearBoxMountingPlate-1;FULLWristAssembly-1/Servobox-1/ServoBoxTruss-2;FULLWristAssembly-1/Servobox-1/ServoMountingWall-1;FULLWristAssembly-1/Servobox-1/ServoMountingWall-2;FULLWristAssembly-1/Differential Gear box-1/ShaftSupport-2;FULLWristAssembly-1/Differential Gear box-1/ShaftSupport-1;FULLWristAssembly-1/Servobox-1/Modified 266N381 For interface-1;FULLWristAssembly-1/Differential Gear box-1/2664N381_Metal Gear - 20 Degree Pressure Angle-3;FULLWristAssembly-1/TensionBar-1;FULLWristAssembly-1/Servobox-1/ServoHornAdapater-1;FULLWristAssembly-1/Servobox-1/ServoHornAdapater-2;FULLWristAssembly-1/Servobox-1/Modified 266N381 For interface-2;FULLWristAssembly-1/Differential Gear box-1/2664N381_Metal Gear - 20 Degree Pressure Angle-4;FULLWristAssembly-1/TensionBar-2,Origin_Axis_3_Joint,Axis4,Axis_3_Joint,revolute,0.393826999999998,0,0,0,-0.000409495780687665,0,Axis_2_Segment,0,-1,0,0,0,0,0,,,,,,,,
|
||||||
Diff Carrier,-8.64620358677695E-06,-0.00516792807449162,-7.22608790769408E-07,0,0,0,0.0655351660884378,1.65846526943977E-05,3.62206129298215E-09,5.09422122565314E-10,4.25479683866677E-05,2.86164802173259E-10,3.87760449919773E-05,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Diff Carrier.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Diff Carrier.STL,,FULLWristAssembly-1/Differential Gear box-1/Endefector plate-2;FULLWristAssembly-1/Differential Gear box-1/2515N313_Metal Pinion-1;FULLWristAssembly-1/Differential Gear box-1/2515N314_Metal Bevel Gear-1;FULLWristAssembly-1/Differential Gear box-1/2515N313_Metal Pinion-2,Origin_Wrist_Differential_Joint,Axis5,Wrist_Differential_Joint,revolute,0.176692001200001,-0.00622300000004081,0,-3.05263944120951,1.57079631189374,1.65994236547327,Wrist,-1,0,0,0,0,0,0,,,,,,,,
|
Diff_Carrier,-8.64620358677695E-06,-0.00516792807449162,-7.22608790769408E-07,0,0,0,0.0655351660884378,1.65846526943977E-05,3.62206129298215E-09,5.09422122565314E-10,4.25479683866677E-05,2.86164802173259E-10,3.87760449919773E-05,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Diff_Carrier.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/Diff_Carrier.STL,,FULLWristAssembly-1/Differential Gear box-1/Endefector plate-2;FULLWristAssembly-1/Differential Gear box-1/2515N313_Metal Pinion-1;FULLWristAssembly-1/Differential Gear box-1/2515N314_Metal Bevel Gear-1;FULLWristAssembly-1/Differential Gear box-1/2515N313_Metal Pinion-2,Origin_Wrist_Differential_Joint,Axis5,Wrist_Differential_Joint,revolute,0.176692001200001,-0.00622300000004081,0,-3.05263944120951,1.57079631189374,1.65994236547327,Wrist,-1,0,0,0,0,0,0,,,,,,,,
|
||||||
End Effector,-0.00327558376591462,0.00327411156667146,-0.0553569354578649,0,0,0,0.397605677640027,0.000631368000075726,-1.01357929540856E-09,-3.06601632900158E-06,0.000105800099414061,2.32813748604228E-09,0.000592001119919064,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/End Effector.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/End Effector.STL,,Assembley-1/Copy End_Effector_Mount-1;Assembley-1/Real Shit - Pin-1;Assembley-1/copy End Effector Mount Center Block-1;Assembley-1/copy Real Shit - Middle Spacer Plate-1;Assembley-1/Copy Real Shit - Right Plate-1;Assembley-1/Copy Real Shit - Left Plate-1;Assembley-1/motor end deffector-1;Assembley-1/Motor adapter-2;Assembley-1/Copy Carbon Rod-1;Assembley-1/Copy Lead Screw-1;Assembley-1/Copy Carbon Rod-2,Origin_Wrist-EF_Roll_Joint,Axis6,Wrist-EF_Roll_Joint,continuous,0,0.01,0,-1.5708,-0.21566,-3.1416,Diff Carrier,0,0,1,,,,,,,,,,,,
|
End_Effector,-0.00327558376591462,0.00327411156667146,-0.0553569354578649,0,0,0,0.397605677640027,0.000631368000075726,-1.01357929540856E-09,-3.06601632900158E-06,0.000105800099414061,2.32813748604228E-09,0.000592001119919064,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/End_Effector.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/End_Effector.STL,,Assembley-1/Copy End_Effector_Mount-1;Assembley-1/Real Shit - Pin-1;Assembley-1/copy End_Effector Mount Center Block-1;Assembley-1/copy Real Shit - Middle Spacer Plate-1;Assembley-1/Copy Real Shit - Right Plate-1;Assembley-1/Copy Real Shit - Left Plate-1;Assembley-1/motor end deffector-1;Assembley-1/Motor adapter-2;Assembley-1/Copy Carbon Rod-1;Assembley-1/Copy Lead Screw-1;Assembley-1/Copy Carbon Rod-2,Origin_Wrist-EF_Roll_Joint,Axis6,Wrist-EF_Roll_Joint,continuous,0,0.01,0,-1.5708,-0.21566,-3.1416,Diff_Carrier,0,0,1,,,,,,,,,,,,
|
||||||
EF Gripper Right,3.60822483003176E-16,0.0395187564799554,-0.0785892929086096,0,0,0,0.0859306256217421,8.1015302646778E-05,2.5410988417629E-21,3.75123099070348E-19,8.51028632685389E-05,1.00631950096307E-08,5.50169350148622E-06,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/EF Gripper Right.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/EF Gripper Right.STL,,Assembley-1/Copy Left_Jaw_Bracket-3;Assembley-1/Gripper-2;Assembley-1/Copy Real Shit - Left Jaw Plate-2;Assembley-1/lead screw nut-2;Assembley-1/Copy Bushing Bearing - Bushing Bearing-1;Assembley-1/Copy Bushing Bearing - Bushing Bearing-4,Origin_Gripper_Slider_Right,Axis7,Gripper_Slider_Right,prismatic,0,0,-0.031677,0,0,3.1416,End Effector,0,1,0,0,0,0,0,,,,,,,,
|
EF_Gripper_Right,3.60822483003176E-16,0.0395187564799554,-0.0785892929086096,0,0,0,0.0859306256217421,8.1015302646778E-05,2.5410988417629E-21,3.75123099070348E-19,8.51028632685389E-05,1.00631950096307E-08,5.50169350148622E-06,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/EF_Gripper_Right.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/EF_Gripper_Right.STL,,Assembley-1/Copy Left_Jaw_Bracket-3;Assembley-1/Gripper-2;Assembley-1/Copy Real Shit - Left Jaw Plate-2;Assembley-1/lead screw nut-2;Assembley-1/Copy Bushing Bearing - Bushing Bearing-1;Assembley-1/Copy Bushing Bearing - Bushing Bearing-4,Origin_Gripper_Slider_Right,Axis7,Gripper_Slider_Right,prismatic,0,0,-0.031677,0,0,3.1416,End_Effector,0,1,0,0,0,0,0,,,,,,,,
|
||||||
EF Gripper Left,0.000260261090099842,0.0391877753208171,-0.0810862651363518,0,0,0,0.0813132558225319,7.92230074239095E-05,8.60239969339994E-10,-3.27617434511821E-07,8.29877943429396E-05,9.84609377733742E-09,4.98027032334885E-06,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/EF Gripper Left.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/EF Gripper Left.STL,,Assembley-1/Copy Left_Jaw_Bracket-1;Assembley-1/Copy Real Shit - Left Jaw Plate-1;Assembley-1/Gripper-1;Assembley-1/lead screw nut-1;Assembley-1/Copy Bushing Bearing - Bushing Bearing-2;Assembley-1/Copy Bushing Bearing - Bushing Bearing-3,Origin_Gripper_Slider_Left,Axis7,Gripper_Slider_Left,prismatic,0,0,-0.031677,0,0,0,End Effector,0,-1,0,0,0,0,0,,,,,,,,
|
EF_Gripper_Left,0.000260261090099842,0.0391877753208171,-0.0810862651363518,0,0,0,0.0813132558225319,7.92230074239095E-05,8.60239969339994E-10,-3.27617434511821E-07,8.29877943429396E-05,9.84609377733742E-09,4.98027032334885E-06,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/EF_Gripper_Left.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://URDF v2 - axes added/meshes/EF_Gripper_Left.STL,,Assembley-1/Copy Left_Jaw_Bracket-1;Assembley-1/Copy Real Shit - Left Jaw Plate-1;Assembley-1/Gripper-1;Assembley-1/lead screw nut-1;Assembley-1/Copy Bushing Bearing - Bushing Bearing-2;Assembley-1/Copy Bushing Bearing - Bushing Bearing-3,Origin_Gripper_Slider_Left,Axis7,Gripper_Slider_Left,prismatic,0,0,-0.031677,0,0,0,End_Effector,0,-1,0,0,0,0,0,,,,,,,,
|
||||||
|
|||||||
|
@@ -47,7 +47,7 @@
|
|||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
name="Axis 0 Plate">
|
name="Axis_0_Plate">
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin
|
<origin
|
||||||
xyz="0.025635 0.047115 0.021109"
|
xyz="0.025635 0.047115 0.021109"
|
||||||
@@ -68,7 +68,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/Axis 0 Plate.STL" />
|
filename="package://rover_urdf_pkg/meshes/Axis_0_Plate.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material
|
<material
|
||||||
name="">
|
name="">
|
||||||
@@ -82,7 +82,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/Axis 0 Plate.STL" />
|
filename="package://rover_urdf_pkg/meshes/Axis_0_Plate.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
@@ -96,18 +96,18 @@
|
|||||||
<parent
|
<parent
|
||||||
link="base_link" />
|
link="base_link" />
|
||||||
<child
|
<child
|
||||||
link="Axis 0 Plate" />
|
link="Axis_0_Plate" />
|
||||||
<axis
|
<axis
|
||||||
xyz="0 -1 0" />
|
xyz="0 -1 0" />
|
||||||
<limit
|
<limit
|
||||||
lower="-3.14"
|
lower="-3.14"
|
||||||
upper="3.14"
|
upper="3.14"
|
||||||
effort="0"
|
effort="0"
|
||||||
velocity="3.1415963" />
|
velocity="31.41593" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
name="Axis 1 Segment">
|
name="Axis_1_Segment">
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin
|
<origin
|
||||||
xyz="0.317731812584795 0.0226837932394467 -2.94234579792906E-05"
|
xyz="0.317731812584795 0.0226837932394467 -2.94234579792906E-05"
|
||||||
@@ -128,7 +128,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/Axis 1 Segment.STL" />
|
filename="package://rover_urdf_pkg/meshes/Axis_1_Segment.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material
|
<material
|
||||||
name="">
|
name="">
|
||||||
@@ -142,7 +142,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/Axis 1 Segment.STL" />
|
filename="package://rover_urdf_pkg/meshes/Axis_1_Segment.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
@@ -154,20 +154,20 @@
|
|||||||
xyz="-0.0271654135185528 0.0927245490180083 0.00384109909109076"
|
xyz="-0.0271654135185528 0.0927245490180083 0.00384109909109076"
|
||||||
rpy="-3.14159265358977 -0.00524713054608625 1.5707963267949" />
|
rpy="-3.14159265358977 -0.00524713054608625 1.5707963267949" />
|
||||||
<parent
|
<parent
|
||||||
link="Axis 0 Plate" />
|
link="Axis_0_Plate" />
|
||||||
<child
|
<child
|
||||||
link="Axis 1 Segment" />
|
link="Axis_1_Segment" />
|
||||||
<axis
|
<axis
|
||||||
xyz="0 -1 0" />
|
xyz="0 -1 0" />
|
||||||
<limit
|
<limit
|
||||||
lower="-1.05"
|
lower="-1.05"
|
||||||
upper="1.6"
|
upper="1.6"
|
||||||
effort="0"
|
effort="0"
|
||||||
velocity="3.1415963" />
|
velocity="31.41593" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
name="Axis 2 Segment">
|
name="Axis_2_Segment">
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin
|
<origin
|
||||||
xyz="0.179701426719665 -0.0176131583689303 5.71147464441535E-05"
|
xyz="0.179701426719665 -0.0176131583689303 5.71147464441535E-05"
|
||||||
@@ -188,7 +188,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/Axis 2 Segment.STL" />
|
filename="package://rover_urdf_pkg/meshes/Axis_2_Segment.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material
|
<material
|
||||||
name="">
|
name="">
|
||||||
@@ -202,7 +202,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/Axis 2 Segment.STL" />
|
filename="package://rover_urdf_pkg/meshes/Axis_2_Segment.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
@@ -214,16 +214,16 @@
|
|||||||
xyz="0.470027000000004 0.0126999999999999 0"
|
xyz="0.470027000000004 0.0126999999999999 0"
|
||||||
rpy="3.14159265358979 0.000449358059257729 0" />
|
rpy="3.14159265358979 0.000449358059257729 0" />
|
||||||
<parent
|
<parent
|
||||||
link="Axis 1 Segment" />
|
link="Axis_1_Segment" />
|
||||||
<child
|
<child
|
||||||
link="Axis 2 Segment" />
|
link="Axis_2_Segment" />
|
||||||
<axis
|
<axis
|
||||||
xyz="0 -1 0" />
|
xyz="0 -1 0" />
|
||||||
<limit
|
<limit
|
||||||
lower="-2.0"
|
lower="-2.0"
|
||||||
upper="2.0"
|
upper="2.0"
|
||||||
effort="0"
|
effort="0"
|
||||||
velocity="3.1415963" />
|
velocity="31.41593" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
@@ -274,7 +274,7 @@
|
|||||||
xyz="0.393826999999998 0 0"
|
xyz="0.393826999999998 0 0"
|
||||||
rpy="0 -0.000409495780687665 0" />
|
rpy="0 -0.000409495780687665 0" />
|
||||||
<parent
|
<parent
|
||||||
link="Axis 2 Segment" />
|
link="Axis_2_Segment" />
|
||||||
<child
|
<child
|
||||||
link="Wrist" />
|
link="Wrist" />
|
||||||
<axis
|
<axis
|
||||||
@@ -283,11 +283,11 @@
|
|||||||
lower="-1.6"
|
lower="-1.6"
|
||||||
upper="1.9"
|
upper="1.9"
|
||||||
effort="0"
|
effort="0"
|
||||||
velocity="3.1415963" />
|
velocity="31.41593" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
name="Diff Carrier">
|
name="Diff_Carrier">
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin
|
<origin
|
||||||
xyz="-8.64620358677695E-06 -0.00516792807449162 -7.22608790769408E-07"
|
xyz="-8.64620358677695E-06 -0.00516792807449162 -7.22608790769408E-07"
|
||||||
@@ -308,7 +308,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/Diff Carrier.STL" />
|
filename="package://rover_urdf_pkg/meshes/Diff_Carrier.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material
|
<material
|
||||||
name="">
|
name="">
|
||||||
@@ -322,7 +322,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/Diff Carrier.STL" />
|
filename="package://rover_urdf_pkg/meshes/Diff_Carrier.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
@@ -336,18 +336,18 @@
|
|||||||
<parent
|
<parent
|
||||||
link="Wrist" />
|
link="Wrist" />
|
||||||
<child
|
<child
|
||||||
link="Diff Carrier" />
|
link="Diff_Carrier" />
|
||||||
<axis
|
<axis
|
||||||
xyz="-1 0 0" />
|
xyz="-1 0 0" />
|
||||||
<limit
|
<limit
|
||||||
lower="-1.6"
|
lower="-1.6"
|
||||||
upper="1.6"
|
upper="1.6"
|
||||||
effort="0"
|
effort="0"
|
||||||
velocity="3.1415963" />
|
velocity="31.41593" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
name="End Effector">
|
name="End_Effector">
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin
|
<origin
|
||||||
xyz="-0.00327558376591462 0.00327411156667146 -0.0553569354578649"
|
xyz="-0.00327558376591462 0.00327411156667146 -0.0553569354578649"
|
||||||
@@ -368,7 +368,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/End Effector.STL" />
|
filename="package://rover_urdf_pkg/meshes/End_Effector.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material
|
<material
|
||||||
name="">
|
name="">
|
||||||
@@ -382,7 +382,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/End Effector.STL" />
|
filename="package://rover_urdf_pkg/meshes/End_Effector.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
@@ -394,15 +394,15 @@
|
|||||||
xyz="0 0.01 0"
|
xyz="0 0.01 0"
|
||||||
rpy="-1.5708 -0.21566 -3.1416" />
|
rpy="-1.5708 -0.21566 -3.1416" />
|
||||||
<parent
|
<parent
|
||||||
link="Diff Carrier" />
|
link="Diff_Carrier" />
|
||||||
<child
|
<child
|
||||||
link="End Effector" />
|
link="End_Effector" />
|
||||||
<axis
|
<axis
|
||||||
xyz="0 0 1" />
|
xyz="0 0 1" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
name="EF Gripper Right">
|
name="EF_Gripper_Right">
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin
|
<origin
|
||||||
xyz="3.60822483003176E-16 0.0395187564799554 -0.0785892929086096"
|
xyz="3.60822483003176E-16 0.0395187564799554 -0.0785892929086096"
|
||||||
@@ -423,7 +423,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/EF Gripper Right.STL" />
|
filename="package://rover_urdf_pkg/meshes/EF_Gripper_Right.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material
|
<material
|
||||||
name="">
|
name="">
|
||||||
@@ -437,7 +437,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/EF Gripper Right.STL" />
|
filename="package://rover_urdf_pkg/meshes/EF_Gripper_Right.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
@@ -449,9 +449,9 @@
|
|||||||
xyz="0 0 -0.031677"
|
xyz="0 0 -0.031677"
|
||||||
rpy="0 0 3.1416" />
|
rpy="0 0 3.1416" />
|
||||||
<parent
|
<parent
|
||||||
link="End Effector" />
|
link="End_Effector" />
|
||||||
<child
|
<child
|
||||||
link="EF Gripper Right" />
|
link="EF_Gripper_Right" />
|
||||||
<axis
|
<axis
|
||||||
xyz="0 1 0" />
|
xyz="0 1 0" />
|
||||||
<limit
|
<limit
|
||||||
@@ -465,7 +465,7 @@
|
|||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<link
|
<link
|
||||||
name="EF Gripper Left">
|
name="EF_Gripper_Left">
|
||||||
<inertial>
|
<inertial>
|
||||||
<origin
|
<origin
|
||||||
xyz="0.000260261090099842 0.0391877753208171 -0.0810862651363518"
|
xyz="0.000260261090099842 0.0391877753208171 -0.0810862651363518"
|
||||||
@@ -486,7 +486,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/EF Gripper Left.STL" />
|
filename="package://rover_urdf_pkg/meshes/EF_Gripper_Left.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
<material
|
<material
|
||||||
name="">
|
name="">
|
||||||
@@ -500,7 +500,7 @@
|
|||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
filename="package://rover_urdf_pkg/meshes/EF Gripper Left.STL" />
|
filename="package://rover_urdf_pkg/meshes/EF_Gripper_Left.STL" />
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
@@ -512,9 +512,9 @@
|
|||||||
xyz="0 0 -0.031677"
|
xyz="0 0 -0.031677"
|
||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<parent
|
<parent
|
||||||
link="End Effector" />
|
link="End_Effector" />
|
||||||
<child
|
<child
|
||||||
link="EF Gripper Left" />
|
link="EF_Gripper_Left" />
|
||||||
<axis
|
<axis
|
||||||
xyz="0 -1 0" />
|
xyz="0 -1 0" />
|
||||||
<limit
|
<limit
|
||||||
|
|||||||
Reference in New Issue
Block a user