|
| 1 | +<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="rover_4wd"> |
| 2 | + |
| 3 | + <xacro:property name="wheel_z_offset" value="0.020" /> |
| 4 | + <xacro:property name="wheel_x_offset" value="0.145" /> |
| 5 | + <xacro:property name="front_flipper_x_offset" value="-0.0035" /> |
| 6 | + <xacro:property name="wheel_y_offset" value="0.18" /> |
| 7 | + <xacro:property name="track_y_offset" value="0.11" /> |
| 8 | + <xacro:property name="wheel_mass" value="1.25" /> |
| 9 | + <xacro:property name="chassis_mass" value="4.53592" /> |
| 10 | + |
| 11 | + <xacro:property name="payload_z_offset" value="0.096" /> |
| 12 | + <xacro:include filename="$(find custom_robots)/urdf/accessories/rover_dev_payload.urdf" /> |
| 13 | + <xacro:include filename="$(find custom_robots)/urdf/accessories/rplidar_s2.urdf" /> |
| 14 | + <xacro:include filename="$(find custom_robots)/urdf/accessories/imu.urdf" /> |
| 15 | + |
| 16 | + <link name="base_link" /> |
| 17 | + |
| 18 | + <link name="chassis_link"> |
| 19 | + <visual> |
| 20 | + <origin xyz="0 0 0" rpy="1.57 -0 1.57" /> |
| 21 | + <geometry> |
| 22 | + <mesh filename="file://$(find custom_robots)/meshes/flipper_chassis.dae"/> |
| 23 | + </geometry> |
| 24 | + </visual> |
| 25 | + |
| 26 | + <visual> |
| 27 | + <origin xyz="0 ${track_y_offset} 0" rpy="1.57 3.1415 0" /> |
| 28 | + <geometry> |
| 29 | + <mesh filename="file://$(find custom_robots)/meshes/flipper_track.dae"/> |
| 30 | + </geometry> |
| 31 | + </visual> |
| 32 | + <collision> |
| 33 | + <origin xyz="0 ${track_y_offset} 0" rpy="1.57 3.1415 0" /> |
| 34 | + <geometry> |
| 35 | + <mesh filename="file://$(find custom_robots)/meshes/flipper_track.dae"/> |
| 36 | + </geometry> |
| 37 | + </collision> |
| 38 | + |
| 39 | + <visual> |
| 40 | + <origin xyz="0 ${-track_y_offset} 0" rpy="1.57 3.1415 0" /> |
| 41 | + <geometry> |
| 42 | + <mesh filename="file://$(find custom_robots)/meshes/flipper_track.dae"/> |
| 43 | + </geometry> |
| 44 | + </visual> |
| 45 | + <collision> |
| 46 | + <origin xyz="0 ${-track_y_offset} 0" rpy="1.57 3.1415 0" /> |
| 47 | + <geometry> |
| 48 | + <mesh filename="file://$(find custom_robots)/meshes/flipper_track.dae"/> |
| 49 | + </geometry> |
| 50 | + </collision> |
| 51 | + |
| 52 | + <collision> |
| 53 | + <origin xyz="0 0 0" rpy="1.57 -0 1.57" /> |
| 54 | + <geometry> |
| 55 | + <mesh filename="file://$(find custom_robots)/meshes/flipper_chassis.dae"/> |
| 56 | + </geometry> |
| 57 | + </collision> |
| 58 | + |
| 59 | + <inertial> |
| 60 | + <origin xyz="0 0 0" rpy="0 0 0"/> |
| 61 | + <mass value="${chassis_mass}" /> |
| 62 | + <inertia ixx="0.028064" ixy="0.0" ixz="0.0" iyy="0.08226" iyz="0.0" izz="0.10258" /> |
| 63 | + </inertial> |
| 64 | + </link> |
| 65 | + |
| 66 | + <joint name="base_to_chassis" type="fixed"> |
| 67 | + <parent link="base_link"/> |
| 68 | + <child link="chassis_link"/> |
| 69 | + <origin xyz="0 0 0.125"/> |
| 70 | + </joint> |
| 71 | + |
| 72 | + <link name="fr_wheel_link"> |
| 73 | + <visual> |
| 74 | + <origin xyz="0 0 0" rpy="-1.57 0 0" /> |
| 75 | + <geometry> |
| 76 | + <mesh filename="file://$(find custom_robots)/meshes/pro_tire.dae"/> |
| 77 | + </geometry> |
| 78 | + </visual> |
| 79 | + <collision> |
| 80 | + <origin xyz="0 0 0" rpy="-1.57 0 0" /> |
| 81 | + <geometry> |
| 82 | + <mesh filename="file://$(find custom_robots)/meshes/pro_tire.dae"/> |
| 83 | + </geometry> |
| 84 | + </collision> |
| 85 | + <inertial> |
| 86 | + <origin xyz="0 0 0" rpy="0 0 0" /> |
| 87 | + <mass value="${wheel_mass}" /> |
| 88 | + <inertia ixx="0.005645" ixy="0.0" ixz="0.0" iyy="0.01008" iyz="0.0" izz="0.005645"/> |
| 89 | + </inertial> |
| 90 | + </link> |
| 91 | + <joint name="fr_wheel_to_chassis" type="continuous"> |
| 92 | + <parent link="chassis_link"/> |
| 93 | + <child link="fr_wheel_link"/> |
| 94 | + <axis xyz="0 1 0"/> |
| 95 | + <origin xyz="${wheel_x_offset + front_flipper_x_offset} ${-wheel_y_offset} 0" rpy="0 0 0"/> |
| 96 | + </joint> |
| 97 | + |
| 98 | + <link name="fl_wheel_link"> |
| 99 | + <visual> |
| 100 | + <origin xyz="0 0 0" rpy="1.57 0 0" /> |
| 101 | + <geometry> |
| 102 | + <mesh filename="file://$(find custom_robots)/meshes/pro_tire.dae"/> |
| 103 | + </geometry> |
| 104 | + </visual> |
| 105 | + <collision> |
| 106 | + <origin xyz="0 0 0" rpy="1.57 0 0" /> |
| 107 | + <geometry> |
| 108 | + <mesh filename="file://$(find custom_robots)/meshes/pro_tire.dae"/> |
| 109 | + </geometry> |
| 110 | + </collision> |
| 111 | + <inertial> |
| 112 | + <origin xyz="0 0 0" rpy="0 0 0" /> |
| 113 | + <mass value="${wheel_mass}" /> |
| 114 | + <inertia ixx="0.005645" ixy="0.0" ixz="0.0" iyy="0.01008" iyz="0.0" izz="0.005645"/> |
| 115 | + </inertial> |
| 116 | + </link> |
| 117 | + <joint name="fl_wheel_to_chassis" type="continuous"> |
| 118 | + <parent link="chassis_link"/> |
| 119 | + <child link="fl_wheel_link"/> |
| 120 | + <axis xyz="0 1 0"/> |
| 121 | + <origin xyz="${wheel_x_offset + front_flipper_x_offset} ${wheel_y_offset} 0" rpy="0 0 0"/> |
| 122 | + </joint> |
| 123 | + |
| 124 | + <link name="rr_wheel_link"> |
| 125 | + <visual> |
| 126 | + <origin xyz="0 0 0" rpy="1.57 0 3.1415" /> |
| 127 | + <geometry> |
| 128 | + <mesh filename="file://$(find custom_robots)/meshes/pro_tire.dae"/> |
| 129 | + </geometry> |
| 130 | + </visual> |
| 131 | + <collision> |
| 132 | + <origin xyz="0 0 0" rpy="1.57 0 3.1415" /> |
| 133 | + <geometry> |
| 134 | + <mesh filename="file://$(find custom_robots)/meshes/pro_tire.dae"/> |
| 135 | + </geometry> |
| 136 | + </collision> |
| 137 | + <inertial> |
| 138 | + <origin xyz="0 0 0" rpy="0 0 0" /> |
| 139 | + <mass value="${wheel_mass}" /> |
| 140 | + <inertia ixx="0.005645" ixy="0.0" ixz="0.0" iyy="0.01008" iyz="0.0" izz="0.005645"/> |
| 141 | + </inertial> |
| 142 | + </link> |
| 143 | + <joint name="rr_wheel_to_chassis" type="continuous"> |
| 144 | + <parent link="chassis_link"/> |
| 145 | + <child link="rr_wheel_link"/> |
| 146 | + <axis xyz="0 1 0"/> |
| 147 | + <origin xyz="${-wheel_x_offset} ${-wheel_y_offset} 0"/> |
| 148 | + </joint> |
| 149 | + |
| 150 | + <link name="rl_wheel_link"> |
| 151 | + <visual> |
| 152 | + <origin xyz="0 0 0" rpy="-1.57 0 3.1415" /> |
| 153 | + <geometry> |
| 154 | + <mesh filename="file://$(find custom_robots)/meshes/pro_tire.dae"/> |
| 155 | + </geometry> |
| 156 | + </visual> |
| 157 | + <collision> |
| 158 | + <origin xyz="0 0 0" rpy="-1.57 0 3.1415" /> |
| 159 | + <geometry> |
| 160 | + <mesh filename="file://$(find custom_robots)/meshes/pro_tire.dae"/> |
| 161 | + </geometry> |
| 162 | + </collision> |
| 163 | + <inertial> |
| 164 | + <origin xyz="0 0 0" rpy="0 0 0" /> |
| 165 | + <mass value="${wheel_mass}" /> |
| 166 | + <inertia ixx="0.005645" ixy="0.0" ixz="0.0" iyy="0.01008" iyz="0.0" izz="0.005645"/> |
| 167 | + </inertial> |
| 168 | + </link> |
| 169 | + <joint name="rl_wheel_to_chassis" type="continuous"> |
| 170 | + <parent link="chassis_link"/> |
| 171 | + <child link="rl_wheel_link"/> |
| 172 | + <axis xyz="0 1 0"/> |
| 173 | + <origin xyz="${-wheel_x_offset} ${wheel_y_offset} 0"/> |
| 174 | + </joint> |
| 175 | + |
| 176 | + <gazebo> |
| 177 | + <plugin name="gz::sim::systems::DiffDrive" filename="gz-sim-diff-drive-system"> |
| 178 | + <num_wheel_pairs>2</num_wheel_pairs> |
| 179 | + <left_joint>rl_wheel_to_chassis</left_joint> |
| 180 | + <left_joint>fl_wheel_to_chassis</left_joint> |
| 181 | + <right_joint>rr_wheel_to_chassis</right_joint> |
| 182 | + <right_joint>fr_wheel_to_chassis</right_joint> |
| 183 | + <wheel_separation>0.24</wheel_separation> |
| 184 | + <wheel_radius>0.122</wheel_radius> |
| 185 | + <max_linear_acceleration>0.5</max_linear_acceleration> |
| 186 | + <min_linear_acceleration>-0.5</min_linear_acceleration> |
| 187 | + <max_angular_acceleration>0.8</max_angular_acceleration> |
| 188 | + <min_angular_acceleration>-0.8</min_angular_acceleration> |
| 189 | + <frame_id>odom</frame_id> |
| 190 | + <child_frame_id>base_link</child_frame_id> |
| 191 | + <topic>/cmd_vel</topic> |
| 192 | + <odom_topic>/odometry/wheels</odom_topic> |
| 193 | + <tf_topic>/tf_gazebo</tf_topic> |
| 194 | + </plugin> |
| 195 | + |
| 196 | + <plugin name="gz::sim::systems::JointStatePublisher" filename="gz-sim-joint-state-publisher-system"> |
| 197 | + <topic>/joint_states</topic> |
| 198 | + </plugin> |
| 199 | + |
| 200 | + <plugin name="gz::sim::systems::OdometryPublisher" filename="gz-sim-odometry-publisher-system"> |
| 201 | + <odom_frame>odom</odom_frame> |
| 202 | + <robot_base_frame>base_link</robot_base_frame> |
| 203 | + <odom_topic>/odom</odom_topic> |
| 204 | + <dimensions>3</dimensions> |
| 205 | + </plugin> |
| 206 | + |
| 207 | + <plugin filename="libNoisyOdometryPlugin.so" name="custom_plugins::NoisyOdometryPlugin"> |
| 208 | + <ros_topic>/odom</ros_topic> |
| 209 | + <gz_cmd_vel_topic>/cmd_vel</gz_cmd_vel_topic> |
| 210 | + <frame_id>odom</frame_id> |
| 211 | + <child_frame_id>base_link</child_frame_id> |
| 212 | + <alpha1>0.005</alpha1> |
| 213 | + <alpha2>0.005</alpha2> |
| 214 | + <alpha3>0.003</alpha3> |
| 215 | + <alpha4>0.003</alpha4> |
| 216 | + </plugin> |
| 217 | + </gazebo> |
| 218 | + |
| 219 | + <plugin filename="gz-sim-pose-publisher-system" name="gz::sim::systems::PosePublisher"> |
| 220 | + <publish_model_pose>true</publish_model_pose> |
| 221 | + <publish_nested_model>true</publish_nested_model> |
| 222 | + <publish_nested_model_pose>true</publish_nested_model_pose> |
| 223 | + <use_pose_vector_msg>true</use_pose_vector_msg> |
| 224 | + </plugin> |
| 225 | + |
| 226 | +</robot> |
0 commit comments