2.4 读取激光雷达信息

你有了轮式里程计wheel_odom且到base_link的转换,然后我需要激光雷达的数据
看你什么雷达了,比如思岚科技,按官网教程,他写了节点能输出pointcloud2信息,然后他还有个包能将其转换为laserscan信息,但是一般的3D雷达是没有转换为laserscan信息这个包的,但比较良心的会直接写3D建图节点,如velodyne的LOAM,那我们就不用gmapping了。
对于其他3D雷达,我们如何进行建图我们之后讲

我们现在有了laserscan信息,wheel_odom,wheel_odom到base_link的tf,我们要再写个laser坐标系到base_link的tf,在launch里写:
有可能有些激光雷达的坐标系名字不是laser,你可以打开他的自带launch文件或者源码看一下它的id是什么。

<launch>
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 0 /laser /base_link 100" />
</launch>

2.5 定位建图
有了laserscan信息,wheel_odom,wheel_odom到base_link的tf,laser到base_link的tf。我们就可以用gmapping建图了。值得注意的是gmapping会根据你的wheel_odom进行粒子滤波,让你的定位更精确再进行栅格建图。如何产生这些东西,我们在后面高中部分说。

<launch><arg name="scan_topic"  default="scan" /> //laser的topic名称,与自己的激光的topic相对应 <arg name="base_frame"  default="base_footprint"/>//机器人的坐标系<arg name="odom_frame"  default="odom"/>//世界坐标<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">//启动slam的节点<param name="base_frame" value="$(arg base_frame)"/><param name="odom_frame" value="$(arg odom_frame)"/><param name="map_update_interval" value="0.01"/>//地图更新的一个间隔,两次scanmatch的间隔,地图更新也受scanmach的影响,如果scanmatch没有成功的话,是不会更新地图的<param name="maxUrange" value="4.0"/>//set maxUrange < maximum range of the real sensor <= maxRange<param name="maxRange" value="5.0"/><param name="sigma" value="0.05"/><param name="kernelSize" value="3"/><param name="lstep" value="0.05"/>optimize机器人移动的初始值(距离)<param name="astep" value="0.05"/>//optimize机器人移动的初始值(角度)<param name="iterations" value="5"/>//icp的迭代次数<param name="lsigma" value="0.075"/><param name="ogain" value="3.0"/><param name="lskip" value="0"/>//为0,表示所有的激光都处理,尽可能为零,如果计算压力过大,可以改成1<param name="minimumScore" value="30"/>//很重要,判断scanmatch是否成功的阈值,过高的话会使scanmatch失败,从而影响地图更新速率<param name="srr" value="0.01"/>//以下四个参数是运动模型的噪声参数<param name="srt" value="0.02"/><param name="str" value="0.01"/><param name="stt" value="0.02"/><param name="linearUpdate" value="0.05"/>//机器人移动linearUpdate距离,进行scanmatch<param name="angularUpdate" value="0.0436"/>机器人选装angularUpdate角度,进行scanmatch<param name="temporalUpdate" value="-1.0"/><param name="resampleThreshold" value="0.5"/><param name="particles" value="8"/>//很重要,粒子个数<!--<param name="xmin" value="-50.0"/><param name="ymin" value="-50.0"/><param name="xmax" value="50.0"/><param name="ymax" value="50.0"/>make the starting size small for the benefit of the Android client's memory...--><param name="xmin" value="-1.0"/>//map初始化的大小<param name="ymin" value="-1.0"/><param name="xmax" value="1.0"/><param name="ymax" value="1.0"/><param name="delta" value="0.05"/><param name="llsamplerange" value="0.01"/><param name="llsamplestep" value="0.01"/><param name="lasamplerange" value="0.005"/><param name="lasamplestep" value="0.005"/><remap from="scan" to="$(arg scan_topic)"/></node>

说明如下:
~inverted_laser (string, default:“false”), (已经已出在 版本 1.1.1; 用transform data 替换它) 激光器是right side up (scans are ordered CCW),还是 upside down (scans are ordered CW)?

~throttle_scans (int, default: 1),处理的扫描数据门限,默认每次处理1个扫描数据(可以设置更大跳过一些扫描数据)

~base_frame (string, default:“base_link”),机器人基座坐标系

~map_frame (string, default:“map”),地图坐标系

~odom_frame (string, default:“odom”),里程计坐标系

~map_update_interval (float, default: 5.0),地图更新频率

~maxUrange (float, default: 80.0),探测最大可用范围,即光束能到达的范围。

~sigma (float, default: 0.05),endpoint匹配标准差

~kernelSize (int, default: 1),用于查找对应的kernel size

~lstep (float, default: 0.05),平移优化步长

~astep (float, default: 0.05),旋转优化步长

~iterations (int, default: 5),扫描匹配迭代步数

~lsigma (float, default: 0.075),用于扫描匹配概率的激光标准差

~ogain (float, default: 3.0),似然估计为平滑重采样影响使用的gain

~lskip (int, default: 0),每次扫描跳过的光束数.

~minimumScore (float, default: 0.0),为获得好的扫描匹配输出结果,用于避免在大空间范围使用有限距离的激光扫描仪(如5m)出现的jumping pose estimates问题。 当 Scores高达600+,如果出现了该问题可以考虑设定值50。

~srr (float, default: 0.1),平移时里程误差作为平移函数(rho/rho)

~srt (float, default: 0.2),平移时的里程误差作为旋转函数 (rho/theta)

~str (float, default: 0.1),旋转时的里程误差作为平移函数 (theta/rho)

~stt (float, default: 0.2),旋转时的里程误差作为旋转函数 (theta/theta)

~linearUpdate (float, default: 1.0),机器人每旋转这么远处理一次扫描

~angularUpdate (float, default: 0.5),Process a scan each time the robot rotates this far

~temporalUpdate (float, default: -1.0),如果最新扫描处理比更新慢,则处理1次扫描。该值为负数时候关闭基于时间的更新

~resampleThreshold (float, default: 0.5),基于重采样门限的Neff

~particles (int, default: 30),滤波器中粒子数目

~xmin (float, default: -100.0),地图初始尺寸

~ymin (float, default: -100.0),地图初始尺寸

~xmax (float, default: 100.0),地图初始尺寸

~ymax (float, default: 100.0),地图初始尺寸

~delta (float, default: 0.05),地图分辨率

~llsamplerange (float, default: 0.01),于似然计算的平移采样距离

~llsamplestep (float, default: 0.01),用于似然计算的平移采样步长

~lasamplerange (float, default: 0.005),用于似然计算的角度采样距离

~lasamplestep (float, default: 0.005),用于似然计算的角度采样步长

~transform_publish_period (float, default: 0.05),变换发布时间间隔.

~occ_thresh (float, default: 0.25),栅格地图栅格值 (i.e., set to 100 in the resultingsensor_msgs/LaserScan).

~maxRange (float),传感器最大范围。如果在传感器距离范围内没有障碍物应该在地图上显示为自由空间。 maxUrange < 真实传感器最大距离范围 <= maxRange.

效果如图:

有了地图你可以用move_base进行导航。

2.6 导航

ros进行导航时先要接受一个goal(这个用rviz发)然后根据激光雷达产生的地图生成全局代价地图,然后用A*/dijsktra算法确定全局最短路径,然后又根据激光雷达的探测可以产生局部代价地图,从而用dwa进行局部路径规划(避障导航)产生局部路径(DWA,RRT),有了局部路径就可以发之前cmd_vel信息进行导航了,官网的图对新手很不友好就不贴了。这需要一个launch,5个file。

<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen"><rosparam file="$(find autolabor_pro1_driver)/param/move_base_params.yaml" command="load" /><rosparam file="$(find autolabor_pro1_driver)/param/global_costmap_params.yaml" command="load" ns="global_costmap"/><rosparam file="$(find autolabor_pro1_driver)/param/local_costmap_params.yaml" command="load" ns="local_costmap"/><rosparam file="$(find autolabor_pro1_driver)/param/global_planner_params.yaml" command="load" ns="GlobalPlanner"/><rosparam file="$(find autolabor_pro1_driver)/param/dwa_local_planner_params.yaml" command="load" ns="DWAPlannerROS"/>
</node>

分别是move_base的配置文件,全局代价地图,局部代价地图,全局规划器和局部规划器。值得注意且经常调的是局部路径规划的范围。 迪杰斯特拉见迪杰斯特拉与A*。A*不过是加了个指示函数,dwa与RRT自己百度去。这里只大致说一下。
先通过给里程计一个增量得到一群模拟路径:

再选择评分最高的路径


一、move base配置文件如下图:(我给出中文注释及用法,方便大家理解)

base_global_planner: "global_planner/GlobalPlanner"
base_local_planner: "dwa_local_planner/DWAPlannerROS"
recovery_behaviors:- {name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery} - {name: rotate_recovery, type: rotate_recovery/RotateRecovery} - {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}# The rate in Hz at which to run the global planning loop. If the frequency is set to 0.0, the global planner will only run when a new goal is received or the local planner reports that its path is blocked.(double, default: 0.0)
planner_frequency: 2.0 (全局规划路径产生频率,如果为0就是给一个goal之后,全局规划路径不变更,这个不用设置太高,不然太耗资源)# The rate in Hz at which to run the control loop and send velocity commands to the base.(double, default: 20.0)
controller_frequency: 10.0 (就是局部规划器cmd_vel发送的频率,发这个让底盘节点响应,发消息给编码器,从而控制小车速度,这个变的时候要把PID的频率也改变,
如果pid的代码不同时刻控制速度是分开存储的就不用,这个也别太快,不然机器响应不了,你只能去调PID参数了,主要是D)# How long the planner will wait in seconds in an attempt to find a valid plan before space-clearing operations are performed.(double, default: 5.0)
planner_patience: 5.0(允许全局规划器计算多少时间,超过这个时间就会显示无法找到路径,如果这个太大,ros可能时序错乱,所以请用速度更快的计算机且不要设太大,或者单独用FPGA处理这个运算)# How long the controller will wait in seconds without receiving a valid control before space-clearing operations are performed.(double, default: 15.0)
controller_patience: 3.0(就是允许局部路径计算时间是多少,超过时间还算不出来这个小车就停下来了,在反应要求这个值比较小,不要太大不然会撞上,这个超过全局路径规划的频率以全局路径规划频率为准,最好的办法是换好的计算机,或者单独用FPGA处理这个运算)# Whether or not to enable the move_base recovery behaviors to attempt to clear out space.(bool, default: true)
recovery_behavior_enabled: true (与前面的对应,让机器人能够清空路径吗,这个设置true可以增加机器人安全性)# Determines whether or not the robot will attempt an in-place rotation when attempting to clear out space. Note: This parameter is only used when the default recovery behaviors are in use, meaning the user has not set the recovery_behaviors parameter to anything custom.(bool, default: true)
clearing_rotation_allowed: false(强烈建议fasle,不然容易打转,超烦)# Determines whether or not to shutdown the costmaps of the node when move_base is in an inactive state (bool, default: false)
shutdown_costmaps: false(是否在movebase未激活的时候关闭代价地图,这个其实movebase断了都不能动了,还说啥,无所谓,但是如果是movebase经常卡死又恢复这种建议开启。但是这样导航也将悲剧,所以好好优化时序吧)# How long in seconds to allow for oscillation before executing recovery behaviors. A value of 0.0 corresponds to an infinite timeout. (double, default: 0.0)
oscillation_timeout: 5.0(恢复前允许震荡多少秒,为了得到比较好的位姿重估计,这是必要的,但不要太大,不然机器人就成傻子了)# How far in meters the robot must move to be considered not to be oscillating. Moving this far resets the timer counting up to the ~oscillation_timeout (double, default: 0.5)
oscillation_distance: 0.3(机器人必须移动多远才能被认为是不振荡的,这个根据你的激光雷达范围设置,激光雷达范围越大,这个值就可以越大,建议设略小于default,但不能太小)# How many times to allow for planning retries before executing recovery behaviors. A value of -1.0 corresponds to an infinite retries.(int32_t, default: -1)
#max_planning_retries: -1(全局规划器如果找不到路,多久允许恢复?-1就是一直允许,与上面的呼应,建议-1,请通过算法优化位姿,而不是恢复行为。)#############################
# plug for recovery_behaviors
#############################
conservative_reset:
# The radius away from the robot in meters outside which obstacles will be removed from the costmaps when they are reverted to the static map.reset_distance: 1.0(比如原本建的全局地图处有个地方他有障碍物,但是等我机器人到障碍物附近(距离小于某个值)时却发现没有,那我可以把它从全局地图移除,这个距离是多少,如果你的计算机比较卡或者机器人运动速度比较快,建议大一些,但是若是周围人很多,建议设小些,这样不会找不到路径。这里这个是保守设置,1米,下面那个是比较激进的,只要不对就更新,估为0米aggressive_reset:
# The radius away from the robot in meters outside which obstacles will be removed from the costmaps when they are reverted to the static map.reset_distance: 0.0(同上面,激进设置)

二、global_costmap如下图:

# ns : global_costmap# The global frame for the costmap to operate in. (string, default: "/map")
global_frame: /map(全局地图坐标名字:gmapping是不是会产生一个map坐标系及base_link到map的tf,估一般是map)# The name of the frame for the base link of the robot.(string, default: "base_link")
robot_base_frame: base_link(就是机器人基坐标)# distance a circular robot should be clear of the obstacle (kobuki: 0.18)
# robot_radius: 0.20  (机器人应距离障碍物最小的距离,即安全边际)
footprint: [[0.40, 0.35], [0.40, -0.35], [-0.40, -0.35], [-0.40, 0.35]]  # if the robot is not circular
(给出机器人的形状,假设机器人是个矩形,你要给出矩形四个角点的坐标,中心是base_link)
# used for obstacle_layer, 3D->voxel 2D->other
map_type: costmap (使用代价地图进行计算路径)# Specifies the delay in transform (tf) data that is tolerable in seconds. This parameter serves as a safeguard to losing a link in the tf tree while still allowing an amount of latency the user is comfortable with to exist in the system. For example, a transform being 0.2 seconds out-of-date may be tolerable, but a transform being 8 seconds out of date is not. If the tf transform between the coordinate frames specified by the global_frame and robot_base_frame parameters is transform_tolerance seconds older than ros::Time::now(), then the navigation stack will stop the robot.(double, default: 0.2)
transform_tolerance: 0.5 (这个是为了时序同步,我们用ROStime进行同步,如果坐标变换转换太慢了,太晚到了,就把机器人停下来,这个不用太大,因为如果太晚才收到,去计算时就有延迟就会撞上,还不如晚到)# The frequency in Hz for the map to be updated.(double, default: 5.0)
update_frequency: 20.0(地图更新频率)# The frequency in Hz for the map to be publish display information.(double, default: 0.0)
publish_frequency: 1.0(地图发布频率,更新频率是开始计算时间,但计算完不一定就要发布,因为在计算之前还可能等其他数据,以及发送的时候为了同步,所以地图更新为1HZ,loam也是1HZ,如果这个值大于等于地图更新频率,那么地图必将更新失败,如果太接近就会产生错误的地图)# Whether or not to use a rolling window version of the costmap. If the static_map parameter is set to true, this parameter must be set to false. (bool, default: false)
rolling_window: false(这个很耗计算资源的,如果计算机很卡,建议false,这样不会一直更新地图,计算能力差的或者动态环境这样更新地图会不稳定)
static_map: true(地图建好了就不变)# If true the full costmap is published to "~<name>/grid" every update. If false only the part of the costmap that has changed is published on the "~<name>/grid_updates" topic. (bool, default: false)
always_send_full_costmap: false (局部更新就好了,如果全部的话,计算机带不动且地图不稳定)# Sequence of plugin specifications, one per layer. Each specification is a dictionary with name and type fields. The name is used to define the parameter namespace for the plugin.
plugins:- {name: static_layer,            type: "costmap_2d::StaticLayer"}- {name: obstacle_layer,          type: "costmap_2d::ObstacleLayer"}- {name: inflation_layer,         type: "costmap_2d::InflationLayer"}# The width of the map in meters.(int, default: 10)
width: 10  (地图多宽:指的是局部代价地图)# The height of the map in meters.(int, default: 10)
height: 10(地图多长:指的是局部代价地图)# The resolution of the map in meters/cell. (double, default: 0.05)
resolution: 0.05(地图分辨率)# The x origin of the map in the global frame in meters. (double, default: 0.0)
origin_x: 0.0(地图原点的x)# The y origin of the map in the global frame in meters. (double, default: 0.0)
origin_y: 0.0(地图原点的y)#############################
#
#        static_layer
#
#############################
(这个是对用mapserver导入的地图而言,当你用gmapping建完图后可用mapserver保存地图)
static_layer:
# The value for which a cost should be considered unknown when reading in a map from the map server. If the costmap is not tracking unknown space, costs of this value will be considered occupied. A value of zero also results in this parameter being unused. (int, default: -1)unknown_cost_value: -1 (比如有占用给了1,没占用给了0,未探测你给啥值?默认-1)# The threshold value at which to consider a cost lethal when reading in a map from the map server.(int, default: 100)lethal_cost_threshold: 100 (有害的cost是啥值,比如障碍物)# The topic that the costmap subscribes to for the static map. This parameter is useful when you have multiple costmap instances within a single node that you want to use different static maps. (string, default: "map")map_topic: map (全局地图坐标系叫啥名字)# Only subscribe to the first message on the map topic, ignoring all subsequent messages (bool, default: false)first_map_only: false (只考虑第一个地图数据?肯定不是,我们还要更新)# In addition to map_topic, also subscribe to map_topic + "_updates" (bool, default: false)subscribe_to_updates: false (还订阅maptopic 的其他update,这个可以结合机器视觉深度学习来使用,具体在后面说)# If true, unknown values in the map messages are translated directly to the layer. Otherwise, unknown values in the map message are translated as FREE_SPACE in the layer.  (bool, default: true)track_unknown_space: true (你看,我们在rviz发一个坐标给为探测区域也能导航,为什么,就是这个)# Only matters if the static layer is not the bottom layer. If true, only the maximum value will be written to the master costmap. (bool, default: false)use_maximum: false (false就是代价地图地图所有情况都更新,true就是指更新障碍物)# If true, translates all map message values to NO_INFORMATION/FREE_SPACE/LETHAL_OBSTACLE (three values). If false, a full spectrum of intermediate values is possible. (bool, default: true)trinary_costmap: true (三重costmap,说白了,打开rviz,有三种地图看到没,如果true就产生那三种地图,false就一种)#############################
#
#        inflation_layer
#
#############################
inflation_layer:
# The radius in meters to which the map inflates obstacle cost values. (double, default: 0.55)inflation_radius: 0.10 (比如障碍物半径是1,为了不装上去,我把障碍物半径考虑成1.1,这时这个值就是0.1)# A scaling factor to apply to cost values during inflation. The cost function is computed as follows for all cells in the costmap further than the inscribed radius distance and closer than the inflation radius distance away from an actual obstacle: exp(-1.0 * cost_scaling_factor * (distance_from_obstacle - inscribed_radius)) * (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1), where costmap_2d::INSCRIBED_INFLATED_OBSTACLE is currently 254. NOTE: since the cost_scaling_factor is multiplied by a negative in the formula, increasing the factor will decrease the resulting cost values. (double, default: 10.0)cost_scaling_factor: 10.0 (cost缩放,如迪杰斯特拉的cost,如果值太大,那么它容易陷入局部极小值,太小的话容易计算太久)#############################
#
#      obstacle_layer
#
#############################
obstacle_layer:
# The maximum height of any obstacle to be inserted into the costmap in meters. This parameter should be set to be slightly higher than the height of your robot. (double, default: 2.0)max_obstacle_height: 2.0 (最多考虑多高的障碍物?比你机器人高些就好了)
# The default maximum distance from the robot at which an obstacle will be inserted into the cost map in meters. This can be over-ridden on a per-sensor basis. (double, default: 2.5)obstacle_range: 3.0 (考虑多远的障碍物?激光雷达比较远就考虑远些,不过计算机会吃不消,建议适中,机器人如果运动很快,这个要设大些)
# The default range in meters at which to raytrace out obstacles from the map using sensor data. This can be over-ridden on a per-sensor basis. (double, default: 3.0)raytrace_range: 4.0 (障碍物追踪范围,略大于上面那个就好)
# If false, each pixel has one of 2 states: lethal obstacle or free. If true, each pixel has one of 3 states: lethal obstacle, free, or unknown.  (bool, default: false)track_unknown_space: false (地图属性,如果是true,那么地图有障碍物,未探测,无障碍物三种,如果false就2种)
# If true, the robot footprint will clear (mark as free) the space in which it travels. (bool, default: true)footprint_clearing_enabled: true (机器人移动那么清空那个栅格,无人驾驶汽车在公路上建议为false)
# A list of observation source names separated by spaces. This defines each of the <source_name> namespaces defined below. (string, default: "")observation_sources: scan(激光雷达发布的话题名)scan:
# The topic on which sensor data comes in for this source. Defaults to the name of the source. (string, default: source_name)topic: scan (激光雷达发布的话题名)
# The frame of the origin of the sensor. Leave empty to attempt to read the frame from sensor data. The frame can be read from both sensor_msgs/LaserScan, sensor_msgs/PointCloud, and sensor_msgs/PointCloud2 messages. (string, default: "")sensor_frame: "" (若空就是直接scan,如果有其他坐标系并有tf的话可以其他)
# How long to keep each sensor reading in seconds. A value of 0.0 will only keep the most recent reading. (double, default: 0.0)observation_persistence: 0.0 (激光点云保持时间,建议为0)
# How often to expect a reading from a sensor in seconds. A value of 0.0 will allow infinite time between readings. This parameter is used as a failsafe to keep the navigation stack from commanding the robot when a sensor has failed. It should be set to a value that is slightly more permissive than the actual rate of the sensor. For example, if we expect a scan from a laser every 0.05 seconds we might set this parameter to be 0.1 seconds to give a generous buffer and account for some amount of system latency. (double, default: 0.0)expected_update_rate: 0.0 (多久从激光雷达读数是允许的,0就可以了,发过来我就收)
# The data type associated with the topic, right now only "PointCloud", "PointCloud2", and "LaserScan" are supported. (string, default: "PointCloud")data_type: LaserScan (数据格式名)
# Whether or not this observation should be used to clear out freespace.  (bool, default: false)clearing: true (是否要用于清除空闲,肯定true啊)
# Whether or not this observation should be used to mark obstacles. (bool, default: true)marking: true (激光雷达数据是否要用于标记障碍物,肯定true啊)
# The maximum height in meters of a sensor  reading considered valid. This is usually set to be slightly higher than the height of the robot. Setting this parameter to a value greater than the global max_obstacle_height parameter has no effect. Setting this parameter to a value less than the global max_obstacle_height will filter out points from this sensor above that height.(double, default: 2.0)max_obstacle_height: 2.0  (最多考虑多高的障碍物?比你机器人高些就好了)
# The minimum height in meters of a sensor reading considered valid. This is usually set to be at ground height, but can be set higher or lower based on the noise model of your sensor. (double, default: 0.0)min_obstacle_height: 0.0  (最多考虑多低的障碍物?地面就可以,除非3D)
# The maximum range in meters at which to insert obstacles into the costmap using sensor data.  (double, default: 2.5)obstacle_range: 3.0 (把半径为多少的障碍物纳入代价地图?)
# The maximum range in meters at which to raytrace out obstacles from the map using sensor data.  (double, default: 3.0)raytrace_range: 4.0  (对半径多少内的障碍物进行跟中)
# Allows for Inf values in "LaserScan" observation messages. The Inf values are converted to the laser maximum range.  (bool, default: false)inf_is_valid: true  (允许laserscan的inf数据,这个表示了激光雷达的能力,所以true)

三、GlobalPlanner全局规划器

# ns : GlobalPlanner# Specifies whether or not to allow the planner to create plans that traverse unknown space. NOTE: if you are using a layered costmap_2d costmap with a voxel or obstacle layer, you must also set the track_unknown_space param for that layer to be true, or it will convert all your unknown space to free space (which planner will then happily go right through). (bool, default: true)
allow_unknown: true (就是在rviz能不能向未探测区域发goal)# A tolerance on the goal point for the planner. The planner will attempt to create a plan that is as close to the specified goal as possible but no further than default_tolerance away. (double, default: 0.0)
default_tolerance: 0.0 (比方说你给rviz一个goal,如果那个点不太好到达,能不能让你到离这个点比较近的点,如果是精确到达的话,0)# Specifies whether or not to visualize the potential area computed via a PointCloud2. (bool, default: false)
visualize_potential: false
(是否显示潜在区域通过激光雷达点的计算过程,没用,直接false)
# If true, use dijkstra's algorithm. Otherwise, A*. (bool, default: true)
use_dijkstra: true
(全局路径规划算法是用迪杰斯特拉还是A*,true就是dijkstra)
# If true, use the quadratic approximation of the potential. Otherwise, use a simpler calculation. (bool, default: true)
use_quadratic: true
(使用二次逼近与否,如果用的话,能够计算更快)
# If true, create a path that follows the grid boundaries. Otherwise, use a gradient descent method. (bool, default: false)
use_grid_path: false
(使用栅格路径?使用的话计算速度会快些,但不精确)
# If for some reason, you want global_planner to exactly mirror the behavior of navfn, set this to true (and use the defaults for the other boolean parameters) (bool, default: false)
old_navfn_behavior: false(如果你希望全局规划器准确地反应导航雷达的行为,就true,)

四、local_costmap参数:

# ns : local_costmap# The global frame for the costmap to operate in. (string, default: "/map")
global_frame: /odom (全局坐标系名)# The name of the frame for the base link of the robot.(string, default: "base_link")
robot_base_frame: base_link (基坐标系名)# distance a circular robot should be clear of the obstacle (kobuki: 0.18)
#robot_radius: 0.20   (距离多远更新障碍物,同global)
footprint: [[0.40, 0.35], [0.40, -0.35], [-0.40, -0.35], [-0.40, 0.35]]   # if the robot is not circular
(同global,设机器人为一矩形,距离点的四个顶点距中心base_link坐标,二维的)
# used for obstacle_layer, 3D->voxel 2D->other
map_type: costmap
(类型是代价地图)
# Specifies the delay in transform (tf) data that is tolerable in seconds. This parameter serves as a safeguard to losing a link in the tf tree while still allowing an amount of latency the user is comfortable with to exist in the system. For example, a transform being 0.2 seconds out-of-date may be tolerable, but a transform being 8 seconds out of date is not. If the tf transform between the coordinate frames specified by the global_frame and robot_base_frame parameters is transform_tolerance seconds older than ros::Time::now(), then the navigation stack will stop the robot.(double, default: 0.2)
transform_tolerance: 0.5
(tf转换允许的最大延迟,同global)# The frequency in Hz for the map to be updated.(double, default: 5.0)
update_frequency: 20.0
(地图更新频率)
# The frequency in Hz for the map to be publish display information.(double, default: 0.0)
publish_frequency: 1.0
(地图发布频率,同global)
# Whether or not to use a rolling window version of the costmap. If the static_map parameter is set to true, this parameter must be set to false. (bool, default: false)
rolling_window: true
static_map: false
(这里是局部代价地图,要进行动态更新)
# If true the full costmap is published to "~<name>/grid" every update. If false only the part of the costmap that has changed is published on the "~<name>/grid_updates" topic. (bool, default: false)
always_send_full_costmap: false
(局部地图当然只发局部的代价地图啦)
# Sequence of plugin specifications, one per layer. Each specification is a dictionary with name and type fields. The name is used to define the parameter namespace for the plugin.
plugins:- {name: obstacle_layer,          type: "costmap_2d::ObstacleLayer"}- {name: inflation_layer,         type: "costmap_2d::InflationLayer"}# The width of the map in meters.(int, default: 10)
width: 10.0
(局部地图宽)
# The height of the map in meters.(int, default: 10)
height: 10.0
(局部地图长)
# The resolution of the map in meters/cell. (double, default: 0.05)
resolution: 0.05
(地图分辨率)
# The x origin of the map in the global frame in meters. (double, default: 0.0)
origin_x: 0.0
(地图原点x坐标)
# The y origin of the map in the global frame in meters. (double, default: 0.0)
origin_y: 0.0
(地图原点y坐标)
#############################
#
#        inflation_layer
#
#############################
inflation_layer:
# The radius in meters to which the map inflates obstacle cost values. (double, default: 0.55)inflation_radius: 0.05
(同global)
# A scaling factor to apply to cost values during inflation. The cost function is computed as follows for all cells in the costmap further than the inscribed radius distance and closer than the inflation radius distance away from an actual obstacle: exp(-1.0 * cost_scaling_factor * (distance_from_obstacle - inscribed_radius)) * (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1), where costmap_2d::INSCRIBED_INFLATED_OBSTACLE is currently 254. NOTE: since the cost_scaling_factor is multiplied by a negative in the formula, increasing the factor will decrease the resulting cost values. (double, default: 10.0)cost_scaling_factor: 10.0
(同global)
#############################
#
#      obstacle_layer
#
#############################
obstacle_layer:
# The maximum height of any obstacle to be inserted into the costmap in meters. This parameter should be set to be slightly higher than the height of your robot. (double, default: 2.0)max_obstacle_height: 2.0(同global)
# The default maximum distance from the robot at which an obstacle will be inserted into the cost map in meters. This can be over-ridden on a per-sensor basis. (double, default: 2.5)obstacle_range: 3.0(同global)
# The default range in meters at which to raytrace out obstacles from the map using sensor data. This can be over-ridden on a per-sensor basis. (double, default: 3.0)raytrace_range: 4.0(同global)
# If false, each pixel has one of 2 states: lethal obstacle or free. If true, each pixel has one of 3 states: lethal obstacle, free, or unknown.  (bool, default: false)track_unknown_space: false(同global)
# If true, the robot footprint will clear (mark as free) the space in which it travels. (bool, default: true)footprint_clearing_enabled: true(同global)
# A list of observation source names separated by spaces. This defines each of the <source_name> namespaces defined below. (string, default: "")observation_sources: scan(同global)scan:
# The topic on which sensor data comes in for this source. Defaults to the name of the source. (string, default: source_name)topic: scan
# The frame of the origin of the sensor. Leave empty to attempt to read the frame from sensor data. The frame can be read from both sensor_msgs/LaserScan, sensor_msgs/PointCloud, and sensor_msgs/PointCloud2 messages. (string, default: "")sensor_frame: ""(同global)
# How long to keep each sensor reading in seconds. A value of 0.0 will only keep the most recent reading. (double, default: 0.0)observation_persistence: 0.0(同global)
# How often to expect a reading from a sensor in seconds. A value of 0.0 will allow infinite time between readings. This parameter is used as a failsafe to keep the navigation stack from commanding the robot when a sensor has failed. It should be set to a value that is slightly more permissive than the actual rate of the sensor. For example, if we expect a scan from a laser every 0.05 seconds we might set this parameter to be 0.1 seconds to give a generous buffer and account for some amount of system latency. (double, default: 0.0)expected_update_rate: 0.0(同global)
# The data type associated with the topic, right now only "PointCloud", "PointCloud2", and "LaserScan" are supported. (string, default: "PointCloud")data_type: LaserScan(同global)
# Whether or not this observation should be used to clear out freespace.  (bool, default: false)clearing: true(同global)
# Whether or not this observation should be used to mark obstacles. (bool, default: true)marking: true(同global)
# The maximum height in meters of a sensor reading considered valid. This is usually set to be slightly higher than the height of the robot. Setting this parameter to a value greater than the global max_obstacle_height parameter has no effect. Setting this parameter to a value less than the global max_obstacle_height will filter out points from this sensor above that height.(double, default: 2.0)max_obstacle_height: 2.0(同global)
# The minimum height in meters of a sensor reading considered valid. This is usually set to be at ground height, but can be set higher or lower based on the noise model of your sensor. (double, default: 0.0)min_obstacle_height: 0.0(同global)
# The maximum range in meters at which to insert obstacles into the costmap using sensor data.  (double, default: 2.5)obstacle_range: 3.0(同global)
# The maximum range in meters at which to raytrace out obstacles from the map using sensor data.  (double, default: 3.0)raytrace_range: 4.0(同global)
# Allows for Inf values in "LaserScan" observation messages. The Inf values are converted to the laser maximum range.  (bool, default: false)inf_is_valid: true(同global)

五、dwa_local_planner参数

# ns : DWAPlannerROS##################################
#
#  Robot Configuration Parameters
#
################################### The x acceleration limit of the robot in meters/sec^2 (double, default: 2.5)
acc_lim_x: 3.0 (x方向最大加速度,速度大了,定位会不准确,所以在保证性能下尽量小)# The y acceleration limit of the robot in meters/sec^2 (double, default: 2.5)
acc_lim_y: 0.0(y方向最大加速度,速度大了,定位会不准确,所以在保证性能下尽量小)# The rotational acceleration limit of the robot in radians/sec^2 (double, default: 3.2)
acc_lim_theta: 10.0(x方向最大角加速度,速度大了,定位会不准确,所以在保证性能下尽量小)# The absolute value of the maximum translational velocity for the robot in m/s (double, default: 0.55)
max_trans_vel: 0.5 (最大平移速度,速度大了,定位会不准确,所以在保证性能下尽量小)# The absolute value of the minimum translational velocity for the robot in m/s (double, default: 0.1)
min_trans_vel: 0.1 (最小平移速度,速度太小了,VO,imu这些东西容易漂移)# The maximum x velocity for the robot in m/s. (double, default: 0.55)
max_vel_x: 0.9(最大x方向速度,速度大了,定位会不准确,所以在保证性能下尽量小)# The minimum x velocity for the robot in m/s, negative for backwards motion. (double, default: 0.0)
min_vel_x: 0.0(最小x方向速度,太小了,VO,imu这些东西容易漂移)# The maximum y velocity for the robot in m/s (double, default: 0.1)
max_vel_y: 0.0(最大y方向速度,速度大了,定位会不准确,所以在保证性能下尽量小)# The minimum y velocity for the robot in m/s (double, default: -0.1)
min_vel_y: 0.0(最小y方向速度,太小了,VO,imu这些东西容易漂移)# The absolute value of the maximum rotational velocity for the robot in rad/s (double, default: 1.0)
max_rot_vel: 1.0 (最大角速度,速度大了,定位会不准确,所以在保证性能下尽量小)# The absolute value of the minimum rotational velocity for the robot in rad/s (double, default: 0.4)
min_rot_vel: 0.3 (最小角速度,速度大了,定位会不准确,所以在保证性能下尽量小)rot_stopped_vel: 0.2 (刹车角速度)
trans_stopped_vel: 0.1 (刹车线速度)
##################################
#
#  Goal Tolerance Parameters
#
################################### The tolerance in radians for the controller in yaw/rotation when achieving its goal (double, default: 0.05)
yaw_goal_tolerance: 0.3 (控制器达到目标的旋转差允许,太小了,机器人会不断调整,从而无法停下)# The tolerance in meters for the controller in the x & y distance when achieving a goal (double, default: 0.10)
xy_goal_tolerance: 0.1 (控制器达到目标的位移差允许,太小了,机器人会不断调整,从而无法停下)# If goal tolerance is latched, if the robot ever reaches the goal xy location it will simply rotate in place, even if it ends up outside the goal tolerance while it is doing so. (bool, default: false)
latch_xy_goal_tolerance: false (如果是true机器人在调整时不会转圈,如果是false就会转圈,建议true,并把前面两个值调大些)##################################
#
#  Forward Simulation Parameters
#
################################### The amount of time to forward-simulate trajectories in seconds (double, default: 1.7)
sim_time: 1.0 (dwa算法不是给位姿一个增量吗,这个增量是由小车的速度及时间间隔时间决定的,这个值越大,计算速度越慢,模拟的路线越长)# The step size, in meters, to take between points on a given trajectory (double, default: 0.025)
sim_granularity: 0.03  (仿真线间隔尺寸,同决定了仿真的路线长度及计算速度,越大越长)
angular_sim_granularity: 0.1(仿真角度间隔尺寸,同决定了仿真的路线长度及计算速度,越大越宽)# The number of samples to use when exploring the x velocity space (integer, default: 3)
vx_samples: 5 (对x速度进行采样的粒子数,越大避障效果越好,但计算越慢)# The number of samples to use when exploring the y velocity space (integer, default: 10)
vy_samples: 1(对y速度进行采样的粒子数,越大避障效果越好,但计算越慢)# The number of samples to use when exploring the theta velocity space (integer, default: 20)
vtheta_samples: 6 (对角速度进行采样的粒子数,越大避障效果越好,但计算越慢)# The frequency at which this controller will be called in Hz. Uses searchParam to read the parameter from parent namespaces if not set in the namespace of the controller. For use with move_base, this means that you only need to set its "controller_frequency" parameter and can safely leave this one unset. (double, default: 20.0)
#controller_frequency: 20 (cmd_vel频率,这个global说过)##################################
#
#   Trajectory Scoring Parameters
#
# cost =  pdist_scale * (distance to path from the endpoint of the trajectory in map cells or meters depending on the meter_scoring parameter)
#  +      gdist_scale * (distance to local goal from the endpoint of the trajectory in map cells or meters depending on the meter_scoring parameter)
#  +      occdist_scale * (maximum obstacle cost along the trajectory in obstacle cost (0-254))
#
##################################
(以上就是dwa的公式了)
# The weighting for how much the controller should stay close to the path it was given (double, default: 32.0)
path_distance_bias: 64.0 (控制器应保持在给定全局路线的权重)# The weighting for how much the controller should attempt to reach its local goal, also controls speed (double, default: 24.0)
goal_distance_bias: 24.0 (控制器达到本地给定目标的权重,注:dwa就是在尽可能接近globalplan下又符合局部代价和安全)# The weighting for how much the controller should attempt to avoid obstacles (double, default: 0.01)
occdist_scale: 0.5 (尝试避免障碍物权重,即为了避障的安全考虑)# The distance from the center point of the robot to place an additional scoring point, in meters (double, default: 0.325)
forward_point_distance: 0.2 (前放点距离,越大越安全,但太大可能找不到路径)# The amount of time that the robot must stop before a collision in order for a trajectory to be considered valid in seconds (double, default: 0.2)
stop_time_buffer: 0.2 (机器人在碰撞前必须停止的时间,模拟轨迹如果撞上了,肯定不好,这个是为了安全,越大越安全)# The absolute value of the velocity at which to start scaling the robot's footprint, in m/s (double, default: 0.25)
scaling_speed: 0.25 (缩放机器人的速度,也是为了安全,越大越安全,但太大可能找不到路径)# The maximum factor to scale the robot's footprint by (double, default: 0.2)
max_scaling_factor: 0.2 (同上面,最大缩放因子)#################################
#
# RotateFirtCostFunction
#
################################## mininum angle robot to path and maximux distance from robot to path begin to make the function work(旋转机器人为找到路径)
angle_threshold: 2.0 (机器人到路径最小转角)
dist_threshold: 0.2 (机器人到路径偏离最大距离)# maximum x direction velocity, this function mainly for rotate robot to path direction, so we have to limit x velocity
max_xv: 0.07 (最大X的直接速度,用于旋转机器人找到路径方向,之前我们有个参数,我是不喜欢旋转)# cost factor for score, the higher it is, the bigger effect it has
cost_factor: 10.0 (见dwa公式)# little bias to defend zero overflow
thetav_bias: 0.2 (这个小偏差是为了防止0溢出,在计算上)##################################
#
#  Oscillation Prevention Parameters
#
################################### How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)
oscillation_reset_dist: 0.05 (在重置振荡标志之前,机器人必须以米为单位移动多远,不能太大,不然机器人容易失控)##################################
#
#      Global Plan Parameters
#
################################### Defines whether or not to eat up the plan as the robot moves along the path. If set to true, points will fall off the end of the plan once the robot moves 1 meter past them. (bool, default: true)
prune_plan: true (是否自动调整计划,如果是true偏离1米就调整,true就好)##################################
#
# Rivz Display Parameters for Debug
#
################################### publish dwa cost grid point cloud
publish_cost_grid_pc: true   (rviz里是否发布这种点云)# publish dwa trajectory point cloud
publish_traj_pc: true (rviz里是否发布这种轨迹的点云)

下一章讲保存地图及如何用静态地图进行导航,及定位的其他方法,恭喜你初中毕业了。

深入理解如何不费吹灰之力搭建一个无人驾驶车(二)2D-小车其他部分(独创导航各参数解析)相关推荐

  1. 深入理解如何不费吹灰之力搭建一个无人驾驶车(四)2D-小车自主部分(从无到有自己写一个无人驾驶框架)(CSDN独创)

    四.从无到有自己动手写个slam算法(CSDN独创) 注1:必须先看完前三章再看这一章,如果想看得轻松请看<概率机器人>与<机器人学状态估计>完再看 注2:本篇为CSDN独创, ...

  2. 从零开始用 Flask 搭建一个网站(二)

    从零开始用 Flask 搭建一个网站(一) 介绍了如何搭建 Python 环境,以及 Flask 应用基本项目结构.我们要搭建的网站是管理第三方集成的控制台,类似于 Slack. 本篇主要讲解数据如何 ...

  3. 利用闲置的树莓派4B搭建一个NAS(二)

    瞎折腾系列之利用闲置的树莓派搭建一个NAS,本文介绍安装好OpenMediaVault后进行基础配置,成功搭建NAS使用,后续关于OMV的配置和使用,以及如何最简单的进行内网穿透请关注后续博文! 利用 ...

  4. 从零搭建一个无人驾驶系统 —— 线控底盘介绍

    线控底盘是无人车的基础,专业术语来说是将经由交互后的操控信号,通过传感器采集变成电信号后,进行控制处理来控制目标机构.简单可以理解为可以使用编程技术控制的车辆底盘.线控底盘最重要的部分是以下4个部分, ...

  5. klearn 文本分类_使用gensim和sklearn搭建一个文本分类器

    总的来讲,一个完整的文本分类器主要由两个阶段,或者说两个部分组成:一是将文本向量化,将一个字符串转化成向量形式:二是传统的分类器,包括线性分类器,SVM, 神经网络分类器等等. 之前看的THUCTC的 ...

  6. 测试开发——搭建一个简单 web服务(flask框架基础)项目实战

    搭建一个简单 web服务-flask框架 一.什么是wsgi? 二.搭建一个简单 web服务 三.扩展 四.请求加参数的情况 五.安装flask 一.什么是wsgi? wsgi是webserver和a ...

  7. 以前不懂事现在只想搞钱,从0-1搭建一个树莓派小车

    项目来源背景 自从上了大学,感触很多,身为一个计算机系的小白,见识到了大佬们的学识渊博,就此下定决心,要向他们不断的靠近(身为一个什么也不懂的小白,难免都不太愿意跟我交流).起初真正意义上认识树莓派是 ...

  8. 利用闲置的树莓派4B搭建一个NAS(一)

    瞎折腾系列之利用闲置的树莓派搭建一个NAS,本文介绍树莓派系统的安装以及在树莓派上安装OpenMediaVault,后续关于OMV的配置和使用,以及如何最简单的进行内网穿透请关注后续博文! 利用闲置的 ...

  9. 5分钟构建一个自己的无人驾驶车

    心情不够振奋,学个新技术吧! 翻译来源: https://www.youtube.com/watch?v=hBedCdzCoWM 发现了一个特逗儿的小伙儿,有一些5分钟系列的视频,介绍一些人工智能的技 ...

最新文章

  1. 查找算法常见的五大面试知识点与两类实战!
  2. 又现“别人家的公司”!网曝腾讯和快手发“阳光普照奖”,给每个员工100股股票!...
  3. CentOS安装Navicat
  4. 用Python实现Gauss-Jordan求逆矩阵
  5. Leetcode题库 15.三数之和_0(双指针 C实现)
  6. ionic4安卓真机调试
  7. 韩顺平 mysql sqlhelper类_(最全)韩顺平jsp购物车源代码(包含数据库)
  8. python orm_python的orm
  9. python使用curve_fit拟合任意分布
  10. java 拦截jsp页面_JSP 过滤器
  11. 质量和品质的区别_质量体系认证,与产品质量认证的区别 !
  12. 莫烦 python教程学习笔记————搭建自己的神经网络
  13. android qq 邮箱格式,QQ邮箱格式怎么写
  14. 鬼迷心窍 歌词翻译 中译日
  15. 组合总和(python实现)
  16. 关于内存条低压标压以及不同品牌容量内存条组建双通道笔记
  17. Python Flask框架
  18. 孩子沉迷抖音,比打王者更可怕?其中影响你一定想不到!
  19. 分享Web前端开发常用的6种编程语言及其优势!
  20. 《大明宫词》之《采桑女》

热门文章

  1. 【Python自然语言处理】读书笔记:第三章:处理原始文本
  2. 星环TranswarpInceptor通过waterdrop添加表,视图,函数和存储过程
  3. 鹏业软件问题处理记录
  4. 服务器监控cacti
  5. 今日头条财经部门后台研发实习生面试
  6. 【今日头条】【实习】放出一大波职位
  7. Lie-Algebraic Averaging For Globally Consistent Motion Estimation
  8. 专题采访高维视力复健体系创始人 两天看清2.0的四维六度空间集训法
  9. MySQL: Access denied for user 'root'@'localhost' (using password: YES)
  10. 安装python 脚本初稿