https://github.com/XFFer/ROS_Resource
连载(四) 中我们使用URDF建模遇到了很多问题,比如多个轮子需要重复书写代码;不能进行参数计算,各个link的位置需要逐个输入参数。
官方Wiki地址跳转
常量定义
<xacro:property name="M_PI" value="3.14159" />
举例:
<xacro:property name="M_PI" value="3.1415926" />
<xacro:property name="base_radius" value="0.20" />
<xacro:property name="base_length" value="0.16" />
<xacro:property name="wheel_radius" value="0.06" />
<xacro:property name="wheel_length" value="0.025" />
<xacro:property name="wheel_joint_y" value="0.19" />
<xacro:property name="wheel_joint_z" value="0.05" />
<xacro:property name="caster_radius" value="0.015" />
<xacro:property name="caster_joint_x" value="0.18" />
常量使用
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
举例:
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${base_length/2 + caster_radius*2}" rpy="0 0 0" />
<parent link="base_footprint" />
<child link="base_link" />
joint>
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_length}" radius="${base_radius}" />
geometry>
<material name="yellow" />
visual>
link>
所有数学运算都会转换成浮点数进行,以保证运算精度。
<origin xyz="0 ${(motor_length+wheel_length)/2} 0" rpy="0 0 0" />
举例:
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${base_length/2 + caster_radius*2}" rpy="0 0 0" />
<parent link="base_footprint" />
<child link="base_link" />
joint>
宏定义
类似于函数,可以实现创建一个轮子的模型,通过再次调用修改参数,创建相同形状,多个轮子模型。
<xacro:macro name="name" params="A B C">
......
xacro:macro>
举例:
<xacro:macro name="wheel" param="prefix reflect">
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="0 ${reflect*wheel_joint_y} ${-wheel_joint_z}" rpy="0 0 0" />
<parent link="base_link" />
<child link="${prefix}_wheel_link" />
<axis xyz="0 1 0" />
joint>
<link name="${prefix}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
geometry>
<material name="gray" />
visual>
link>
xacro:macro>
宏调用
<name A="A_value" B="B_value" C="C_value" />
举例:
<wheel prefix="left" reflect="1" />
<wheel prefix="right" reflect="-1" />
<xacro:include filename="$(find mbot_description)/urdf/mbot_base_gazebo.xacro" />
举例:
<xacro:include filename="$(find mbot_description)/urdf/sensors/camera_gazebo.xacro" />
<xacro:include filename="$(find mbot_description)/urdf/mbot_base_gazebo.xacro" />
由于硬件包括各种有刷无刷电机、机械臂、激光雷达、视觉传感器,驱动方式都有很大的差别。故硬件抽象层是对硬件进行包装,使它更容易能够和上层控制层绑定在一起。
上图中包含了上述的几个模块,Controller Manager可以帮助管理不同的控制器,如:底盘控制器,机械臂等的启动、暂停、运行、停止;具体的是一个PID Loops,这个闭环PID更像在应用层面,会向下发指令会通过Hardware Resource Interface Layer这个硬件资源的接口,以不同的形式发布;在仿真器中会有DefaultRobotHWSim默认硬件抽象,但对真实机器人,就需要自己去构建这个硬件抽象RobotHW,这里也存在一个PID闭环控制,但偏向于控制板,如STM32对某个电机的控制,再通过解码器Encoders得到关节的状态信息反馈给Controller。
前面MoveIt的插入课,我们用到过joint_position_controller,对机械臂进行MotionPlanning。这里我们列举控制器的所有类型,可参考 https://github.com/ros-controls/ros_control/wiki/controller_interface
转动惯量是大学物理的内容研究的是2D平面的,公式为: J = ∑ m r 2 J=\sum mr^2 J=∑mr2, M = J ω M=J\omega M=Jω, ω \omega ω是角速度,而这里的惯性参数是三维的,用一个惯性矩阵来描述。推了一下圆柱体的公式,同样长方体和球体也可以使用三次积分的方式求出。
<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>
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_length}" radius="{base_radius}" />
geometry>
<material name="yellow" />
visual>
<collison>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_length}" radius="{base_radius}" />
geometry>
collision>
<cylinder_inertial_matrix m="${base_mass}" r="${base_radius}" h="${base_length}" />
link>
Gazebo中需要添加色彩标签。由于rviz和gazebo的色彩空间不同,描述形式不一样,不能通用,如果不标记标签,Gazebo内的模型都为灰色。
<gazebo reference="base_link">
<material>Gazebo/Bluematerial>
gazebo>
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Graymaterial>
gazebo>
<gazebo reference="base_footprint">
<turnGravityoff>falseturnGravityoff>
gazebo>
“base_footprint”是对底盘在地面的一个映射,这里需要把这个影子的重力设置为无。
<gazebo reference="${prefix}_caster_link">
<material>Gazebo/Blackmaterial>
gazebo>
为每一个joint添加虚拟电机(传动装置)。这里使用了硬件接口——速度控制接口hardware_interface/VelocityJointInterface。
<transmission name="${prefix}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmissiontype>
<joint name="${prefix}_name_wheel_joint">
<hardwareInterface>hardware_interface/VelocityJointInterfacehardwareInterface>
joint>
<actuator name="${prefix}_wheel_joint_motor">
<hardwareInterface>hardware_interface/VelocityJointInterfacehardwareInterface>
<mechanicalReduction>1mechanicalReduction>
actuator>
transmission>
<gazebo>
<plugin name="differential_drive_controller"
filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>DebugrosDebugLevel>
<publishWheelTF>truepublishWheelTF>
<robotNamespace>/robotNamespace>
<publishTf>1publishTf>
<publishWheelJointState>truepublishWheelJointState>
<alwaysOn>truealwaysOn>
<updateRate>100.0updateRate>
<legacyMode>truelegacyMode>
<leftJoint>left_wheel_jointleftJoint>
<rightJoint>right_wheel_jointrightJoint>
<wheelSeparation>${wheel_joint_y*2}wheelSeparation>
<wheelDiameter>${wheel_radius*2}wheelDiameter>
<broadcastTF>1broadcastTF>
<wheelTorque>30wheelTorque>
<wheelAcceleration>1.8wheelAcceleration>
<commandTopic>cmd_velcommandTopic>
<odometryFrame>odomodometryFrame>
<odometryTopic>odomodometryTopic>
<robotBaseFrame>base_footprintrobotBaseFrame>
plugin>
gazebo>
全向移动使用libgazebo_ros_planar_move这个插件,具体gazebo插件可以参考官方网站。
在gazebo中加载机器人模型需要首先将.xacro文件写入.launch文件中用来执行。
示例:
<launch>
<arg name="paused" default="false" />
<arg name="use_sim_time" default="true" />
<arg name="gui" default="true" />
<arg name="headless" default="false" />
<arg name="debug" default="false" />
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)" />
<arg name="paused" value="$(arg paused)" />
<arg name="use_sim_time" value="$(arg use_sim_time)" />
<arg name="gui" value="$(arg gui)" />
<arg name="headless" value="$(arg headless)" />
include>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find mobot_description)/urdf/mbot_gazebo.xacro'"/>
<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" output="screen" >
<param name="publish_frequency" type="double" value="50.0" />
node>
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model mrobot -param robot_description" />
launch>
$ roslaunch mbot_gazebo view_mbot_gazebo_empty_world.launch
$ rostopic list
会发现/cmd_vel,那么就可以通过
$ rostopic pub /cmd_vel geometry_msgs/Twist "linear:
x: 0.6
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 0.5"
发布运动指令了。
从https://bitbucket.org/osrf/gazebo_models/downloads/下载,提前放到模型~/.gazebo/models下,.gazebo文件夹一般是隐藏的,点击ctrl+h
可以显示隐藏文件夹。下载的模型包解压后需要把文件内的所有文件散开放,每个文件夹都是一个模型。
在Gazebo仿真环境,点击左上角的Insert插入,就可以放置物理环境了,通过左上角的Save World As可以保存当前设置的仿真环境。
首先需要打开一个Gazebo World。可以使用
$ roslaunch mbot_gazebo view_mbot_gazebo_empty_world.launch
但是要事先把功能包放置到工作空间下。(功能包已经在全文开头给出了github地址)
点击File中的Building Editor
通过左边的墙体、窗户、门,颜色,质感等,构建一个虚拟的物理环境。
下面我们运行一个gazebo提供的仿真环境,只不过也就是放了几个东西而已。
$ roslaunch mbot_gazebo view_mbot_gazebo_play_ground.launch
然后运行一个gazebo提供的键盘控制小车移动的脚本。
$ roslaunch mbot_teleop mbot_teleop.launch
你会发现使用i
前进(红色X轴),使用,
后退,使用j
向左转,l
右转,q
加速等等,kinetic中左右是相反的,你会发现小车是具有惯性的,这就是惯性矩阵的作用,同样小车碰撞物体时,可能推动物体前进(在物体质量较轻时),小车对物体有力的作用。
示例:(示例中仅包含传感器设置,并不包含其他模型构建,不是完整的)
<gazebo reference="${prefix}_link">
<sensor type="camera" name="camera_node">
<update_rate>30.0update_rate>
<camera name="head">
<horizontal_fov>1.3962634horizontal_fov>
<image>
<width>1280width>
<height>720height>
<format>R8G8B8format>
image>
<clip>
<near>0.02near>
<far>300far>
clip>
<noise>
<type>gaussiantype>
<mean>0.0mean>
<stddev>0.007stddev>
noise>
camera>
<plugin name="gazebo_camera" filename="libgazebo_ros_camera.so">
<alwaysOn>truealwayOn>
<updateRate>0.0updateRate>
<cameraName>/cameracameraName>
<imageTopicName>image_rawimageTopicName>
<cameraInfoTopicName>camera_infocmaeraInfoTopicName>
<frameName>camera_linkframName>
<hackBaseline>0.07hackBaseline>
<distortionK1>0.0distortionK1>
<distortionK2>0.0distortionK2>
<distortionK3>0.0distortionK3>
<distortionT1>0.0distortionT1>
<distortionT2>0.0distortionT2>
plugin>
sensor>
gazebo>
可以运行一下给出功能包里的程序
$ roslaunch mbot_gazebo view_mbot_with_camera_gazebo.launch
随后运行
$ rostopic list
可以看到多出很多由camera开头的话题,我们用rqt_image_view显示话题仿真的图像
$ rqt_image_view
Kinect通过红外感知周围物体的深度信息。
示例:(示例中仅包含传感器设置,并不包含其他模型构建,不是完整的)
<gazebo reference="${prefix}_link">
<sensor type="depth" name="${prefix}">
<always_on>truealways_on>
<update_rate>20.0update_rate>
<camera>
<horizontal_fov>${60.0*M_PI/180.0}horizontal_fov>
<image>
<width>640width>
<height>480height>
<format>R8G8B8format>
image>
<clip>
<near>0.05near>
<far>8.0far>
clip>
camera>
<plugin name="kinect_${prefix}_controller" filename="libgazebo_ros_openni_kinect.so">
<alwaysOn>truealwayOn>
<updateRate>10updateRate>
<cameraName>${prefix}cameraName>
<imageTopicName>rgb/image_rawimageTopicName>
<depthImageTopicName>depth/image_rawdepthImageTopicName>
<pointCloudTopicName>depth/pointspointCloudTopicName>
<depthImageCameraInfoTopicName>depth/camera_infodepthImageCameraInfoTopicName>
<cameraInfoTopicName>rgb/camera_infocmaeraInfoTopicName>
<frameName>${prefix}_frame_opticalframName>
<baseline>0.1beseline>
<distortionk1>0.0distortionk1>
<distortionk2>0.0distortionk2>
<distortionk3>0.0distortionk3>
<distortiont1>0.0distortiont1>
<distortiont2>0.0distortiont2>
<pointCloudCutoff>0.4pointCloudCutoff>
plugin>
sensor>
gazebo>
同样可以执行给出功能包中的.launch文件
$ roslaunch mbot_gazebo view_mbot_with_kinect_gazebo.launch
使用rostopic list输出的话题中由kinect开头的都是该仿真摄像头提供的话题。我们可以通过rviz进行显示。
$ rosrun rviz rviz
添加PointCloud2和Image选择Kinect发布的话题,就可以在rviz中显示出来。
示例:这里也只列出仿真传感器的设置,其他设置大差不差。
这里是一个二维的雷达,可以得到二维的深度信息。
<gazebo reference="${prefix}_link">
<sensor type="ray" name="rplidar">
<pose>0 0 0 0 0 0pose>
<visualize>falsevisualize>
<update_rate>5.5update_rate>
<ray>
<scan>
<horizontal>
<samples>360samples>
<resolution>1resolution>
<min_angle>-3min_angle>
<max_angle>3max_angle>
horizontal>
scan>
<range>
<min>0.10min>
<max>6.0max>
<resolution>0.01resolution>
range>
<noise>
<type>gaussiantype>
<mean>0.0mean>
<stddev>0.01stddev>
noise>
ray>
<plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
<topicName>/scantopicName>
<frameName>laser_linkframeName>
plugin>
sensor>
gazebo>