虚拟墙是在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="~filename" value="$(arg virtual_wall)"/>
</node>

</launch>

4、添加好虚拟激光进去costmap.yaml文件,本来一个scan的,现在添加为两个scan。

obstacle_layer:
enabled: true
combination_method: 1
track_unknown_space: true
obstacle_range: 2.5
raytrace_range: 3.0
observation_sources: scan scan1
scan: {
sensor_frame: /laser_link,
data_type: LaserScan,
topic: /scan,
marking: true,
clearing: true
}
scan1: {
sensor_frame: /laser_link,
data_type: LaserScan,
topic: /virtual_sensor_scan,
marking: true,
clearing: false
}

5、修改wall_publisher.py。

#修改
wall_pub = rospy.Publisher('wall_pose_list', WallList, latch = True)
#为
wall_pub = rospy.Publisher('wall_pose_list', WallList, latch = True,queue_size= 10)

6、可以启动导航包看效果了,后面墙的参数自己再好好消化。

Ros导航虚拟墙设置_git