Skip to content

Instantly share code, notes, and snippets.

@EpsAvlc
Created May 12, 2021 08:40
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 0 You must be signed in to fork a gist
  • Save EpsAvlc/c21dfa85fdcda26b9bdd679ba57260fd to your computer and use it in GitHub Desktop.
Save EpsAvlc/c21dfa85fdcda26b9bdd679ba57260fd to your computer and use it in GitHub Desktop.
robuster_horizon.urdf.xarco
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="mr1000">
<!-- <xacro:arg name="robot_namespace" default="/robuster_horizon" /> -->
<xacro:arg name="robot_namespace" default="/" />
<xacro:arg name="gpu" default="false"/>
<xacro:property name="gpu" value="$(arg gpu)" />
<!-- Wheel Properties -->
<xacro:property name="wheel_length" value="0.1143" />
<xacro:property name="wheel_radius" value="0.1651" />
<!-- Wheel Mounting Positions -->
<xacro:property name="wheelbase" value="0.4885" /> <!-- distance betwee front wheel and rear wheel -->
<xacro:property name="track" value="0.5347" /> <!-- separation between left wheel and right wheel: 0.1143 + 0.4204 = 0.5347-->
<xacro:property name="wheel_vertical_offset" value="0.04" />
<!-- Base Size -->
<xacro:property name="base_x_size" value="0.866" />
<xacro:property name="base_y_size" value="0.400" />
<xacro:property name="base_z_size" value="0.2165" />
<xacro:property name="M_PI" value="3.14159"/>
<!-- Lidar Config -->
<xacro:property name="LiDARName" value="rslidar80" />
<xacro:property name="topicName" value="rslidar80_points" />
<xacro:property name="frameName" value="rslidar80_frame" />
<xacro:property name="min_range" value="0.9" />
<xacro:property name="max_range" value="130.0" />
<xacro:property name="samples" value="440"/>
<xacro:property name="hz" value="10" />
<xacro:property name="gaussianNoise" value="0.008" />
<!-- Included URDF/XACRO Files -->
<xacro:include filename="$(find active_mapping)/urdf/mr1000_wheel.urdf.xacro" />
<link name="base_link">
<inertial>
<!-- husky
<mass value="46.034" />
<origin xyz="-0.00065 -0.085 0.062" />
<inertia ixx="0.6022" ixy="-0.02364" ixz="-0.1197" iyy="1.7386" iyz="-0.001544" izz="2.0296" />
-->
<!-- turtlebot
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
-->
<!-- mr1000 -->
<origin xyz="0.0083361 0.00033765 0.10648" rpy="0 0 0" />
<mass value="13.336" />
<inertia ixx="0.12049" ixy="5.9344E-06" ixz="-0.001006" iyy="0.32804" iyz="-7.8809E-07" izz="0.41342" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://active_mapping/meshes/base_linkm3.STL" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="${base_x_size} ${base_y_size} ${base_z_size}"/>
</geometry>
</collision>
<!-- <collision>
<origin xyz="0 0 ${base_z_size*3/4-0.01}" rpy="0 0 0" />
<geometry>
<box size="${base_x_size*4/5} ${base_y_size} ${base_z_size/2-0.02}"/>
</geometry>
</collision> -->
</link>
<gazebo reference="base_link">
<material>Gazebo/Yellow</material>
</gazebo>
<!-- Base footprint is on the ground under the robot -->
<link name="base_footprint"/>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${wheel_vertical_offset - wheel_radius}" rpy="0 0 0" />
<parent link="base_link" />
<child link="base_footprint" />
</joint>
<!-- Wheel links generated from macros -->
<xacro:mr1000_wheel wheel_prefix="front_left">
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:mr1000_wheel>
<xacro:mr1000_wheel wheel_prefix="front_right">
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:mr1000_wheel>
<xacro:mr1000_wheel wheel_prefix="rear_left">
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:mr1000_wheel>
<xacro:mr1000_wheel wheel_prefix="rear_right">
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:mr1000_wheel>
<!-- IMU Link is the standard mounting position for the UM6 IMU.-->
<link name="imu_link">
<inertial>
<origin xyz="0.0083361 0.00033765 0.10648" rpy="0 0 0" />
<mass value="0.336" />
<inertia ixx="0.12049" ixy="0.0" ixz="0.0" iyy="0.01788" iyz="0.0" izz="0.41342" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.05 0.05 0.02"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.05 0.05 0.02"/>
</geometry>
</collision>
</link>
<joint name="imu_joint" type="fixed">
<!-- <origin xyz="$(optenv HUSKY_IMU_XYZ 0.19 0 0.149)" rpy="$(optenv HUSKY_IMU_RPY 0 -1.5708 3.1416)" /> -->
<!-- http://wiki.ros.org/husky_bringup/Tutorials/Customize%20Husky%20Configuration -->
<origin xyz="0 0 ${base_z_size}" rpy="0 ${-M_PI/2} ${M_PI}" />
<parent link="base_link" />
<child link="imu_link" />
</joint>
<gazebo reference="imu_link">
<material>Gazebo/Red</material>
</gazebo>
<!-- Gazebo imu controller -->
<gazebo>
<plugin name="imu_controller" filename="libhector_gazebo_ros_imu.so">
<robotNamespace>$(arg robot_namespace)</robotNamespace>
<updateRate>50.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>imu/data</topicName>
<accelDrift>0.005 0.005 0.005</accelDrift>
<accelGaussianNoise>0.005 0.005 0.005</accelGaussianNoise>
<rateDrift>0.005 0.005 0.005 </rateDrift>
<rateGaussianNoise>0.005 0.005 0.005 </rateGaussianNoise>
<headingDrift>0.005</headingDrift>
<headingGaussianNoise>0.005</headingGaussianNoise>
</plugin>
</gazebo>
<!-- livox -->
<xacro:property name="lidar_link_width" value="0.003" />
<xacro:property name="lidar_link_len" value="0.2" />
<xacro:macro name="inertial_matrix" params="mass">
<inertial>
<mass value="${mass}" />
<inertia ixx="0.05" ixy="0.0" ixz="0.0" iyy="0.025" iyz="0.0" izz="0.05" />
</inertial>
</xacro:macro>
<joint name="crank_joint" type="fixed">
<parent link="base_link"/>
<child link="lidar_link"/>
<origin xyz="0 0 ${base_z_size + 0.3}" rpy="0 0 0"/>
</joint>
<link name="lidar_link" >
<visual>
<origin xyz="0 0 ${lidar_link_len/2}" rpy="0 0 0" />
<geometry>
<cylinder radius="${lidar_link_width}" length="${lidar_link_len}"/>
</geometry>
<material name="Blue" />
</visual>
<collision>
<origin xyz="0 0 ${lidar_link_len/2}" rpy="0 ${M_PI/2} 0" />
<geometry>
<cylinder radius="${lidar_link_width}" length="${lidar_link_len/2-0.1}"/>
</geometry>
</collision>
<xacro:inertial_matrix mass="0.05"/>
</link>
<xacro:include filename="$(find livox_laser_simulation)/urdf/livox_horizon.xacro"/>
<xacro:Livox_HORIZON name="livox"/>
<joint name="livox_base_joint" type="revolute">
<parent link="lidar_link"/>
<child link="livox_base"/>
<origin rpy="0 0 0"
xyz="0.05 0 ${lidar_link_len}"/>
<axis xyz="0 1 0" />
<dynamics damping="0.5" friction="0.06"/>
<limit effort="300" velocity="0.2" lower="-1.57" upper="1.57"/>
</joint>
<transmission name="simple_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="livox_base_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="foo_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Gazebo differentiate controller -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>$(arg robot_namespace)</robotNamespace>
<legacyModeNS>false</legacyModeNS>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<gazebo>
<plugin name="car_odom_publisher" filename="libgazebo_ros_p3d.so">
<alwaysOn>true</alwaysOn>
<updateRate>50.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>robuster_odom_gt</topicName>
<gaussianNoise>0.0</gaussianNoise>
<frameName>map</frameName>
</plugin>
</gazebo>
</robot>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment