小猫

版主
  • 主题:39
  • 回复:39
  • 金钱:132
  • 积分:181
在理解了move_base的基础上,我们开始机器人的定位与导航。gmaping包是用来生成地图的,需要使用实际的机器人获取激光或者深度数据,所以我们先在已有的地图上进行导航与定位的仿真。
        amcl是移动机器人二维环境下的概率定位系统。它实现了自适应(或kld采样)的蒙特卡罗定位方法,其中针对已有的地图使用粒子滤波器跟踪一个机器人的姿态。
一、测试
        首先运行机器人节点:
  1. [plain] view plaincopy
  2. roslaunch rbx1_bringup fake_turtlebot.launch  
复制代码
      然后运行amcl节点,使用测试地图:
  1. [plain] view plaincopy
  2. roslaunch rbx1_nav fake_amcl.launch map:=test_map.yaml  
复制代码
     可以看一下fake_amcl.launch这个文件的内容:
  1. [plain] view plaincopy
  2. <launch>  
  3.   <!-- Set the name of the map yaml file: can be overridden on the command line. -->  
  4.   <arg name="map" default="test_map.yaml" />  
  5.   <!-- Run the map server with the desired map -->  
  6.   <node name="map_server" pkg="map_server" type="map_server" args="$(find rbx1_nav)/maps/$(arg map)"/>  
  7.   <!-- The move_base node -->  
  8.   <include file="$(find rbx1_nav)/launch/fake_move_base.launch" />  
  9.    
  10.   <!-- Run fake localization compatible with AMCL output -->  
  11.   <node pkg="fake_localization" type="fake_localization"  name="fake_localization" output="screen" />  
  12.   <!-- For fake localization we need static transforms between /odom and /map and /map and /world -->  
  13.   <node pkg="tf" type="static_transform_publisher" name="odom_map_broadcaster"   
  14. args="0 0 0 0 0 0 /odom /map 100" />  
  15. </launch>  
复制代码
这个lanuch文件作用是加载地图,并且调用fake_move_base.launch文件打开move_base节点并加载配置文件,最后运行amcl
         然后运行rviz
  1. [plain] view plaincopy
  2. rosrun rviz rviz -d `rospack find rbx1_nav`/nav_fuerte.vcg  
复制代码
这时在rvoiz中就应该显示出了地图和机器人:

现在就可以通过rviz在地图上选择目标位置了,然后就会看到机器人自动规划出一条全局路径,并且导航前进:


二、自主导航
        在实际应用中,我们往往希望机器人能够自主进行定位和导航,不需要认为的干预,这样才更智能化。在这一节的测试中,我们让目标点在地图中随机生成,然后机器人自动导航到达目标。
        这里运行的主要文件是:fake_nav_test.launch,让我们来看一下这个文件的内容:   
  1. [plain] view plaincopy
  2. <launch>  
  3.   
  4.   <param name="use_sim_time" value="false" />  
  5.   
  6.   <!-- Start the ArbotiX controller -->  
  7.   <include file="$(find rbx1_bringup)/launch/fake_turtlebot.launch" />  
  8.   
  9.   <!-- Run the map server with the desired map -->  
  10.   <node name="map_server" pkg="map_server" type="map_server" args="$(find rbx1_nav)/maps/test_map.yaml"/>  
  11.   
  12.   <!-- The move_base node -->  
  13.   <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">  
  14.     <rosparam file="$(find rbx1_nav)/config/fake/costmap_common_params.yaml" command="load" ns="global_costmap" />  
  15.     <rosparam file="$(find rbx1_nav)/config/fake/costmap_common_params.yaml" command="load" ns="local_costmap" />  
  16.     <rosparam file="$(find rbx1_nav)/config/fake/local_costmap_params.yaml" command="load" />  
  17.     <rosparam file="$(find rbx1_nav)/config/fake/global_costmap_params.yaml" command="load" />  
  18.     <rosparam file="$(find rbx1_nav)/config/fake/base_local_planner_params.yaml" command="load" />  
  19.     <rosparam file="$(find rbx1_nav)/config/nav_test_params.yaml" command="load" />  
  20.   </node>  
  21.    
  22.   <!-- Run fake localization compatible with AMCL output -->  
  23.   <node pkg="fake_localization" type="fake_localization" name="fake_localization" output="screen" />  
  24.    
  25.   <!-- For fake localization we need static transform between /odom and /map -->  
  26.   <node pkg="tf" type="static_transform_publisher" name="map_odom_broadcaster" args="0 0 0 0 0 0 /map /odom 100" />  
  27.    
  28.   <!-- Start the navigation test -->  
  29.   <node pkg="rbx1_nav" type="nav_test.py" name="nav_test" output="screen">  
  30.     <param name="rest_time" value="1" />  
  31.     <param name="fake_test" value="true" />  
  32.   </node>  
  33.    
  34. </launch>  
复制代码

这个lanuch的功能比较多:
      1) 加载机器人驱动
      2) 加载地图
      3) 启动move_base节点,并且加载配置文件
      4) 运行amcl节点
      5) 然后加载nav_test.py执行文件,进行随机导航
        相当于是把我们之前实验中的多个lanuch文件合成了一个文件。
        现在开始进行测试,先运行ROS
  1. [plain] view plaincopy
  2. roscore  
复制代码

然后我们运行一个监控的窗口,可以实时看到机器人发送的数据:
  1. [plain] view plaincopy
  2. rxconsole  
复制代码
接着运行lanuch文件,并且在一个新的终端中打开rviz
  1. [plain] view plaincopy
  2. roslaunch rbx1_nav fake_nav_test.launch  
  3. (打开新终端)  
  4. rosrun rviz rviz -d `rospack find rbx1_nav`/nav_test_fuerte.vcg  
复制代码

        好了,此时就看到了机器人已经放在地图当中了。然后我们点击rviz上的“2D Pose Estimate”按键,然后左键在机器人上单击,让绿色的箭头和黄色的箭头重合,机器人就开始随机选择目标导航了:


在监控窗口中,我们可以看到机器人发送的状态信息:
三、导航代码分析
  1. [plain] view plaincopy
  2. #!/usr/bin/env python  
  3.   
  4. import roslib; roslib.load_manifest('rbx1_nav')  
  5. import rospy  
  6. import actionlib  
  7. from actionlib_msgs.msg import *  
  8. from geometry_msgs.msg import Pose, PoseWithCovarianceStamped, Point, Quaternion, Twist  
  9. from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal  
  10. from random import sample  
  11. from math import pow, sqrt  
  12.   
  13. class NavTest():  
  14.     def __init__(self):  
  15.         rospy.init_node('nav_test', anonymous=True)  
  16.          
  17.         rospy.on_shutdown(self.shutdown)  
  18.          
  19.         # How long in seconds should the robot pause at each location?  
  20.         # 在每个目标位置暂停的时间  
  21.         self.rest_time = rospy.get_param("~rest_time", 10)  
  22.          
  23.         # Are we running in the fake simulator?  
  24.         # 是否仿真?  
  25.         self.fake_test = rospy.get_param("~fake_test", False)  
  26.          
  27.         # Goal state return values  
  28.         # 到达目标的状态  
  29.         goal_states = ['PENDING', 'ACTIVE', 'PREEMPTED',   
  30.                        'SUCCEEDED', 'ABORTED', 'REJECTED',  
  31.                        'PREEMPTING', 'RECALLING', 'RECALLED',  
  32.                        'LOST']  
  33.          
  34.         # Set up the goal locations. Poses are defined in the map frame.   
  35.         # An easy way to find the pose coordinates is to point-and-click  
  36.         # Nav Goals in RViz when running in the simulator.  
  37.         # Pose coordinates are then displayed in the terminal  
  38.         # that was used to launch RViz.  
  39.         # 设置目标点的位置  
  40.         # 如果想要获得某一点的坐标,在rviz中点击 2D Nav Goal 按键,然后单机地图中一点  
  41.         # 在终端中就会看到坐标信息  
  42.         locations = dict()  
  43.          
  44.         locations['hall_foyer'] = Pose(Point(0.643, 4.720, 0.000), Quaternion(0.000, 0.000, 0.223, 0.975))  
  45.         locations['hall_kitchen'] = Pose(Point(-1.994, 4.382, 0.000), Quaternion(0.000, 0.000, -0.670, 0.743))  
  46.         locations['hall_bedroom'] = Pose(Point(-3.719, 4.401, 0.000), Quaternion(0.000, 0.000, 0.733, 0.680))  
  47.         locations['living_room_1'] = Pose(Point(0.720, 2.229, 0.000), Quaternion(0.000, 0.000, 0.786, 0.618))  
  48.         locations['living_room_2'] = Pose(Point(1.471, 1.007, 0.000), Quaternion(0.000, 0.000, 0.480, 0.877))  
  49.         locations['dining_room_1'] = Pose(Point(-0.861, -0.019, 0.000), Quaternion(0.000, 0.000, 0.892, -0.451))  
  50.          
  51.         # Publisher to manually control the robot (e.g. to stop it)  
  52.         # 发布控制机器人的消息  
  53.         self.cmd_vel_pub = rospy.Publisher('cmd_vel', Twist)  
  54.          
  55.         # Subscribe to the move_base action server  
  56.         # 订阅move_base服务器的消息  
  57.         self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)  
  58.          
  59.         rospy.loginfo("Waiting for move_base action server...")  
  60.          
  61.         # Wait 60 seconds for the action server to become available  
  62.         # 60s等待时间限制  
  63.         self.move_base.wait_for_server(rospy.Duration(60))  
  64.          
  65.         rospy.loginfo("Connected to move base server")  
  66.          
  67.         # A variable to hold the initial pose of the robot to be set by   
  68.         # the user in RViz  
  69.         # 保存机器人的在rviz中的初始位置  
  70.         initial_pose = PoseWithCovarianceStamped()  
  71.          
  72.         # Variables to keep track of success rate, running time,  
  73.         # and distance traveled  
  74.         # 保存成功率、运行时间、和距离的变量  
  75.         n_locations = len(locations)  
  76.         n_goals = 0  
  77.         n_successes = 0  
  78.         i = n_locations  
  79.         distance_traveled = 0  
  80.         start_time = rospy.Time.now()  
  81.         running_time = 0  
  82.         location = ""  
  83.         last_location = ""  
  84.          
  85.         # Get the initial pose from the user  
  86.         # 获取初始位置(仿真中可以不需要)  
  87.         rospy.loginfo("*** Click the 2D Pose Estimate button in RViz to set the robot's initial pose...")  
  88.         rospy.wait_for_message('initialpose', PoseWithCovarianceStamped)  
  89.         self.last_location = Pose()  
  90.         rospy.Subscriber('initialpose', PoseWithCovarianceStamped, self.update_initial_pose)  
  91.          
  92.         # Make sure we have the initial pose  
  93.         # 确保有初始位置  
  94.         while initial_pose.header.stamp == "":  
  95.             rospy.sleep(1)  
  96.               
  97.         rospy.loginfo("Starting navigation test")  
  98.          
  99.         # Begin the main loop and run through a sequence of locations  
  100.         # 开始主循环,随机导航  
  101.         while not rospy.is_shutdown():  
  102.             # If we've gone through the current sequence,  
  103.             # start with a new random sequence  
  104.             # 如果已经走完了所有点,再重新开始排序  
  105.             if i == n_locations:  
  106.                 i = 0  
  107.                 sequence = sample(locations, n_locations)  
  108.                 # Skip over first location if it is the same as  
  109.                 # the last location  
  110.                 # 如果最后一个点和第一个点相同,则跳过  
  111.                 if sequence[0] == last_location:  
  112.                     i = 1  
  113.               
  114.             # Get the next location in the current sequence  
  115.             # 在当前的排序中获取下一个目标点  
  116.             location = sequence[i]  
  117.                           
  118.             # Keep track of the distance traveled.  
  119.             # Use updated initial pose if available.  
  120.             # 跟踪形式距离  
  121.             # 使用更新的初始位置  
  122.             if initial_pose.header.stamp == "":  
  123.                 distance = sqrt(pow(locations[location].position.x -   
  124.                                     locations[last_location].position.x, 2) +  
  125.                                 pow(locations[location].position.y -   
  126.                                     locations[last_location].position.y, 2))  
  127.             else:  
  128.                 rospy.loginfo("Updating current pose.")  
  129.                 distance = sqrt(pow(locations[location].position.x -   
  130.                                     initial_pose.pose.pose.position.x, 2) +  
  131.                                 pow(locations[location].position.y -   
  132.                                     initial_pose.pose.pose.position.y, 2))  
  133.                 initial_pose.header.stamp = ""  
  134.               
  135.             # Store the last location for distance calculations  
  136.             # 存储上一次的位置,计算距离  
  137.             last_location = location  
  138.               
  139.             # Increment the counters  
  140.             # 计数器加1  
  141.             i += 1  
  142.             n_goals += 1  
  143.          
  144.             # Set up the next goal location  
  145.             # 设定下一个目标点  
  146.             self.goal = MoveBaseGoal()  
  147.             self.goal.target_pose.pose = locations[location]  
  148.             self.goal.target_pose.header.frame_id = 'map'  
  149.             self.goal.target_pose.header.stamp = rospy.Time.now()  
  150.               
  151.             # Let the user know where the robot is going next  
  152.             # 让用户知道下一个位置  
  153.             rospy.loginfo("Going to: " + str(location))  
  154.               
  155.             # Start the robot toward the next location  
  156.             # 向下一个位置进发  
  157.             self.move_base.send_goal(self.goal)  
  158.               
  159.             # Allow 5 minutes to get there  
  160.             # 五分钟时间限制  
  161.             finished_within_time = self.move_base.wait_for_result(rospy.Duration(300))   
  162.               
  163.             # Check for success or failure  
  164.             # 查看是否成功到达  
  165.             if not finished_within_time:  
  166.                 self.move_base.cancel_goal()  
  167.                 rospy.loginfo("Timed out achieving goal")  
  168.             else:  
  169.                 state = self.move_base.get_state()  
  170.                 if state == GoalStatus.SUCCEEDED:  
  171.                     rospy.loginfo("Goal succeeded!")  
  172.                     n_successes += 1  
  173.                     distance_traveled += distance  
  174.                     rospy.loginfo("State:" + str(state))  
  175.                 else:  
  176.                   rospy.loginfo("Goal failed with error code: " + str(goal_states[state]))  
  177.               
  178.             # How long have we been running?  
  179.             # 运行所用时间  
  180.             running_time = rospy.Time.now() - start_time  
  181.             running_time = running_time.secs / 60.0  
  182.               
  183.             # Print a summary success/failure, distance traveled and time elapsed  
  184.             # 输出本次导航的所有信息  
  185.             rospy.loginfo("Success so far: " + str(n_successes) + "/" +   
  186.                           str(n_goals) + " = " +   
  187.                           str(100 * n_successes/n_goals) + "%")  
  188.             rospy.loginfo("Running time: " + str(trunc(running_time, 1)) +   
  189.                           " min Distance: " + str(trunc(distance_traveled, 1)) + " m")  
  190.             rospy.sleep(self.rest_time)  
  191.               
  192.     def update_initial_pose(self, initial_pose):  
  193.         self.initial_pose = initial_pose  
  194.   
  195.     def shutdown(self):  
  196.         rospy.loginfo("Stopping the robot...")  
  197.         self.move_base.cancel_goal()  
  198.         rospy.sleep(2)  
  199.         self.cmd_vel_pub.publish(Twist())  
  200.         rospy.sleep(1)  
  201.         
  202. def trunc(f, n):  
  203.     # Truncates/pads a float f to n decimal places without rounding  
  204.     slen = len('%.*f' % (n, f))  
  205.     return float(str(f)[:slen])  
  206.   
  207. if __name__ == '__main__':  
  208.     try:  
  209.         NavTest()  
  210.         rospy.spin()  
  211.     except rospy.ROSInterruptException:  
  212.         rospy.loginfo("AMCL navigation test finished.")  
复制代码