前言

好久不见,甚是想念。大家好,我是小沐。
书接上文,上一篇文章我们进行了仿真环境的配置但是呢它并没有进行导航相关的配置,所以还不能进行move-base的相关操作,本文将延续上文进行move_base的配置。上一篇文章还给各位萌新同学留了思考任务,不知道各位同学有没有思考,如果没有思考的话,可能会在这篇文章吃到一丢丢苦头哦~

正文

提到move_base就不得不提到这个图了:

导航的基本框架图,老司机们是不是很熟悉呀,这个图可以说是十分的经典了,那因为很多初学者也会看这个文章,所以我们简单了解一下。
这个呢,是ROS 提供的 move_base 功能包的关系图,我们可以使用move_base 功能包在我们利用slam算法(gmapping、hector、cartographer等slam算法)建立好的地图中指定目标位置和方向, 然后move_base 就会根据机器人的传感器信息控制机器人到达目标位置,是不是很神奇,能够达到这样的目的,是因为move_base功能包主要功能包括:结合机器人的里程计信息和定位信息,作出路径规划,输出前进速度和转向速度。目前在机器人SLAM及导航的使用中不可避免地需要使用movebase提供的安全可靠的机制。move_base是导航包Navigation的核心,它包含了很多的插件, 这些插件用于负责一些更细微的任务:全局规划、局部规划、全局地图、局部地图、恢复行为,那简单介绍一下就行了哈,具体的一介绍,就多了去了,总之一句话我们知道move_base是导航包Navigation的核心,我们想要导航就要配置一下它(这里只是为了通俗易懂,大家不要细扣,细扣问题大了去了……)。这里其实有很多东西要讲但是呢真要真要讲起来,一篇博客真的放不开,所以我决定这篇博客我们暂时不讲原理,把它抛开,就硬这头皮告诉大家配置,让大家先玩起来再说,如果车都不能动,那多扫兴不是。


先简单说一下实现导航的流程吧,拿实体车来说(这个大家肯定要知道,虽然不讲原理,但是该有的还是要有滴,以下仅代表个人观点,小沐自己的习惯罢了):
1.配置车的控制器,从底层到上位机,你先保证车能够通过键盘或是手柄操控,保证能跑。
2.配置车的各部分传感器,这其中包括但不仅限于:雷达、imu、利用编码器数据制作的odom、摄像头等……
3.安装amcl解决定位问题,如果你的定位不稳定的话,可能还要将各部分传感器数据进行多传感器数据融合,还可以通过ekf滤波一下啥的(高深了哈~了解就行)
4.等进行完上面的步骤,诶,那么你可以配置move_base导航了,这里呢主要是安装导航功能包然后就是配置相关的yaml文件了。
5.然后就是增加拓展功能,语音、视觉、优化参数等……
是不是很简单呢,那现在我们开始说我们的仿真环境。
我们打开仿真环境,然后我们新开一个终端打开我们的rqt工具箱,分别查看我们的tf树和graph:
tf(命令:rosrun rqt_tf_tree rqt_tf_tree):

根据这个图我们得到关键信息:map数据直接给base_link,传感器或是轮子直接连接在base_link上,那么机器人主坐标系定了base_link,主坐标系我们会在后面的yaml文件里进行修改,而且这里我们得到我们并不需要amcl进行定位,因为是map直接发布的base_link,就很准不需要amcl。
graph(命令:rosrun rqt_graph rqt_graph):

这个图我们得到的关键数据就更多了,我们可以看到诶,车子的控制器是怎样的,还有一个mux_controller(这个是一个数据选择器,我们可以利用它可以选择键盘控制还是手柄控制等等),车子的各个传感器是怎么通过仿真节点f1tenth_simulator发出来并且是发给谁的。这里最为重要的的就是这个drive了,大家可以注意到,我们的控制器是输出给drive的,然后drive发回给了f1tenth_simulator,这意味这什么呢,这意味着我们找到了仿真车的控制反馈节点,我们之后配置move_base控制车,就要用到这个节点了,当然小沐很严谨,那我们验证一下:(命令:rostopic info /drive ,此命令是查看drive的具体信息)

那,阿克曼数据格式有没有,发布者订阅者说明我们找对了!
然后我们可以rostopic echo /drive ,回到启动仿真环境的终端,选择一个控制器控制一下车,你就会发现在这个节点在根据你的控制发出指令。
那么接下来就是十分简单了,这里不知道为什么简单的我来告诉你,因为move_base参数配置十分简单,可很多人配置之后有导航路径但是并不能够发动车子,这是因为move_base发布的cmd_vel是twist数据格式,我们只需要将其进行一个简单转换就好了,也就是说我们写一个简单的python程序订阅cmd_vel获取数据然后进行处理将处理过后的数据发布给drive就好啦(c++也是可以的,大家可以自行设计,我用的teb功能包自带的python转换文件,修改了一下就好,偷懒了哈哈)思路就是这样,那么接下来我们就可以开始配置了。
我呢为了分辨我自己配置的包,我自己新建了一个功能包:
使用命令:catkin_create_pkg 功能包的名字(我的是xiaomu_nav) roscpp rospy std_msgs

然后我们新建一个launch文件夹存放launch文件,一个param文件夹用来放置参数(我这里又在param文件夹下新建了一个teb文件夹用来单独存放teb的参数),一个script文件夹用来放置python文件(c++文件放在src里),新建一个rviz文件夹用来存放rviz。
下面直接一波上一波参数(估计这篇博客就长长的了……):
simulator_nav.launch (我自己改了一下,注释掉了不必要的)

<?xml version="1.0"?>
<launch>
  <!-- Listen to messages from joysicks 
  <node pkg="joy" name="joy_node" type="joy_node"/>-->

  <!-- Launch a map from the maps folder-->
  <arg name="map" default="$(find f1tenth_simulator)/maps/levine.yaml"/>
  <node pkg="map_server" name="map_server" type="map_server" args="$(arg map)"/>

  <!-- Launch the racecar model -->
  <include file="$(find f1tenth_simulator)/launch/racecar_model.launch"/>

  <!-- Begin the simulator with the parameters from params.yaml -->
  <node pkg="f1tenth_simulator" name="f1tenth_simulator" type="simulator" output="screen">
    <rosparam command="load" file="$(find f1tenth_simulator)/params.yaml"/>
  </node>

  <!-- Launch the mux node with the parameters from params.yaml 
  <node pkg="f1tenth_simulator" name="mux_controller" type="mux" output="screen">
    <rosparam command="load" file="$(find f1tenth_simulator)/params.yaml"/>
  </node>
-->
  <!-- Launch the behavior controller node with the parameters from params.yaml 
  <node pkg="f1tenth_simulator" name="behavior_controller" type="behavior_controller" output="screen">
    <rosparam command="load" file="$(find f1tenth_simulator)/params.yaml"/>
  </node>
-->
  <!-- Launch the Random Walker Node 
  <node pkg="f1tenth_simulator" name="random_walker" type="random_walk" output="screen">
    <rosparam command="load" file="$(find f1tenth_simulator)/params.yaml"/>
  </node>
-->
  <!-- Launch the Keyboard Node 
  <node pkg="f1tenth_simulator" name="keyboard" type="keyboard" output="screen">
    <rosparam command="load" file="$(find f1tenth_simulator)/params.yaml"/>
  </node>
-->
  <!-- ***Put launch command for new planner here:-->
  <!-- Launch the New Planner Node -->
  <!--   <node pkg="f1tenth_simulator" name="new node's name" type="new file name" output="screen">
          <rosparam command="load" file="$(find f1tenth_simulator)/params.yaml"/>
       </node>    -->


  <!-- Launch RVIZ -->
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find f1tenth_simulator)/launch/simulator.rviz" output="screen"/>
</launch>

xiaomu_teb_nav.launch( 我自己起的名字哈,大家可以自己设计)

<?xml version="1.0"?>

<launch>

    <!-- map 更换地图
       <arg name="map" default="$(find f1tenth_simulator)/maps/levine_blocked.yaml"/>
    -->
    <arg name="map" default="$(find f1tenth_simulator)/maps/levine.yaml"/>

    <!--simulator 仿真环境 -->
    <include file="$(find f1tenth_simulator)/launch/simulator_nav.launch">
        <arg name="map" value="$(arg map)"/>
    </include>

    <!-- Map server 启动的地图服务 因为我要开两个地图服务所以改了名字另外一个地图服务在仿真环境的launch里-->
    <node name="map_server_slam" pkg="map_server" type="map_server" args="$(find xiaomu_nav)/maps/levine.yaml">
        <remap from="map" to="slam_map"/>
    </node>

    <!-- Navigation  导航参数相关-->
    <node pkg="move_base" type="move_base" respawn="false" name="move_base">
        <rosparam file="$(find xiaomu_nav)/param/teb/move_base_params.yaml" command="load"/> <!---->
        <rosparam file="$(find xiaomu_nav)/param/teb/costmap_common_params.yaml" command="load" ns="global_costmap" />
        <rosparam file="$(find xiaomu_nav)/param/teb/costmap_common_params.yaml" command="load" ns="local_costmap" />
        <rosparam file="$(find xiaomu_nav)/param/teb/local_costmap_params.yaml" command="load" />
        <rosparam file="$(find xiaomu_nav)/param/teb/global_costmap_params.yaml" command="load" />
        <rosparam file="$(find xiaomu_nav)/param/teb/global_planner_params.yaml" command="load" />
        <rosparam file="$(find xiaomu_nav)/param/teb/teb_local_planner_params.yaml" command="load" />        

        <param name="base_global_planner" value="global_planner/GlobalPlanner" />
        <param name="planner_frequency" value="10" /> <!--10   15 -->               
        <param name="planner_patience" value="5" />                  
        <param name="use_dijkstra" value="true" /> 
        <param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
        <param name="controller_frequency" value="5" />             
        <param name="controller_patience" value="5" /> 
    </node>

    <!-- cmd_vel to ackermann_cmd   转换节点 -->
    <node pkg="xiaomu_nav" type="cmd_vel_to_ackermann_drive.py" name="vel_to_ackermann" >
        <param name="twist_cmd_topic" value="/cmd_vel" />
    <param name="ackermann_cmd_topic" value="/drive" />
    </node> 


</launch>

xiaomu_rviz.launch (启动rviz,这是一个专门看代价地图的rviz,注意rviz的name,我改了名字,重名的rviz是不被允许打开的,仿真环境开了一个)

<?xml version="1.0"?>

<launch>

    <node pkg="rviz" type="rviz" name="rviz_nav" args="-d $(find xiaomu_nav)/rviz/teb_nav.rviz"  />

</launch>

costmap_common_params.yaml (代价地图文件)


#---standard pioneer footprint---
#---(in meters)---

footprint: [ [-0.3,-0.2], [0.3,-0.2], [0.3,0.2], [-0.3,0.2] ]

transform_tolerance: 0.2
map_type: costmap

obstacle_layer:
 enabled: true
 obstacle_range: 2.5
 raytrace_range: 3.0
 inflation_radius: 0.2
 track_unknown_space: false
 combination_method: 1

 observation_sources: laser_scan_sensor
 laser_scan_sensor: {data_type: LaserScan, topic: scan, marking: true, clearing: true}


inflation_layer:
  enabled:              true
  cost_scaling_factor:  10.0  # exponential rate at which the obstacle cost drops off (default: 10)
  inflation_radius:     1.0  # max. distance from an obstacle at which costs are incurred for planning paths.

static_layer:
  enabled:              true
  map_topic:            "/map"

global_costmap_params.yaml

global_costmap:
  global_frame: map
  robot_base_frame: base_link
  update_frequency: 5.0
  publish_frequency: 2.0
  transform_tolerance: 0.5
  rolling_window: false
  static_map: false

  transform_tolerance: 0.5

  plugins:
    - {name: static_layer,            type: "costmap_2d::StaticLayer"}
    - {name: obstacle_layer,          type: "costmap_2d::VoxelLayer"}
    - {name: inflation_layer,         type: "costmap_2d::InflationLayer"}

global_planner_params.yaml

GlobalPlanner:
  allow_unknown: true # 是否允许规划器规划穿过未知区域的路径,只设计该参数为true还不行,还要在costmap_commons_params.yaml中设置track_unknown_space参数也为true才行.
  default_tolerance: 0.2 #0.05 # 当设置的目的地被障碍物占据时,需要以该参数为半径寻找到最近的点作为新目的地点
  use_dijkstra: true #true # 设置为true,将使用dijkstra算法,否则使用A*算法 false true
  use_quadratic: true #false  #true # 设置为true,将使用二次函数近似函数,否则使用更加简单的计算方式,这样节省硬件计算资源  false 
  use_grid_path: false #false # 如果设置为true,则会规划一条沿着网格边界的路径,偏向于直线穿越网格,否则将使用梯度下降算法,路径更为光滑点 
  outline_map: false
  old_navfn_behavior: false # 若在某些情况下,想让global_planner完全复制navfn的功能,那就设置为true,但是需要注意navfn是非常旧的ROS系统中使用的,现在已经都用global_planner代替navfn了,所以不建议设置为true.

  visualize_potential: false # 指定是否可视化PointCloud2计算的潜在区域
  publish_potential: false # 发布可行性点话题"potential",false不发布

  lethal_cost: 253 #253 # 致命代价值,默认是设置为253,可以动态来配置该参数.
  neutral_cost: 50 #50 # 中等代价值,默认设置是50,可以动态配置该参数.
  cost_factor: 3.0 # 代价地图与每个代价值相乘的因子.

  orientation_mode: 0 # 如何设置每个点的方向(None = 0,Forward = 1,Interpolate = 2,ForwardThenInterpolate = 3,Backward = 4,Leftward = 5,Rightward = 6)(可动态重新配置)
  orientation_window_size: 1 # 根据orientation_mode指定的位置积分来得到使用窗口的方向.默认值1,可以动态重新配置.

local_costmap_params.yaml

local_costmap:
  global_frame: map
  robot_base_frame: base_link
  update_frequency: 10.0
  publish_frequency: 5.0
  rolling_window: true
  width: 5
  height: 5
  resolution: 0.2
  transform_tolerance: 0.5
  plugins:
   - {name: obstacle_layer,      type: "costmap_2d::ObstacleLayer"}
   - {name: inflation_layer,     type: "costmap_2d::InflationLayer"}

move_base_params.yaml

# Move base node parameters. For full documentation of the parameters in this file, please see
#
#  http://www.ros.org/wiki/move_base
#
shutdown_costmaps: false

#controller_frequency: 10.0
#controller_patience: 3.0

#planner_frequency: 10.0
#planner_patience: 5.0

oscillation_timeout: 10.0
oscillation_distance: 0.2

clearing_rotation_allowed: false

teb_local_planner_params.yaml

TebLocalPlannerROS:

 odom_topic: odom

 # Trajectory

 teb_autosize: True
 dt_ref: 0.3
 dt_hysteresis: 0.1
 max_samples: 500
 global_plan_overwrite_orientation: True
 allow_init_with_backwards_motion: True 
 max_global_plan_lookahead_dist: 3.5 # 3.0 3.5
 global_plan_viapoint_sep: 0.05 # -1 0.05
 global_plan_prune_distance: 1.5
 exact_arc_length: True
 feasibility_check_no_poses: 1
 publish_feedback: False

 # Robot

 max_vel_x: 5
 max_vel_x_backwards: 3.5
 max_vel_y: 0.0
 max_vel_theta: 2.5 # the angular velocity is also bounded by min_turning_radius in case of a carlike robot (r = v / omega)
 acc_lim_x: 3.5
 acc_lim_theta: 1.0

 # ********************** Carlike robot parameters ********************
 min_turning_radius: 0.8        # Min turning radius of the carlike robot (compute value using a model or adjust with rqt_reconfigure manually)
 wheelbase: 0.38                 # Wheelbase of our robot
 cmd_angle_instead_rotvel: false # stage simulator takes the angle instead of the rotvel as input (twist message)
 # ********************************************************************

 footprint_model: # types: "point", "circular", "two_circles", "line", "polygon"
   type: "line"
   radius: 0.2 # for type "circular"
   line_start: [-0.3, 0.0] # for type "line"
   line_end: [0.3, 0.0] # for type "line"


 # GoalTolerance

 xy_goal_tolerance: 0.2
 yaw_goal_tolerance: 0.1
 free_goal_vel: True # False
 complete_global_plan: True

 # Obstacles

 min_obstacle_dist: 0.4 # This value must also include our robot's expansion, since footprint_model is set to "line".
 inflation_dist: 0.6 #0.6
 include_costmap_obstacles: True
 legacy_obstacle_association: False
 costmap_obstacles_behind_robot_dist: 1.0
 obstacle_poses_affected: 30 #15

 dynamic_obstacle_inflation_dist: 0.6
 include_dynamic_obstacles: True 

 costmap_converter_plugin: ""
 costmap_converter_spin_thread: True
 costmap_converter_rate: 5

 # Optimization

 no_inner_iterations: 4
 no_outer_iterations: 3
 optimization_activate: True
 optimization_verbose: False
 penalty_epsilon: 0.1
 obstacle_cost_exponent: 4
 weight_max_vel_x: 100 #1
 weight_max_vel_theta: 1
 weight_acc_lim_x: 10 #1
 weight_acc_lim_theta: 1 #1
 weight_kinematics_nh: 1000
 weight_kinematics_forward_drive: 1000
 weight_kinematics_turning_radius: 1
 weight_optimaltime: 10 # must be > 0
 weight_shortest_path: 0
 weight_obstacle: 200 # 100
 weight_inflation: 10 #0.2
 weight_dynamic_obstacle: 10 # not in use yet
 weight_dynamic_obstacle_inflation: 0.2
 weight_viapoint: 4 #1 1.5
 weight_adapt_factor: 2

 # Homotopy Class Planner

 enable_homotopy_class_planning: False
 enable_multithreading: True
 max_number_classes: 2
 selection_cost_hysteresis: 1.0
 selection_prefer_initial_plan: 0.95
 selection_obst_cost_scale: 1.0
 selection_alternative_time_cost: False

 roadmap_graph_no_samples: 15
 roadmap_graph_area_width: 5
 roadmap_graph_area_length_scale: 1.0
 h_signature_prescaler: 0.5
 h_signature_threshold: 0.1
 obstacle_heading_threshold: 0.45
 switching_blocking_period: 0.0
 viapoints_all_candidates: True
 delete_detours_backwards: True
 max_ratio_detours_duration_best_duration: 3.0
 visualize_hc_graph: False
 visualize_with_time_as_z_axis_scale: False

# Recovery

 shrink_horizon_backup: True
 shrink_horizon_min_duration: 10
 oscillation_recovery: True
 oscillation_v_eps: 0.1
 oscillation_omega_eps: 0.1
 oscillation_recovery_min_duration: 10
 oscillation_filter_duration: 10

这里这个teb参数暂时不给大家讲解了,有些很复杂,要细聊参数这篇博客长了去了,我们暂时抛开这个话题。
cmd_vel_to_ackermann_drive.py(转换节点,这里注意一个参数wheelbase,这是轴距在使用时记得修改,我的已经改好,可以直接使用)

#!/usr/bin/env python

import rospy, math
from geometry_msgs.msg import Twist
from ackermann_msgs.msg import AckermannDriveStamped

def convert_trans_rot_vel_to_steering_angle(v, omega, wheelbase):
  if omega == 0 or v == 0:
    return 0

  radius = v / omega
  return math.atan(wheelbase / radius)


def cmd_callback(data):
  global wheelbase
  global ackermann_cmd_topic
  global frame_id
  global pub

  v = data.linear.x
  steering = convert_trans_rot_vel_to_steering_angle(v, data.angular.z, wheelbase)

  msg = AckermannDriveStamped()
  msg.header.stamp = rospy.Time.now()
  msg.header.frame_id = frame_id
  msg.drive.steering_angle = steering
  msg.drive.speed = v

  pub.publish(msg)


if __name__ == '__main__': 
  try:

    rospy.init_node('cmd_vel_to_ackermann_drive')

    twist_cmd_topic = rospy.get_param('~twist_cmd_topic', '/cmd_vel') 
    ackermann_cmd_topic = rospy.get_param('~ackermann_cmd_topic', '/ackermann_cmd')
    wheelbase = rospy.get_param('~wheelbase', 0.38)
    frame_id = rospy.get_param('~frame_id', 'odom')

    rospy.Subscriber(twist_cmd_topic, Twist, cmd_callback, queue_size=1)
    pub = rospy.Publisher(ackermann_cmd_topic, AckermannDriveStamped, queue_size=1)

    rospy.loginfo("Node 'cmd_vel_to_ackermann_drive' started.\nListening to %s, publishing to %s. Frame id: %s, wheelbase: %f", "/cmd_vel", ackermann_cmd_topic, frame_id, wheelbase)

    rospy.spin()

  except rospy.ROSInterruptException:
    pass

那么,配置完成之后的rqt_graph:

结语

天之博特的F1TENTH无人车挑战答疑课(bilibili):
https://www.bilibili.com/video/BV1Qh411q7FT (其中一节)
一共有如下这些:

大家可以结合这些进行知识补充,我这次的文章并没有写的特别全(推荐大家去看看答疑并跟着操作一下,对搭建还是很有帮助的,因为时间并不长,这也是个很重要的一个学习过程),相当于简单分享了一下我的思路以及我的具体参数能够保证大家可以跑起来并尝试此次的代码。
考虑到大家最后可能还是不能很好的理解文章的意思,文章的最后放上我自己配置好的环境代码:
https://gitee.com/xiaomuxingyan/f1_ws/tree/master/
(ps:出了一些小插曲,提交的f1tenth_simulator文件夹还有tianracer文件夹是空文件,emm可能是因为我自己拉取的代码是我自己代码库的原因,如果大家拉取下来这两个文件夹是空的,没事不要紧,根据上一篇文章进行一下拉取就好了,我自己配置代码都在xiaomu_nav里,它和另外两个包是隔离开来的,大家正确安装好仿真环境后该包可以直接使用,记得读readme。)


谢谢大家观看,我的能力还是有限,总感觉啰嗦了一大堆无用的东西,嗯,下一篇一要有所改善,共勉!如有错误,还请指正,感激不尽!