Skip to content
This repository has been archived by the owner on Jul 27, 2022. It is now read-only.

Commit

Permalink
Merge pull request #11 from Edwinlinks/hero_urdf
Browse files Browse the repository at this point in the history
Update the hero description files
  • Loading branch information
qiayuanl authored Mar 30, 2022
2 parents ff94e57 + 4d525a7 commit d2ffd7b
Show file tree
Hide file tree
Showing 10 changed files with 27 additions and 67 deletions.
Binary file modified meshes/hero/base.stl
Binary file not shown.
Binary file removed meshes/hero/cover.stl
Binary file not shown.
Binary file modified meshes/hero/pitch.stl
Binary file not shown.
Binary file modified meshes/hero/trigger.stl
Binary file not shown.
Binary file modified meshes/hero/yaw.stl
Binary file not shown.
54 changes: 7 additions & 47 deletions urdf/hero/chassis.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,18 +3,18 @@
<xacro:include filename="$(find rm_description)/urdf/common/mecanum_wheel.urdf.xacro"/>

<!-- https://upload.wikimedia.org/wikipedia/commons/5/52/Wheelbase_and_Track.png -->
<xacro:property name="wheel_track" value="0.500"/>
<xacro:property name="wheel_base" value="0.475"/>
<xacro:property name="wheel_offset_z" value="-0.036"/>
<xacro:property name="wheel_track" value="0.392"/>
<xacro:property name="wheel_base" value="0.404"/>
<xacro:property name="wheel_offset_z" value="0.000031"/>

<xacro:macro name="chassis" params="roller_type">

<link name="base_link">
<inertial>
<mass value="19.31"/>
<origin xyz="-0.02282 0.002773 0.008173"/>
<inertia ixx="4.041e-1" ixy="7.617e-3" ixz="-1.317e-2" iyy="3.322e-1"
iyz="7.985e-2" izz="1.8e-1"/>
<mass value="8.44"/>
<origin xyz="-0.000578 0.00437 0.0620"/>
<inertia ixx="2.081e-1" ixy="5.195e-3" ixz="2.242e-3" iyy="2.784e-1"
iyz="2.494e-3" izz="3.521e-1"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand All @@ -31,46 +31,6 @@
</link>


<link name="cover">
<inertial>
<mass value="0.118"/>
<origin xyz="-0.037 -0.003 0.0"/>
<inertia ixx="6.240e-4" ixy="7.325e-4" ixz="1.839e-5" iyy="1.083e-3" iyz="-1.166e-5" izz="1.602e-3"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://rm_description/meshes/hero/cover.stl" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
<collision>
<origin xyz="0.033 0.0 -0.0" rpy="0 0.0 0"/>
<geometry>
<mesh filename="package://rm_description/meshes/hero/cover.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>

<joint name="cover_joint" type="revolute">
<axis xyz="1 0 0"/>
<origin xyz="-0.27 0.201 0.125"/>
<limit effort="1" velocity="30" lower="-3.14" upper="3.14"/>
<dynamics damping="0.0" friction="0.1"/>
<parent link="base_link"/>
<child link="cover"/>
</joint>

<transmission name="trans_cover_joint">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="cover_joint_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="cover_joint">
<offset>0</offset>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
</transmission>

<xacro:mecanum_wheel prefix="left_front" connected_to="base_link"
wheel_x_offset="${wheel_track/2}" wheel_y_offset="${wheel_base/2}"
wheel_z_offset="${wheel_offset_z}"
Expand Down
20 changes: 10 additions & 10 deletions urdf/hero/gimbal.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@

<link name="yaw">
<inertial>
<mass value="3.941"/>
<origin xyz="-0.052 -0.057 0.152"/>
<inertia ixx="1.250e-1" ixy="-1.357e-2" ixz="3.487e-2" iyy="1.218e-1"
iyz="3.775e-2" izz="3.242e-2"/>
<mass value="2.171"/>
<origin xyz="-0.0423 0.0528 0.0324"/>
<inertia ixx="1.926e-2" ixy="4.754e-3" ixz="7.073e-3" iyy="1.801e-2"
iyz="-3.208e-3" izz="1.945e-2"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand All @@ -27,7 +27,7 @@
</link>

<joint name="yaw_joint" type="revolute">
<origin xyz="0 0 0.129"
<origin xyz="0 0 0.205"
rpy="0 0 0"/>
<dynamics damping="0.0" friction="0.1"/>
<limit effort="1.2" velocity="13.82" lower="-1e10" upper="1e10"/>
Expand All @@ -38,10 +38,10 @@

<link name="pitch">
<inertial>
<mass value="1.125"/>
<origin xyz="0.104 0.0 0.024"/>
<inertia ixx="2.658e-3" ixy="4.995e-6" ixz="-3.326e-3" iyy="2.084e-2"
iyz="6.020e-6" izz="1.948e-2"/>
<mass value="1.43"/>
<origin xyz="0.0480 0.00133 0.0501"/>
<inertia ixx="1.087e-2" ixy="1.543e-3" ixz="-1.474e-3" iyy="1.820e-2"
iyz="3.219e-3" izz="1.614e-2"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand All @@ -58,7 +58,7 @@
</link>

<joint name="pitch_joint" type="revolute">
<origin xyz="-0.06 0 0.191 " rpy="0 0 0"/>
<origin xyz="-0.05 0 0.151 " rpy="0 0 0"/>
<dynamics damping="0.0" friction="0.1"/>
<limit effort="1.2" velocity="13.82" lower="${pitch_lower_limit}" upper="${pitch_upper_limit}"/>
<safety_controller k_velocity="0.1"
Expand Down
4 changes: 2 additions & 2 deletions urdf/hero/hero.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,12 @@
<xacro:include filename="$(find rm_description)/urdf/hero/gimbal.transmission.urdf.xacro"/>
<xacro:include filename="$(find rm_description)/urdf/common/imu.urdf.xacro"/>
<xacro:include filename="$(find rm_description)/urdf/common/camera.urdf.xacro"/>
<xacro:camera_sensor xyz="0.05 0 -0.07" rpy="${pi} 0 -0.02" frame_id="$(arg camera_link)" parent="pitch"
<xacro:camera_sensor xyz="0.0445 0 0.109" rpy="${pi} 0 -0.02" frame_id="$(arg camera_link)" parent="pitch"
camera_sim="$(arg use_simulation)"/>
<xacro:camera_optical_frame xyz="0.2527 0.0071 -0.0984" rpy="1.5486 -0.0025 1.600"
frame_id="$(arg camera_optical_frame)" parent="pitch"
camera_sim="$(arg use_simulation)"/>
<xacro:IMU connected_to="pitch" imu_name="gimbal_imu" xyz="0.08 0. 0.08" rpy="0 0 -${pi/2}"/>
<xacro:IMU connected_to="pitch" imu_name="gimbal_imu" xyz="0.08 0. 0.08" rpy="${pi} ${pi} ${pi}"/>

<xacro:if value="$(arg load_shooter)">
<xacro:include filename="$(find rm_description)/urdf/hero/shooter.urdf.xacro"/>
Expand Down
2 changes: 1 addition & 1 deletion urdf/hero/shooter.transmission.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<transmission name="trans_trigger_joint">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="trigger_joint_motor">
<mechanicalReduction>-26.851</mechanicalReduction>
<mechanicalReduction>76.8128</mechanicalReduction>
</actuator>
<joint name="trigger_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
Expand Down
14 changes: 7 additions & 7 deletions urdf/hero/shooter.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@
<xacro:include filename="$(find rm_description)/urdf/common/friction.urdf.xacro"/>


<xacro:property name="wheel_offset_x" value="0.084"/>
<xacro:property name="wheel_offset_x" value="0.075"/>
<xacro:property name="wheel_offset_y" value="0.049"/>
<xacro:property name="wheel_offset_z" value="0.0"/>
<xacro:property name="wheel_offset_z" value="0"/>


<xacro:friction_wheel prefixs="left" connected_to="pitch"
Expand All @@ -19,10 +19,10 @@

<link name="trigger">
<inertial>
<mass value="0.295177"/>
<origin xyz="-0.00842 0.0 0.00605"/>
<inertia ixx="2.255e-4" ixy="2.5698e-7" ixz="2.3929e-6" iyy="2.233e-4"
iyz="5.22e-7" izz="2.643e-4"/>
<mass value="1.4"/>
<origin xyz="-0.0146 -0.00736 -0.00154"/>
<inertia ixx="4.443e-3" ixy="-1.694e-3" ixz="-1.776e-3" iyy="1.122e-2"
iyz="-3.693e-4" izz="1.347e-2"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand All @@ -39,7 +39,7 @@
</link>

<joint name="trigger_joint" type="continuous">
<origin xyz="-0.064 0 0" rpy="0 0 0"/>
<origin xyz="0 0 0.063" rpy="0 0 0"/>
<dynamics damping="0.0" friction="0.01"/>
<limit effort="6.99" velocity="35.758" lower="-1e16" upper="1e16"/>
<parent link="base_link"/>
Expand Down

0 comments on commit d2ffd7b

Please sign in to comment.