赞
踩
创建一个机器人,包含本体、控制器、传感器。在gazebo物理引擎中加载真实世界模型,在rviz通过各种插件查看状态。
首先,看一下整体的项目截图
urdf02_gazebo功能包下面有/config文件夹放置rviz的配置文件,/launch文件夹放置启动文件,/world文件夹放置gazebo的物理世界模型,/xacro文件夹放机器人模型文件,分别在/xacro当前目录下放机器人本体的xacro文件,以及在/xacro/gazebo文件夹下放控制和传感器文件,最终所有的xacro文件都集成进/xacro/car_gazebo.xacro中,即car_gazebo.xacro集成了机器人本体、控制器、传感器,值得注意的是,xacro集成了这么多个不同的 xacro文件,其本质上是将所有的xacro文件复制到一块的,所以不同的xacro文件可写同一个name,反正最终都会复制集成到同一个xacro文件下,car_gazebo.xacro如下所示。
<robot name="car" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="head.xacro" />
<xacro:include filename="base.xacro" />
<xacro:include filename="camera.xacro" />
<xacro:include filename="laser.xacro" />
<xacro:include filename="gazebo/move.xacro" />
<xacro:include filename="gazebo/laser_sensor.xacro" />
<xacro:include filename="gazebo/camera_sensor.xacro" />
</robot>
其中第一个head.xacro是计算inertial惯性矩阵的,因为gazebo是需要考虑真实物理引擎的,所以head.xacro里封装了宏(相当于函数,包含函数名和参数),每个宏函数都是标准的物体,如球,圆柱等,传参传入质量,长宽高半径等,宏函数就会自动计算惯性矩阵,宏函数在机器人本体设计直接调用即可。
<robot name="base" xmlns:xacro="http://wiki.ros.org/xacro"> <!-- Macro for inertia matrix head.xacro --> <xacro:macro name="sphere_inertial_matrix" params="m r"> <inertial> <mass value="${m}" /> <inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0" iyy="${2*m*r*r/5}" iyz="0" izz="${2*m*r*r/5}" /> </inertial> </xacro:macro> <xacro:macro name="cylinder_inertial_matrix" params="m r h"> <inertial> <mass value="${m}" /> <inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0" iyy="${m*(3*r*r+h*h)/12}" iyz = "0" izz="${m*r*r/2}" /> </inertial> </xacro:macro> <xacro:macro name="Box_inertial_matrix" params="m l w h"> <inertial> <mass value="${m}" /> <inertia ixx="${m*(h*h + l*l)/12}" ixy = "0" ixz = "0" iyy="${m*(w*w + l*l)/12}" iyz= "0" izz="${m*(w*w + h*h)/12}" /> </inertial> </xacro:macro> </robot>
以下是各个机器人本体连杆link的设计,包括小车底盘、摄像头、雷达,其中的inertial惯性矩阵用到了head.xacro的宏函数。
<!-- 使用 xacro 优化 URDF 版的小车底盘实现: base.xacro 实现思路: 1.将一些常量、变量封装为 xacro:property 比如:PI 值、小车底盘半径、离地间距、车轮半径、宽度 .... 2.使用 宏 封装驱动轮以及支撑轮实现,调用相关宏生成驱动轮与支撑轮 --> <!-- 根标签,必须声明 xmlns:xacro --> <robot name="my_base" xmlns:xacro="http://www.ros.org/wiki/xacro"> <!-- 封装变量、常量 --> <!-- PI 值设置精度需要高一些,否则后续车轮翻转量计算时,可能会出现肉眼不能察觉的车轮倾斜,从而导致模型抖动 --> <xacro:property name="PI" value="3.1415926"/> <!-- 宏:黑色设置 --> <material name="black"> <color rgba="0.0 0.0 0.0 1.0" /> </material> <!-- 底盘属性 --> <xacro:property name="base_footprint_radius" value="0.001" /> <!-- base_footprint 半径 --> <xacro:property name="base_link_radius" value="0.1" /> <!-- base_link 半径 --> <xacro:property name="base_link_length" value="0.08" /> <!-- base_link 长 --> <xacro:property name="earth_space" value="0.015" /> <!-- 离地间距 --> <xacro:property name="base_link_m" value="0.5" /> <!-- 质量 --> <!-- 底盘 --> <link name="base_footprint"> <visual> <geometry> <sphere radius="${base_footprint_radius}" /> </geometry> </visual> </link> <link name="base_link"> <visual> <geometry> <cylinder radius="${base_link_radius}" length="${base_link_length}" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0" /> <material name="yellow"> <color rgba="0.5 0.3 0.0 0.5" /> </material> </visual> <collision> <geometry> <cylinder radius="${base_link_radius}" length="${base_link_length}" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0" /> </collision> <xacro:cylinder_inertial_matrix m="${base_link_m}" r="${base_link_radius}" h="${base_link_length}" /> </link> <joint name="base_link2base_footprint" type="fixed"> <parent link="base_footprint" /> <child link="base_link" /> <origin xyz="0 0 ${earth_space + base_link_length / 2 }" /> </joint> <gazebo reference="base_link"> <material>Gazebo/Yellow</material> </gazebo> <!-- 驱动轮 --> <!-- 驱动轮属性 --> <xacro:property name="wheel_radius" value="0.0325" /><!-- 半径 --> <xacro:property name="wheel_length" value="0.015" /><!-- 宽度 --> <xacro:property name="wheel_m" value="0.05" /> <!-- 质量 --> <!-- 驱动轮宏实现 --> <xacro:macro name="add_wheels" params="name flag"> <link name="${name}_wheel"> <visual> <geometry> <cylinder radius="${wheel_radius}" length="${wheel_length}" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" /> <material name="black" /> </visual> <collision> <geometry> <cylinder radius="${wheel_radius}" length="${wheel_length}" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" /> </collision> <xacro:cylinder_inertial_matrix m="${wheel_m}" r="${wheel_radius}" h="${wheel_length}" /> </link> <joint name="${name}_wheel2base_link" type="continuous"> <parent link="base_link" /> <child link="${name}_wheel" /> <origin xyz="0 ${flag * base_link_radius} ${-(earth_space + base_link_length / 2 - wheel_radius) }" /> <axis xyz="0 1 0" /> </joint> <gazebo reference="${name}_wheel"> <material>Gazebo/Red</material> </gazebo> </xacro:macro> <xacro:add_wheels name="left" flag="1" /> <xacro:add_wheels name="right" flag="-1" /> <!-- 支撑轮 --> <!-- 支撑轮属性 --> <xacro:property name="support_wheel_radius" value="0.0075" /> <!-- 支撑轮半径 --> <xacro:property name="support_wheel_m" value="0.03" /> <!-- 质量 --> <!-- 支撑轮宏 --> <xacro:macro name="add_support_wheel" params="name flag" > <link name="${name}_wheel"> <visual> <geometry> <sphere radius="${support_wheel_radius}" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0" /> <material name="black" /> </visual> <collision> <geometry> <sphere radius="${support_wheel_radius}" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0" /> </collision> <xacro:sphere_inertial_matrix m="${support_wheel_m}" r="${support_wheel_radius}" /> </link> <joint name="${name}_wheel2base_link" type="continuous"> <parent link="base_link" /> <child link="${name}_wheel" /> <origin xyz="${flag * (base_link_radius - support_wheel_radius)} 0 ${-(base_link_length / 2 + earth_space / 2)}" /> <axis xyz="1 1 1" /> </joint> <gazebo reference="${name}_wheel"> <material>Gazebo/Red</material> </gazebo> </xacro:macro> <xacro:add_support_wheel name="front" flag="1" /> <xacro:add_support_wheel name="back" flag="-1" /> </robot>
<!-- 摄像头相关的 xacro 文件 camera.xacro --> <robot name="my_camera" xmlns:xacro="http://wiki.ros.org/xacro"> <!-- 摄像头属性 --> <xacro:property name="camera_length" value="0.01" /> <!-- 摄像头长度(x) --> <xacro:property name="camera_width" value="0.025" /> <!-- 摄像头宽度(y) --> <xacro:property name="camera_height" value="0.025" /> <!-- 摄像头高度(z) --> <xacro:property name="camera_x" value="0.08" /> <!-- 摄像头安装的x坐标 --> <xacro:property name="camera_y" value="0.0" /> <!-- 摄像头安装的y坐标 --> <xacro:property name="camera_z" value="${base_link_length / 2 + camera_height / 2}" /> <!-- 摄像头安装的z坐标:底盘高度 / 2 + 摄像头高度 / 2 --> <xacro:property name="camera_m" value="0.01" /> <!-- 摄像头质量 --> <!-- 摄像头关节以及link --> <link name="camera"> <visual> <geometry> <box size="${camera_length} ${camera_width} ${camera_height}" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> <material name="black" /> </visual> <collision> <geometry> <box size="${camera_length} ${camera_width} ${camera_height}" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> </collision> <xacro:Box_inertial_matrix m="${camera_m}" l="${camera_length}" w="${camera_width}" h="${camera_height}" /> </link> <joint name="camera2base_link" type="fixed"> <parent link="base_link" /> <child link="camera" /> <origin xyz="${camera_x} ${camera_y} ${camera_z}" /> </joint> <gazebo reference="camera"> <material>Gazebo/Blue</material> </gazebo> </robot>
<!-- 小车底盘添加雷达 laser.xacro --> <robot name="my_laser" xmlns:xacro="http://wiki.ros.org/xacro"> <!-- 雷达支架 --> <xacro:property name="support_length" value="0.15" /> <!-- 支架长度 --> <xacro:property name="support_radius" value="0.01" /> <!-- 支架半径 --> <xacro:property name="support_x" value="0.0" /> <!-- 支架安装的x坐标 --> <xacro:property name="support_y" value="0.0" /> <!-- 支架安装的y坐标 --> <xacro:property name="support_z" value="${base_link_length / 2 + support_length / 2}" /> <!-- 支架安装的z坐标:底盘高度 / 2 + 支架高度 / 2 --> <xacro:property name="support_m" value="0.02" /> <!-- 支架质量 --> <link name="support"> <visual> <geometry> <cylinder radius="${support_radius}" length="${support_length}" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> <material name="red"> <color rgba="0.8 0.2 0.0 0.8" /> </material> </visual> <collision> <geometry> <cylinder radius="${support_radius}" length="${support_length}" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> </collision> <xacro:cylinder_inertial_matrix m="${support_m}" r="${support_radius}" h="${support_length}" /> </link> <joint name="support2base_link" type="fixed"> <parent link="base_link" /> <child link="support" /> <origin xyz="${support_x} ${support_y} ${support_z}" /> </joint> <gazebo reference="support"> <material>Gazebo/White</material> </gazebo> <!-- 雷达属性 --> <xacro:property name="laser_length" value="0.05" /> <!-- 雷达长度 --> <xacro:property name="laser_radius" value="0.03" /> <!-- 雷达半径 --> <xacro:property name="laser_x" value="0.0" /> <!-- 雷达安装的x坐标 --> <xacro:property name="laser_y" value="0.0" /> <!-- 雷达安装的y坐标 --> <xacro:property name="laser_z" value="${support_length / 2 + laser_length / 2}" /> <!-- 雷达安装的z坐标:支架高度 / 2 + 雷达高度 / 2 --> <xacro:property name="laser_m" value="0.1" /> <!-- 雷达质量 --> <!-- 雷达关节以及link --> <link name="laser"> <visual> <geometry> <cylinder radius="${laser_radius}" length="${laser_length}" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> <material name="black" /> </visual> <collision> <geometry> <cylinder radius="${laser_radius}" length="${laser_length}" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> </collision> <xacro:cylinder_inertial_matrix m="${laser_m}" r="${laser_radius}" h="${laser_length}" /> </link> <joint name="laser2support" type="fixed"> <parent link="support" /> <child link="laser" /> <origin xyz="${laser_x} ${laser_y} ${laser_z}" /> </joint> <gazebo reference="laser"> <material>Gazebo/Black</material> </gazebo> </robot>
以上是机器人本体的连杆link部件设计,那么小车还需要控制器还有上面的传感器真实引用,关于这部分内容我放在了/gazebo文件下。
控制器也是通过xacro文件实现,小车动起来主要是通过joint关节传动,比如小车左轮与地盘连接的joint关节,控制关节转动即可,由于小车有两个驱动轮,所以joint驱动也封装成宏函数来实现。
<robot name="my_car_move" xmlns:xacro="http://wiki.ros.org/xacro"> <!-- 传动实现:用于连接控制器与关节 /gazebo/move.xacro --> <xacro:macro name="joint_trans" params="joint_name"> <!-- Transmission is important to link the joints and the controller --> <transmission name="${joint_name}_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${joint_name}"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> </joint> <actuator name="${joint_name}_motor"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> </xacro:macro> <!-- 每一个驱动轮都需要配置传动装置 --> <xacro:joint_trans joint_name="left_wheel2base_link" /> <xacro:joint_trans joint_name="right_wheel2base_link" /> <!-- 控制器 --> <gazebo> <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so"> <rosDebugLevel>Debug</rosDebugLevel> <publishWheelTF>true</publishWheelTF> <robotNamespace>/</robotNamespace> <publishTf>1</publishTf> <publishWheelJointState>true</publishWheelJointState> <alwaysOn>true</alwaysOn> <updateRate>100.0</updateRate> <legacyMode>true</legacyMode> <leftJoint>left_wheel2base_link</leftJoint> <!-- 左轮 --> <rightJoint>right_wheel2base_link</rightJoint> <!-- 右轮 --> <wheelSeparation>${base_link_radius * 2}</wheelSeparation> <!-- 车轮间距 --> <wheelDiameter>${wheel_radius * 2}</wheelDiameter> <!-- 车轮直径 --> <broadcastTF>1</broadcastTF> <wheelTorque>30</wheelTorque> <wheelAcceleration>1.8</wheelAcceleration> <commandTopic>cmd_vel</commandTopic> <!-- 运动控制话题 --> <odometryFrame>odom</odometryFrame> <odometryTopic>odom</odometryTopic> <!-- 里程计话题 --> <robotBaseFrame>base_footprint</robotBaseFrame> <!-- 根坐标系 --> </plugin> </gazebo> </robot>
接下来是传感器的配置,因为机器人本体已经有了camera连杆和laser连杆,所以现在需要给这两个存在的连杆配上传感器,也就是将传感器映射到连杆中。引用方式是gazebo reference=“连杆名”,连杆名在机器人本体连杆文件中,保持一致。
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro"> <!-- 被引用的link /gazebo/camera_sensor.xacro --> <gazebo reference="camera"> <!-- 类型设置为 camara --> <sensor type="camera" name="camera_node"> <update_rate>30.0</update_rate> <!-- 更新频率 --> <!-- 摄像头基本信息设置 --> <camera name="head"> <horizontal_fov>1.3962634</horizontal_fov> <image> <width>1280</width> <height>720</height> <format>R8G8B8</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 name="gazebo_camera" filename="libgazebo_ros_camera.so"> <alwaysOn>true</alwaysOn> <updateRate>0.0</updateRate> <cameraName>/camera</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> </robot>
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro"> <!-- 雷达 /gazebo/laser_sensor.xacro--> <gazebo reference="laser"> <sensor type="ray" name="rplidar"> <pose>0 0 0 0 0 0</pose> <visualize>true</visualize> <update_rate>5.5</update_rate> <ray> <scan> <horizontal> <samples>360</samples> <resolution>1</resolution> <min_angle>-3</min_angle> <max_angle>3</max_angle> </horizontal> </scan> <range> <min>0.10</min> <max>30.0</max> <resolution>0.01</resolution> </range> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.01</stddev> </noise> </ray> <plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so"> <topicName>/scan</topicName> <frameName>laser</frameName> </plugin> </sensor> </gazebo> </robot>
好了,终于完成了机器人的整体设计了,现在机器人有了本体,还有了两轮差速控制器,还有了传感器。
接下来就让机器人通过launch文件启动gazebo和rviz中吧。
分别通过launch来启动gazebo和rviz,有启动先后顺序的,因为car_gazebo.xacro先在car_gazebo.launch中加载到参数服务器中,所以要先启动car_gazebo.launch,并且在car_rviz.launch不需要加载car_gazebo.xacro文件,因为car_gazebo.launch已经将其加载参数服务器了。
<launch>
<!-- car_gazebo.launch
将 xacro 文件的内容加载到参数服务器 -->
<param name="robot_description" command="$(find xacro)/xacro $(find urdf02_gazebo)/xacro/car_gazebo.xacro" />
<!-- 启动 gazebo -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find urdf02_gazebo)/world/box_house.world" />
</include>
<!-- 在 gazebo 中显示机器人模型 -->
<node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description" />
</launch>
<launch>
<!-- car_rviz.launch
启动 rviz,加载rviz配置 -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find urdf02_gazebo)/config/show.rviz"/>
<!-- 关节以及机器人状态发布节点 -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
</launch>
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。