Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
92 changes: 92 additions & 0 deletions CustomRobots/roverrobotics_description/meshes/flipper_chassis.dae

Large diffs are not rendered by default.

89 changes: 89 additions & 0 deletions CustomRobots/roverrobotics_description/meshes/flipper_track.dae

Large diffs are not rendered by default.

92 changes: 92 additions & 0 deletions CustomRobots/roverrobotics_description/meshes/pro_tire.dae

Large diffs are not rendered by default.

17,878 changes: 17,878 additions & 0 deletions CustomRobots/roverrobotics_description/meshes/rover_payload.dae

Large diffs are not rendered by default.

162 changes: 162 additions & 0 deletions CustomRobots/roverrobotics_description/meshes/rplidar_s2.dae

Large diffs are not rendered by default.

26 changes: 26 additions & 0 deletions CustomRobots/roverrobotics_description/urdf/accessories/imu.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="imu">

<link name="imu_link"/>

<joint name="imu_to_payload" type="fixed">
<parent link="payload_link"/>
<child link="imu_link"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>

<gazebo reference="imu_link">
<sensor name="imu" type="imu">
<always_on>1</always_on>
<update_rate>50</update_rate>
<visualize>true</visualize>
<topic>imu/data</topic>
<enable_metrics>true</enable_metrics>
<frame_id>imu_link</frame_id>
</sensor>
</gazebo>

<gazebo>
<plugin filename="gz-sim-imu-system" name="gz::sim::systems::Imu"/>
</gazebo>

</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="rover_miti_payload">

<link name="payload_link">
<visual>
<origin xyz="0 0.0115 0" rpy="1.57 -0 1.57" />
<geometry>
<mesh filename="file://$(find roverrobotics_description)/meshes/rover_payload.dae"/>
</geometry>
</visual>

<collision>
<origin xyz="0 0.0115 0" rpy="1.57 -0 1.57" />
<geometry>
<mesh filename="file://$(find roverrobotics_description)/meshes/rover_payload.dae"/>
</geometry>
</collision>

<inertial>
<origin xyz="-0.01 0 0" rpy="0 0 0"/>
<mass value="2.95" />
<inertia ixx="0.018398" ixy="0.0" ixz="0.0" iyy="0.04064" iyz="0.0" izz="0.05396" />
</inertial>
</link>

<joint name="payload_to_chassis" type="fixed">
<parent link="chassis_link"/>
<child link="payload_link"/>
<origin xyz="0 0 ${payload_z_offset}"/>
</joint>

</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="rplidar_s2">

<link name="lidar_link">
<visual>
<origin xyz="0 0 0" rpy="-1.57 0 3.1415"/>
<geometry>
<mesh filename="file://$(find roverrobotics_description)/meshes/rplidar_s2.dae"/>
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="-1.57 0 3.1415"/>
<geometry>
<mesh filename="file://$(find roverrobotics_description)/meshes/rplidar_s2.dae"/>
</geometry>
</collision>

</link>

<joint name="lidar_to_payload" type="fixed">
<parent link="payload_link"/>
<child link="lidar_link"/>
<origin xyz="0.174 0 0.10" rpy="0 0 3.1415"/>
</joint>

<gazebo reference="lidar_link">
<sensor name='gpu_lidar' type='gpu_lidar'>
<pose>0 0 0 0 0 0</pose>
<topic>scan</topic>
<frame_id>lidar_link</frame_id>
<update_rate>10</update_rate>
<lidar>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-3.14159</min_angle>
<max_angle>3.14159</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>0.0</min_angle>
<max_angle>0.0</max_angle>
</vertical>
</scan>
<range>
<min>0.15</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
</lidar>
<visualize>true</visualize>
<always_on>1</always_on>
</sensor>
</gazebo>

<gazebo>
<plugin filename="gz-sim-sensors-system" name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
</gazebo>

</robot>
220 changes: 220 additions & 0 deletions CustomRobots/roverrobotics_description/urdf/rover_4wd.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,220 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="rover_4wd">

<xacro:property name="wheel_z_offset" value="0.020" />
<xacro:property name="wheel_x_offset" value="0.145" />
<xacro:property name="front_flipper_x_offset" value="-0.0035" />
<xacro:property name="wheel_y_offset" value="0.18" />
<xacro:property name="track_y_offset" value="0.11" />
<xacro:property name="wheel_mass" value="1.25" />
<xacro:property name="chassis_mass" value="4.53592" />

<xacro:property name="payload_z_offset" value="0.096" />
<xacro:include filename="accessories/rover_dev_payload.urdf" />
<xacro:include filename="accessories/rplidar_s2.urdf" />
<xacro:include filename="accessories/imu.urdf" />

<link name="base_link" />
<link name="chassis_link">
<visual>
<origin xyz="0 0 0" rpy="1.57 -0 1.57" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/flipper_chassis.dae"/>
</geometry>
</visual>
<visual>
<origin xyz="0 ${track_y_offset} 0" rpy="1.57 3.1415 0" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/flipper_track.dae"/>
</geometry>
</visual>

<collision>
<origin xyz="0 ${track_y_offset} 0" rpy="1.57 3.1415 0" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/flipper_track.dae"/>
</geometry>
</collision>

<visual>
<origin xyz="0 ${-track_y_offset} 0" rpy="1.57 3.1415 0" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/flipper_track.dae"/>
</geometry>
</visual>

<collision>
<origin xyz="0 ${-track_y_offset} 0" rpy="1.57 3.1415 0" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/flipper_track.dae"/>
</geometry>
</collision>

<collision>
<origin xyz="0 0 0" rpy="1.57 -0 1.57" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/flipper_chassis.dae"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${chassis_mass}" />
<inertia ixx="0.028064" ixy="0.0" ixz="0.0" iyy="0.08226" iyz="0.0" izz="0.10258" />
</inertial>
</link>

<joint name="base_to_chassis" type="fixed">
<parent link="base_link"/>
<child link="chassis_link"/>
<origin xyz="0 0 0.125"/>
</joint>


<link name="fr_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="-1.57 0 0" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/pro_tire.dae"/>
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="-1.57 0 0" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/pro_tire.dae"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="${wheel_mass}" />
<inertia ixx="0.005645" ixy="0.0" ixz="0.0" iyy= "0.01008" iyz="0.0" izz="0.005645"/>
</inertial>
<mu>5.0</mu>
</link>
<joint name="fr_wheel_to_chassis" type="continuous">
<parent link="chassis_link"/>
<child link="fr_wheel_link"/>
<axis xyz="0 1 0"/>
<origin xyz="${wheel_x_offset + front_flipper_x_offset} ${-wheel_y_offset} 0" rpy="0 0 0"/>
</joint>

<link name="fl_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/pro_tire.dae"/>
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/pro_tire.dae"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="${wheel_mass}" />
<inertia ixx="0.005645" ixy="0.0" ixz="0.0" iyy= "0.01008" iyz="0.0" izz="0.005645"/>
</inertial>
<mu>5.0</mu>
</link>
<joint name="fl_wheel_to_chassis" type="continuous">
<parent link="chassis_link"/>
<child link="fl_wheel_link"/>
<axis xyz="0 1 0"/>
<origin xyz="${wheel_x_offset + front_flipper_x_offset} ${wheel_y_offset} 0" rpy="0 0 0"/>
</joint>

<link name="rr_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 3.1415" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/pro_tire.dae"/>
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="1.57 0 3.1415" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/pro_tire.dae"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="${wheel_mass}" />
<inertia ixx="0.005645" ixy="0.0" ixz="0.0" iyy= "0.01008" iyz="0.0" izz="0.005645"/>
</inertial>
<mu>5.0</mu>
</link>
<joint name="rr_wheel_to_chassis" type="continuous">
<parent link="chassis_link"/>
<child link="rr_wheel_link"/>
<axis xyz="0 1 0"/>
<origin xyz="${-wheel_x_offset} ${-wheel_y_offset} 0"/>
</joint>

<link name="rl_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="-1.57 0 3.1415" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/pro_tire.dae"/>
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="-1.57 0 3.1415" />
<geometry>
<mesh filename="package://roverrobotics_description/meshes/pro_tire.dae"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="${wheel_mass}" />
<inertia ixx="0.005645" ixy="0.0" ixz="0.0" iyy= "0.01008" iyz="0.0" izz="0.005645"/>
</inertial>
<mu>5.0</mu>
</link>
<joint name="rl_wheel_to_chassis" type="continuous">
<parent link="chassis_link"/>
<child link="rl_wheel_link"/>
<axis xyz="0 1 0"/>
<origin xyz="${-wheel_x_offset} ${wheel_y_offset} 0"/>
</joint>


<gazebo>
<plugin name="gz::sim::systems::DiffDrive" filename="gz-sim-diff-drive-system">
<num_wheel_pairs>2</num_wheel_pairs>
<left_joint>rl_wheel_to_chassis</left_joint>
<left_joint>fl_wheel_to_chassis</left_joint>
<right_joint>rr_wheel_to_chassis</right_joint>
<right_joint>fr_wheel_to_chassis</right_joint>
<wheel_separation>0.24</wheel_separation>
<wheel_radius>0.122</wheel_radius>

<max_linear_acceleration>5</max_linear_acceleration>
<min_linear_acceleration>-5</min_linear_acceleration>
<max_angular_acceleration>4</max_angular_acceleration>
<min_angular_acceleration>-4</min_angular_acceleration>


<frame_id>odom</frame_id>
<child_frame_id>base_link</child_frame_id>

<topic>/cmd_vel</topic>
<odom_topic>/odometry/wheels</odom_topic>
<tf_topic>/tf_gazebo</tf_topic>

</plugin>

<plugin filename="gz-sim-joint-state-publisher-system" name="gz::sim::systems::JointStatePublisher">
<topic>/joint_states</topic>
</plugin>
</gazebo>

</robot>