Skip to content
Merged
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
226 changes: 226 additions & 0 deletions CustomRobots/rover_4wd_description/urdf/rover_4wd_noisy_high.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,226 @@
<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="$(find custom_robots)/urdf/accessories/rover_dev_payload.urdf" />
<xacro:include filename="$(find custom_robots)/urdf/accessories/rplidar_s2.urdf" />
<xacro:include filename="$(find custom_robots)/urdf/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="file://$(find custom_robots)/meshes/flipper_chassis.dae"/>
</geometry>
</visual>

<visual>
<origin xyz="0 ${track_y_offset} 0" rpy="1.57 3.1415 0" />
<geometry>
<mesh filename="file://$(find custom_robots)/meshes/flipper_track.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 ${track_y_offset} 0" rpy="1.57 3.1415 0" />
<geometry>
<mesh filename="file://$(find custom_robots)/meshes/flipper_track.dae"/>
</geometry>
</collision>

<visual>
<origin xyz="0 ${-track_y_offset} 0" rpy="1.57 3.1415 0" />
<geometry>
<mesh filename="file://$(find custom_robots)/meshes/flipper_track.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 ${-track_y_offset} 0" rpy="1.57 3.1415 0" />
<geometry>
<mesh filename="file://$(find custom_robots)/meshes/flipper_track.dae"/>
</geometry>
</collision>

<collision>
<origin xyz="0 0 0" rpy="1.57 -0 1.57" />
<geometry>
<mesh filename="file://$(find custom_robots)/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="file://$(find custom_robots)/meshes/pro_tire.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="-1.57 0 0" />
<geometry>
<mesh filename="file://$(find custom_robots)/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>
</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="file://$(find custom_robots)/meshes/pro_tire.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<geometry>
<mesh filename="file://$(find custom_robots)/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>
</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="file://$(find custom_robots)/meshes/pro_tire.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="1.57 0 3.1415" />
<geometry>
<mesh filename="file://$(find custom_robots)/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>
</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="file://$(find custom_robots)/meshes/pro_tire.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="-1.57 0 3.1415" />
<geometry>
<mesh filename="file://$(find custom_robots)/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>
</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>0.5</max_linear_acceleration>
<min_linear_acceleration>-0.5</min_linear_acceleration>
<max_angular_acceleration>0.8</max_angular_acceleration>
<min_angular_acceleration>-0.8</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 name="gz::sim::systems::JointStatePublisher" filename="gz-sim-joint-state-publisher-system">
<topic>/joint_states</topic>
</plugin>

<plugin name="gz::sim::systems::OdometryPublisher" filename="gz-sim-odometry-publisher-system">
<odom_frame>odom</odom_frame>
<robot_base_frame>base_link</robot_base_frame>
<odom_topic>/odom</odom_topic>
<dimensions>3</dimensions>
</plugin>

<plugin filename="libNoisyOdometryPlugin.so" name="custom_plugins::NoisyOdometryPlugin">
<ros_topic>/odom</ros_topic>
<gz_cmd_vel_topic>/cmd_vel</gz_cmd_vel_topic>
<frame_id>odom</frame_id>
<child_frame_id>base_link</child_frame_id>
<alpha1>0.005</alpha1>
<alpha2>0.005</alpha2>
<alpha3>0.003</alpha3>
<alpha4>0.003</alpha4>
</plugin>
</gazebo>

<plugin filename="gz-sim-pose-publisher-system" name="gz::sim::systems::PosePublisher">
<publish_model_pose>true</publish_model_pose>
<publish_nested_model>true</publish_nested_model>
<publish_nested_model_pose>true</publish_nested_model_pose>
<use_pose_vector_msg>true</use_pose_vector_msg>
</plugin>

</robot>
Loading