第二章、配置xacro文件
0.前言
roslaunch tianracer_description gazebo.launch
roslaunch tianracer_description display.launch
1.添加传动装置
<?xml version="1.0" encoding="utf-8"?>
<robot name="tianracer" xmlns:xacro="http://ros.org/wiki/xacro">
<link name="base_link">
</link>
<link name="chassis">
<inertial>
<origin
xyz="0.0623235722457065 0.0014584636628485 0.0350371599032402"
rpy="0 0 0" />
<mass
value="5" />
<inertia ixx="0.010609" ixy="0" ixz="0"
iyy="0.050409" iyz="0"
izz="0.05865" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh filename="package://tianracer_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://tianracer_description/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<joint name="base_link_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link"/>
<child link="chassis" />
</joint>
<link
name="left_steering_hinge">
<inertial>
<origin
xyz="0.00160901052986848 0.00421500740928921 0.000999991873067492"
rpy="0 0 0" />
<mass
value="0.34" />
<inertia
ixx="4E-06"
ixy="0"
ixz="0"
iyy="4E-06"
iyz="0"
izz="4E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/left_steering_hinge.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://tianracer_description/meshes/left_steering_hinge.STL" />
</geometry>
</collision>
</link>
<joint
name="left_steering_hinge_joint"
type="revolute">
<origin
xyz="0.1237 0.070647 0.0235"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="left_steering_hinge" />
<axis
xyz="0 0 1" />
<limit
lower="-0.6"
upper="0.6"
effort="10"
velocity="1000" />
</joint>
<link
name="left_front_wheel">
<inertial>
<origin
xyz="-1.16652756898539E-10 0.000722301233977055 -0.000982991824011559"
rpy="0 0 0" />
<mass
value="0.7" />
<inertia ixx="0.00026046" ixy="0" ixz="0"
iyy="0.00026046" iyz="0"
izz="0.00041226" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/left_front_wheel.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://tianracer_description/meshes/left_front_wheel.STL" />
</geometry>
</collision>
</link>
<joint
name="left_front_wheel_joint"
type="continuous">
<origin
xyz="0 0.015649 0"
rpy="0 0 0" />
<parent
link="left_steering_hinge" />
<child
link="left_front_wheel" />
<axis
xyz="0 1 0" />
</joint>
<link
name="right_steering_hinge">
<inertial>
<origin
xyz="0.00160901052986852 -0.00421500740928916 0.00100000812693248"
rpy="0 0 0" />
<mass
value="0.34" />
<inertia
ixx="4E-06"
ixy="0"
ixz="0"
iyy="4E-06"
iyz="0"
izz="4E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/right_steering_hinge.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://tianracer_description/meshes/right_steering_hinge.STL" />
</geometry>
</collision>
</link>
<joint
name="right_steering_hinge_joint"
type="revolute">
<origin
xyz="0.12626 -0.065953 0.0235"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="right_steering_hinge" />
<axis
xyz="0 0 1" />
<limit
lower="-0.6"
upper="0.6"
effort="10"
velocity="1000" />
</joint>
<link
name="right_front_wheel">
<inertial>
<origin
xyz="1.16652479342783E-10 -0.000722301233976874 -0.000982991824011684"
rpy="0 0 0" />
<mass
value="0.7" />
<inertia ixx="0.00026046" ixy="0" ixz="0"
iyy="0.00026046" iyz="0"
izz="0.00041226" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/right_front_wheel.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://tianracer_description/meshes/right_front_wheel.STL" />
</geometry>
</collision>
</link>
<joint
name="right_front_wheel_joint"
type="continuous">
<origin
xyz="0 -0.015649 0"
rpy="0 0 0" />
<parent
link="right_steering_hinge" />
<child
link="right_front_wheel" />
<axis
xyz="0 1 0" />
</joint>
<link
name="left_rear_wheel">
<inertial>
<origin
xyz="-6.22009417952651E-06 0.000722301233977513 1.58299866985546E-05"
rpy="0 0 0" />
<mass
value="0.7" />
<inertia ixx="0.00026046" ixy="0" ixz="0"
iyy="0.00026046" iyz="0"
izz="0.00041226" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/left_rear_wheel.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://tianracer_description/meshes/left_rear_wheel.STL" />
</geometry>
</collision>
</link>
<joint
name="left_rear_wheel_joint"
type="continuous">
<origin
xyz="-0.12626 0.081602 0.0225"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="left_rear_wheel" />
<axis
xyz="0 1 0" />
</joint>
<link
name="right_rear_wheel">
<inertial>
<origin
xyz="5.49312575473526E-06 -0.000722301233977277 1.60966959317256E-05"
rpy="0 0 0" />
<mass
value="0.7" />
<inertia ixx="0.00026046" ixy="0" ixz="0"
iyy="0.00026046" iyz="0"
izz="0.00041226" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh filename="package://tianracer_description/meshes/right_rear_wheel.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://tianracer_description/meshes/right_rear_wheel.STL" />
</geometry>
</collision>
</link>
<joint
name="right_rear_wheel_joint"
type="continuous">
<origin
xyz="-0.1237 -0.086296 0.0225"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="right_rear_wheel" />
<axis
xyz="0 1 0" />
</joint>
<link
name="lidar">
<inertial>
<origin
xyz="-0.0120919804823413 0.0023160815953297 -0.0191850779635995"
rpy="0 0 0" />
<mass
value="0.0792224121739075" />
<inertia
ixx="2.10579541640659E-05"
ixy="-1.189626176555E-07"
ixz="4.23690141563745E-07"
iyy="2.51190032657276E-05"
iyz="-7.86831091483644E-09"
izz="4.38241306407012E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/lidar.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://tianracer_description/meshes/lidar.STL" />
</geometry>
</collision>
</link>
<joint
name="lidar_joint"
type="fixed">
<origin
xyz="0.093603 -8.284E-05 0.12377"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="lidar" />
<axis
xyz="0 0 0" />
</joint>
<link
name="camera">
<inertial>
<origin
xyz="-0.00831465204525364 0.000297862545499916 -0.000809694900417546"
rpy="0 0 0" />
<mass
value="0.0203878842392581" />
<inertia
ixx="4.0787812214101E-06"
ixy="-1.28709200468823E-08"
ixz="-1.65865223773842E-08"
iyy="3.17565570823081E-06"
iyz="-1.52713816393124E-08"
izz="2.98536150732633E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/camera.STL" />
</geometry>
<material
name="">
<color
rgba="0.43921568627451 0.43921568627451 0.43921568627451 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/camera.STL" />
</geometry>
</collision>
</link>
<joint
name="camera_joint"
type="fixed">
<origin
xyz="0.14851 0.0022137 0.0975"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="camera" />
<axis
xyz="0 0 0" />
</joint>
<link
name="real_sense">
<inertial>
<origin
xyz="-0.00975078931607951 0.00306064913353049 -7.04374991291334E-05"
rpy="0 0 0" />
<mass
value="0.103311749598955" />
<inertia
ixx="7.35323632954531E-05"
ixy="3.0437488683846E-06"
ixz="2.08538534427428E-08"
iyy="7.40427481540393E-06"
iyz="-1.93018760531168E-08"
izz="7.2832884533889E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/real_sense.STL" />
</geometry>
<material
name="">
<color
rgba="0.666666666666667 0.698039215686274 0.768627450980392 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://tianracer_description/meshes/real_sense.STL" />
</geometry>
</collision>
</link>
<joint
name="real_sense_joint"
type="fixed">
<origin
xyz="0.19864 0.0038046 0.052021"
rpy="0 0 0" />
<parent
link="base_link" />
<child
link="real_sense" />
<axis
xyz="0 0 0" />
</joint>
<?xml version="1.0" encoding="utf-8"?>
<robot name="tianracer" xmlns:xacro="http://ros.org/wiki/xacro">
以及一些惯性参数的修改。
本次项目做的是基于twist消息的阿克曼转向移动机器人,为实现该机器人的运动学,我们给两个后轮以及连接两个前轮的steer添加传动装置。为使用ROS控制驱动机器人,需要在模型中加入transmission元素,将传动装置与joint绑定。
<transmission name="right_steering_hinge_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_steering_hinge_joint" >
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="right_steering_hinge_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
<motorTorqueConstant>100</motorTorqueConstant>
</actuator>
</transmission>
<transmission name="left_steering_hinge_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_steering_hinge_joint" >
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="left_steering_hinge_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
<motorTorqueConstant>100</motorTorqueConstant>
</actuator>
</transmission>
<transmission name="right_rear_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="right_rear_wheel_joint" >
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="right_rear_wheel_joint_motor">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="left_rear_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="left_rear_wheel_joint" >
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="left_rear_wheel_joint_motor">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
2.添加插件
添加gazebo插件
[gazebo官网] http://gazebosim.org/tutorials/?tut=ros_urdf
<gazebo reference="chassis">
<mu1 value="0.0"/>
<mu2 value="0.0"/>
<kp value="10000000.0" />
<kd value="1.0" />
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="left_steering_hinge">
<mu1 value="2.0"/>
<mu2 value="2.0"/>
<kp value="10000000.0" />
<kd value="1.0" />
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="left_rear_wheel">
<mu1 value="2.0"/>
<mu2 value="2.0"/>
<kp value="10000000.0" />
<kd value="1.0" />
<fdir1 value="1 0 0"/>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="right_steering_hinge">
<mu1 value="2.0"/>
<mu2 value="2.0"/>
<kp value="10000000.0" />
<kd value="1.0" />
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="right_rear_wheel">
<mu1 value="2.0"/>
<mu2 value="2.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="2.0"/>
<mu2 value="2.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="2.0"/>
<mu2 value="2.0"/>
<kp value="10000000.0" />
<kd value="1.0" />
<fdir1 value="0 0 1"/>
<material>Gazebo/Black</material>
</gazebo>
添加ros_control插件
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/tianracer</robotNamespace>
<robotParam>robot_description</robotParam>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
<gazebo>
<plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
<jointName>left_rear_wheel_joint, right_rear_wheel_joint, left_steering_hinge_joint, right_steering_hinge_joint, right_front_wheel_joint,left_ front_wheel_joint</jointName>
<updateRate>50.0</updateRate>
<robotNamespace>/tianracer</robotNamespace>
<alwaysOn>true</alwaysOn>
</plugin>
</gazebo>
<!-- hokuyo -->
<xacro:unless value="$(optenv DISABLE_GAZEBO_LASER false)">
<gazebo reference="lidar">
<material>Gazebo/Grey</material>
<sensor type="ray" name="hokuyo_sensor">
<pose>0 0 0.0124 0 0 0</pose>
<visualize>false</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 name="gazebo_ros_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/scan</topicName>
<frameName>lidar</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:unless>
<!-- camera -->
<gazebo reference="camera">
<material>Gazebo/Grey</material>
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>rrbot/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
<gazebo reference="real_sense">
<sensor type="depth" name="real_sense">
<always_on>true</always_on>
<update_rate>20.0</update_rate>
<camera>
<horizontal_fov>${60.0*3.14/180.0}</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>8.0</far>
</clip>
</camera>
<plugin name="kinect_real_sense_controller" filename="libgazebo_ros_openni_kinect.so">
<cameraName>real_sense</cameraName>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<imageTopicName>rgb/image_raw</imageTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<frameName>real_sense</frameName>
<baseline>0.1</baseline>
<distortion_k1>0.0</distortion_k1>
<distortion_k2>0.0</distortion_k2>
<distortion_k3>0.0</distortion_k3>
<distortion_t1>0.0</distortion_t1>
<distortion_t2>0.0</distortion_t2>
<pointCloudCutoff>0.4</pointCloudCutoff>
</plugin>
</sensor>
</gazebo>
<xacro:include filename="$(find tianracer_description)/urdf/tianracer.gazebo" />
小结
参考资料
1.古月老师的<<ROS机器人开发实践>>
2.从零开始自动驾驶:https://www.bilibili.com/video/BV1ZJ41187tS?spm_id_from=333.999.0.0
评论(2)
您还未登录,请登录后发表或查看评论