mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
494 lines
16 KiB
XML
494 lines
16 KiB
XML
<?xml version="1.0" ?>
|
|
<!-- =================================================================================== -->
|
|
<!-- | This document was autogenerated by xacro from racecar.xacro | -->
|
|
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
|
<!-- =================================================================================== -->
|
|
<robot name="racecar" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
<!-- inertial parameter macros -->
|
|
<!-- geometry macros -->
|
|
<!-- transmission macros -->
|
|
<!-- Add chassis and it's inertia link -->
|
|
<link name="base_link">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<mass value=".1"/>
|
|
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="chassis">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<mass value=".1"/>
|
|
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="meshes/chassis.STL"/>
|
|
</geometry>
|
|
<material name="blue"/>
|
|
</visual>
|
|
</link>
|
|
<joint name="base_link_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0.05"/>
|
|
<parent link="base_link"/>
|
|
<child link="chassis"/>
|
|
</joint>
|
|
<link name="chassis_inertia">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.1477 0 0"/>
|
|
<mass value="4.0"/>
|
|
<inertia ixx="0.010609" ixy="0" ixz="0" iyy="0.050409" iyz="0" izz="0.05865"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="chassis_inertia_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="chassis"/>
|
|
<child link="chassis_inertia"/>
|
|
</joint>
|
|
<!-- Add the left rear wheel with its joints and tranmissions -->
|
|
<link name="left_rear_wheel">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
|
|
<mass value="0.34055"/>
|
|
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="meshes/left_rear_wheel.obj"/>
|
|
</geometry>
|
|
<material name="white"/>
|
|
</visual>
|
|
<collision>
|
|
robot
|
|
|
|
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
|
|
<geometry>
|
|
<cylinder length="0.045" radius="0.05"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="left_rear_wheel_joint" type="continuous">
|
|
<origin rpy="1.5708 0 0" xyz="0 0.1 0"/>
|
|
<parent link="chassis"/>
|
|
<child link="left_rear_wheel"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="10" velocity="100"/>
|
|
</joint>
|
|
<transmission name="left_rear_wheel_transmission" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="left_rear_wheel_joint">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="left_rear_wheel_motor">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<!-- Add the right rear wheel with its joints and tranmissions -->
|
|
<link name="right_rear_wheel">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
|
|
<mass value="0.34055"/>
|
|
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="meshes/right_rear_wheel.obj"/>
|
|
</geometry>
|
|
<material name="white"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
|
|
<geometry>
|
|
<cylinder length="0.045" radius="0.05"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="right_rear_wheel_joint" type="continuous">
|
|
<origin rpy="1.5708 0 0" xyz="0 -0.1 0"/>
|
|
<parent link="chassis"/>
|
|
<child link="right_rear_wheel"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="10" velocity="100"/>
|
|
</joint>
|
|
<transmission name="right_rear_wheel_transmission" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="right_rear_wheel_joint">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="right_rear_wheel_motor">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<!-- Add the left steering hinge with its joints and tranmissions -->
|
|
<link name="left_steering_hinge">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<mass value="0.100"/>
|
|
<inertia ixx="4E-06" ixy="0" ixz="0" iyy="4E-06" iyz="0" izz="4E-06"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="meshes/left_steering_hinge.STL"/>
|
|
</geometry>
|
|
<material name="grey"/>
|
|
</visual>
|
|
</link>
|
|
<joint name="left_steering_hinge_joint" type="revolute">
|
|
<origin rpy="0 1.5708 0" xyz="0.325 0.1 0"/>
|
|
<parent link="chassis"/>
|
|
<child link="left_steering_hinge"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="10" lower="-1.0" upper="1.0" velocity="100"/>
|
|
</joint>
|
|
<transmission name="left_steering_hinge_transmission" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="left_steering_hinge_joint">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="left_steering_hinge_motor">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<!-- Add the right steering hinge with its joints and tranmissions -->
|
|
<link name="right_steering_hinge">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<mass value="0.100"/>
|
|
<inertia ixx="4E-06" ixy="0" ixz="0" iyy="4E-06" iyz="0" izz="4E-06"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="meshes/right_steering_hinge.STL"/>
|
|
</geometry>
|
|
<material name="grey"/>
|
|
</visual>
|
|
</link>
|
|
<joint name="right_steering_hinge_joint" type="continuous">
|
|
<origin rpy="0 1.5708 0" xyz="0.325 -0.1 0"/>
|
|
<parent link="chassis"/>
|
|
<child link="right_steering_hinge"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="10" lower="-1.0" upper="1.0" velocity="100"/>
|
|
</joint>
|
|
<transmission name="right_steering_hinge_transmission" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="right_steering_hinge_joint">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="right_steering_hinge_motor">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<!-- Add the left front wheel with its joints and tranmissions -->
|
|
<link name="left_front_wheel">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
|
|
<mass value="0.34055"/>
|
|
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="meshes/left_front_wheel.obj"/>
|
|
</geometry>
|
|
<material name="white"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 -0.0225"/>
|
|
<geometry>
|
|
<cylinder length="0.045" radius="0.05"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="left_front_wheel_joint" type="continuous">
|
|
<origin rpy="1.5708 0 0" xyz="0 0 0"/>
|
|
<parent link="left_steering_hinge"/>
|
|
<child link="left_front_wheel"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="10" velocity="100"/>
|
|
</joint>
|
|
<transmission name="left_front_wheel_transmission" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="left_front_wheel_joint">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="left_front_wheel_motor">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<!-- Add the left front wheel with its joints and tranmissions -->
|
|
<link name="right_front_wheel">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
|
|
<mass value="0.34055"/>
|
|
<inertia ixx="0.00026046" ixy="0" ixz="0" iyy="0.00026046" iyz="0" izz="0.00041226"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="meshes/right_front_wheel.obj"/>
|
|
</geometry>
|
|
<material name="white"/>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0.0225"/>
|
|
<geometry>
|
|
<cylinder length="0.045" radius="0.05"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="right_front_wheel_joint" type="continuous">
|
|
<origin rpy="1.5708 0 0" xyz="0 0 0"/>
|
|
<parent link="right_steering_hinge"/>
|
|
<child link="right_front_wheel"/>
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="10" velocity="100"/>
|
|
</joint>
|
|
<transmission name="right_front_wheel_transmission" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="right_front_wheel_joint">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="right_front_wheel_motor">
|
|
<hardwareInterface>EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
<!-- Add Hokuyo laser scanner -->
|
|
<link name="laser">
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<mass value="0.130"/>
|
|
<inertia ixx="4E-06" ixy="0" ixz="0" iyy="4E-06" iyz="0" izz="4E-06"/>
|
|
</inertial>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.1 0.1 0.1"/>
|
|
</geometry>
|
|
</collision>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="meshes/hokuyo.obj"/>
|
|
<material name="grey"/>
|
|
</geometry>
|
|
</visual>
|
|
</link>
|
|
<joint name="hokuyo_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0.265 0.0 0.075"/>
|
|
<parent link="chassis"/>
|
|
<child link="laser"/>
|
|
<axis xyz="0 0 1"/>
|
|
</joint>
|
|
<!-- zed camera -->
|
|
<link name="zed_camera_link">
|
|
<inertial>
|
|
<mass value="1e-5"/>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
|
|
</inertial>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.033 0.175 0.030"/>
|
|
</geometry>
|
|
</collision>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.033 0.175 0.030"/>
|
|
</geometry>
|
|
<material name="red"/>
|
|
</visual>
|
|
</link>
|
|
<joint name="zed_camera_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0.390 0 0.04"/>
|
|
<parent link="chassis"/>
|
|
<child link="zed_camera_link"/>
|
|
<axis xyz="0 0 1"/>
|
|
<!-- <limit lower="0.0" upper="0.0" effort="0.0" velocity="0.0" /> -->
|
|
</joint>
|
|
<!-- zed camera lenses -->
|
|
<!-- It seems these have to have a non-zero mass to have a camera attached? -->
|
|
<link name="camera_link">
|
|
<!-- this needs to match the name in zed_wrapper/zed_tf.launch -->
|
|
<inertial>
|
|
<mass value="1e-5"/>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="zed_camera_right_link">
|
|
<inertial>
|
|
<mass value="1e-5"/>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
|
|
</inertial>
|
|
</link>
|
|
<joint name="zed_camera_left_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0.06 0"/>
|
|
<parent link="zed_camera_link"/>
|
|
<child link="camera_link"/>
|
|
<axis xyz="0 0 1"/>
|
|
</joint>
|
|
<joint name="zed_camera_right_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 -0.06 0"/>
|
|
<parent link="zed_camera_link"/>
|
|
<child link="zed_camera_right_link"/>
|
|
<axis xyz="0 0 1"/>
|
|
</joint>
|
|
<!-- Add the remaining xacros -->
|
|
<!-- Gazebo references -->
|
|
<gazebo reference="chassis">
|
|
<mu1 value="0.0"/>
|
|
<mu2 value="0.0"/>
|
|
<kp value="10000000.0"/>
|
|
<kd value="1.0"/>
|
|
<material>Gazebo/Blue</material>
|
|
</gazebo>
|
|
<gazebo reference="left_rear_wheel">
|
|
<mu1 value="1.0"/>
|
|
<mu2 value="1.0"/>
|
|
<kp value="10000000.0"/>
|
|
<kd value="1.0"/>
|
|
<fdir1 value="1 0 0"/>
|
|
<material>Gazebo/Black</material>
|
|
</gazebo>
|
|
<gazebo reference="right_rear_wheel">
|
|
<mu1 value="1.0"/>
|
|
<mu2 value="1.0"/>
|
|
<kp value="10000000.0"/>
|
|
<kd value="1.0"/>
|
|
<fdir1 value="1 0 0"/>
|
|
<material>Gazebo/Black</material>
|
|
</gazebo>
|
|
<gazebo reference="left_front_wheel">
|
|
<mu1 value="1.0"/>
|
|
<mu2 value="1.0"/>
|
|
<kp value="10000000.0"/>
|
|
<kd value="1.0"/>
|
|
<fdir1 value="0 0 1"/>
|
|
<material>Gazebo/Black</material>
|
|
</gazebo>
|
|
<gazebo reference="right_front_wheel">
|
|
<mu1 value="1.0"/>
|
|
<mu2 value="1.0"/>
|
|
<kp value="10000000.0"/>
|
|
<kd value="1.0"/>
|
|
<fdir1 value="0 0 1"/>
|
|
<material>Gazebo/Black</material>
|
|
</gazebo>
|
|
<!-- Gazebo plugins -->
|
|
<gazebo>
|
|
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
|
|
<robotNamespace>/racecar</robotNamespace>
|
|
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
|
</plugin>
|
|
</gazebo>
|
|
<gazebo reference="laser">
|
|
<material>Gazebo/Grey</material>
|
|
<sensor name="hokuyo_sensor" type="ray">
|
|
<pose>0 0 0.0124 0 0 0</pose>
|
|
<visualize>true</visualize>
|
|
<update_rate>40</update_rate>
|
|
<ray>
|
|
<scan>
|
|
<horizontal>
|
|
<samples>1081</samples>
|
|
<resolution>1</resolution>
|
|
<min_angle>-2.3561944902</min_angle>
|
|
<max_angle>2.3561944902</max_angle>
|
|
</horizontal>
|
|
</scan>
|
|
<range>
|
|
<min>0.1</min>
|
|
<max>10.0</max>
|
|
<resolution>0.01</resolution>
|
|
</range>
|
|
<noise>
|
|
<mean>0.0</mean>
|
|
<stddev>0.01</stddev>
|
|
</noise>
|
|
</ray>
|
|
<plugin filename="libgazebo_ros_laser.so" name="gazebo_ros_hokuyo_controller">
|
|
<topicName>/scan</topicName>
|
|
<frameName>laser</frameName>
|
|
</plugin>
|
|
</sensor>
|
|
</gazebo>
|
|
<gazebo reference="camera_link">
|
|
<sensor name="zed_camera_left_sensor" type="camera">
|
|
<update_rate>30.0</update_rate>
|
|
<!-- math.atan(320 / 687.8065795898438) * 2 -->
|
|
<camera name="zed_camera_left_camera">
|
|
<horizontal_fov>0.8709216071359963</horizontal_fov>
|
|
<image>
|
|
<width>640</width>
|
|
<height>480</height>
|
|
<format>B8G8R8</format>
|
|
</image>
|
|
<clip>
|
|
<near>0.02</near>
|
|
<far>300</far>
|
|
</clip>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0.0</mean>
|
|
<stddev>0.007</stddev>
|
|
</noise>
|
|
</camera>
|
|
<plugin filename="libgazebo_ros_camera.so" name="camera_controller">
|
|
<alwaysOn>true</alwaysOn>
|
|
<updateRate>30.0</updateRate>
|
|
<cameraName>/camera/zed</cameraName>
|
|
<imageTopicName>rgb/image_rect_color</imageTopicName>
|
|
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
|
|
<frameName>camera_link</frameName>
|
|
<hackBaseline>0</hackBaseline>
|
|
<!-- set this to 0.12 for the second camera -->
|
|
<distortionK1>0.0</distortionK1>
|
|
<distortionK2>0.0</distortionK2>
|
|
<distortionK3>0.0</distortionK3>
|
|
<distortionT1>0.0</distortionT1>
|
|
<distortionT2>0.0</distortionT2>
|
|
</plugin>
|
|
</sensor>
|
|
</gazebo>
|
|
<material name="white">
|
|
<color rgba="1. 1. 1. 1.0"/>
|
|
</material>
|
|
<material name="black">
|
|
<color rgba="0. 0. 0. 1.0"/>
|
|
</material>
|
|
<material name="blue">
|
|
<color rgba="0.0 0.0 0.8 1.0"/>
|
|
</material>
|
|
<material name="green">
|
|
<color rgba="0.0 0.8 0.0 1.0"/>
|
|
</material>
|
|
<material name="grey">
|
|
<color rgba="0.2 0.2 0.2 1.0"/>
|
|
</material>
|
|
<material name="orange">
|
|
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
|
|
</material>
|
|
<material name="brown">
|
|
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
|
|
</material>
|
|
<material name="red">
|
|
<color rgba="0.8 0.0 0.0 1.0"/>
|
|
</material>
|
|
</robot>
|
|
|