1. 程式人生 > >三輪全向輪底盤SLAM挖坑系列-虛擬牆

三輪全向輪底盤SLAM挖坑系列-虛擬牆

虛擬牆是在turtlebot2那裡調包出來修改的,主要在RVIZ上面佈置一些虛擬的牆體,並加進去虛擬的鐳射,好讓虛擬的牆體也擁有膨脹區域,機器人到達虛擬牆體能夠進行避障。

1、安裝好yocs_virtual_sensor的包,這個包需要安裝比較多的依賴檔案

$ git clone https://github.com/yujinrobot/yujin_ocs.git
$ sudo apt-get install ros-kinetic-ecl-*
$ git clone https://github.com/yujinrobot/yocs_msgs.git
$ sudo apt-get install ros-kinetic-ar-track-alvar

2、編譯yovs_virtual_sensor包,這個包需要自己更改CMakeLists.txt檔案,不然啟動launch檔案時候會提示找不到節點,主要更改下面這幾句:

## Specify additional locations of header files
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})

## Declare a cpp executable
add_executable(virtual_sensor_node src/virtual_sensor_node.cpp)

## Add cmake target dependencies of the executable/library
add_dependencies(virtual_sensor_node yocs_msgs_gencpp)

## Specify libraries to link a library or executable target against
target_link_libraries(virtual_sensor_node ${catkin_LIBRARIES})

#############
## Install ##
#############

install(TARGETS virtual_sensor_node
        DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

3、配置standalone.launch檔案,需要新增yaml檔案進去,還有虛擬牆的節點。

<launch>
  <arg name="virtual_wall" default="$(find yocs_virtual_sensor)/data/wall_list.yaml"/>
  <node name="virtual_sensor" pkg="yocs_virtual_sensor" type="virtual_sensor_node" >
    <param name="range_min"    value="0.0"/>
    <param name="range_max"    value="6.0"/>
    <param name="frequency"    value="10.0"/>
    <param name="hits_count"   value="3"/>
    <param name="global_frame" value="/map"/>
    <param name="sensor_frame" value="/base_link"/>
  </node>
  <node pkg="tf" type="static_transform_publisher" name="base_to_virtual" args="0 0 0 0 0 0 /base_footprint /virtual_laser 50"/>
  <node name="wall_publisher" pkg="yocs_virtual_sensor" type="wall_publisher.py" required="true" >
    <param name="virtual_wall" value="$(arg virtual_wall)"/>
  </node>

</launch>

4、新增好虛擬鐳射進去costmap.yaml檔案,本來一個scan的,現在新增為兩個scan

obstacle_range: 2.5
raytrace_range: 3.0
footprint: [[-0.3, -0.3], [-0.3, 0.3], [0.3, 0.3], [0.3, -0.3]]
#robot_radius: ir_of_robot
inflation_radius: 0.5
cost_scaling_factor: 10.0
observation_sources: scan1 scan2

scan1: {sensor_frame: base_link,  observation_persistence: 0.0, max_obstacle_height: 0.4, min_obstacle_height: 0.0, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
scan2: {sensor_frame: base_link,  observation_persistence: 0.0, max_obstacle_height: 0.4, min_obstacle_height: 0.0, data_type: LaserScan, topic: /virtual_sensor_scan, marking: true, clearing: false}

5、可以啟動導航包看效果了,後面牆的引數自己再好好消化。