<?xml version="1.0" encoding="utf-8"?>
<robot name="panda" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="lidar_type" value="$(env LIDAR_TYPE)"/>
<xacro:property name="camera_type" value="$(env CAMERA_TYPE)"/>
<link name="base_footprint"/>
<joint name="base_footprint_joint" type="fixed">
<origin
xyz="0 0 0.078"
rpy="0 0 0" />
<parent
link="base_footprint" />
<child
link="base_link" />
<axis
xyz="0 0 0" />
</joint>
<link name="base_link">
<inertial>
<origin
xyz="0.00335276342427124 -0.000388208958960666 0.136610457045616"
rpy="0 0 0" />
<mass
value="0.717467591182504" />
<inertia
ixx="0.0036960427951579"
ixy="7.83136539663561E-07"
ixz="-1.65638390817698E-07"
iyy="0.00309037867081111"
iyz="-1.34697711267945E-07"
izz="0.00356445158486582" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://robot_description/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://robot_description/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<!-- define wheel -->
<xacro:macro name="wheel" params="prefix *joint_origin *joint_axis">
<link name="${prefix}_wheel_link">
<inertial>
<origin
xyz="0 2.7728E-07 0.00017522"
rpy="0 0 0" />
<mass
value="0.87209" />
<inertia
ixx="0.001446"
ixy="0"
ixz="0"
iyy="0.001446"
iyz="1.7804E-06"
izz="0.0025711" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://robot_description/meshes/${prefix}_wheel_link.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://robot_description/meshes/${prefix}_wheel_link.STL" />
</geometry>
</collision>
</link>
<joint
name="${prefix}_wheel_joint"
type="continuous">
<xacro:insert_block name="joint_origin"/>
<xacro:insert_block name="joint_axis"/>
<parent
link="base_link" />
<child
link="${prefix}_wheel_link" />
</joint>
</xacro:macro>
<!-- instantiate 4 drive wheels -->
<xacro:wheel prefix="left_front">
<origin
xyz="0.128 0.15065 -4.5101E-05"
rpy="-1.5708 0 0" />
<axis xyz="0 0.0015825 1" />
</xacro:wheel>
<xacro:wheel prefix="left_rear">
<origin
xyz="-0.128 0.15065 -4.5101E-05"
rpy="-1.5708 0 0" />
<axis xyz="0 0.0015825 1" />
</xacro:wheel>
<xacro:wheel prefix="right_front">
<origin
xyz="0.128 -0.15065 -4.5101E-05"
rpy="-1.5708 0 3.1416" />
<axis xyz="0 -0.0015825 -1" />
</xacro:wheel>
<xacro:wheel prefix="right_rear">
<origin
xyz="-0.128 -0.15065 -4.5101E-05"
rpy="-1.5708 0 3.1416" />
<axis xyz="0 -0.0015825 -1" />
</xacro:wheel>
<!-- imu -->
<link name="imu"/>
<joint name="imu_joint" type="fixed">
<origin
xyz="-0.0015 0.0265 0.031895"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="imu" />
<axis
xyz="0 0 0" />
</joint>
<!-- define sonar -->
<xacro:macro name="sonar" params="suffix *joint_origin">
<link name="sonar${suffix}_link"/>
<joint name="sonar${suffix}_joint" type="fixed">
<xacro:insert_block name="joint_origin"/>
<parent
link="base_link" />
<child
link="sonar${suffix}_link" />
<axis
xyz="0 0 0" />
</joint>
</xacro:macro>
<!-- instantiate sonar -->
<xacro:sonar suffix="1">
<origin
xyz="0.203 0 0.042895"
rpy="0 0 0" />
</xacro:sonar>
<xacro:sonar suffix="2">
<origin
xyz="0 -0.113 0.074895"
rpy="0 0 -1.5708" />
</xacro:sonar>
<xacro:sonar suffix="3">
<origin
xyz="-0.203 0 0.042895"
rpy="0 0 3.1416" />
</xacro:sonar>
<xacro:sonar suffix="4">
<origin
xyz="0 0.113 0.074895"
rpy="0 0 1.5708" />
</xacro:sonar>
<xacro:macro name="lidar" params="name *joint_origin *joint_axis">
<link name="base_laser_link">
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://robot_description/meshes/${name}_link.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint name="base_laser_joint" type="fixed">
<xacro:insert_block name="joint_origin"/>
<parent
link="base_link" />
<child
link="base_laser_link" />
<xacro:insert_block name="joint_axis"/>
</joint>
</xacro:macro>
<xacro:if value="${lidar_type == 'rplidar'}">
<xacro:lidar name="rplidar">
<origin
xyz="0.012833 0 0.1509"
rpy="0 0 -3.1416" />
<axis
xyz="0 0 0" />
</xacro:lidar>
</xacro:if>
<xacro:if value="${lidar_type == 'rplidar_s2'}">
<xacro:lidar name="rplidar_s2">
<origin
xyz="0.002 0 0.5081"
rpy="0 0 -3.1416" />
<axis
xyz="0 0 0" />
</xacro:lidar>
</xacro:if>
<xacro:if value="${lidar_type in ['nvilidar', 'vp300']}">
<xacro:lidar name="nvilidar">
<origin
xyz="0.0155 0 0.5139"
rpy="0 0 0" />
<axis
xyz="0 0 0" />
</xacro:lidar>
</xacro:if>
<xacro:if value="${lidar_type == 'rslidar'}">
<xacro:lidar name="rslidar">
<origin
xyz="0.04 0 0.5194"
rpy="0 0 0" />
<axis
xyz="0 0 0" />
</xacro:lidar>
</xacro:if>
<xacro:if value="${camera_type == 'astras'}">
<link name="camera_link">
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://robot_description/meshes/camera_link.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint name="camera_joint" type="fixed">
<origin
xyz="0.1095 0 0.483945253357142"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="camera_link" />
<axis
xyz="0 0 0" />
</joint>
</xacro:if>
<xacro:if value="${camera_type == 'csi72'}">
<link name="base_camera_link">
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://robot_description/meshes/base_camera_link.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
</link>
<joint name="base_camera_joint" type="fixed">
<origin
xyz="0.11343 0 0.32923"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="base_camera_link" />
<axis
xyz="0 0 0" />
</joint>
</xacro:if>
</robot>