Excerpt |
---|
本页介绍了display_virtual_lines的用法, 包含如何在rviz中显示虚拟墙的功能。 |
本页内容
Table of Contents |
---|
运行环境准备
软件平台
- Ubuntu 16.04 AMD04 X86
- ROS Kinetic
硬件平台
(以下任选其一)
- Slamware 套装 (基于Slamware导航方案的用户机器人系统)
- Apollo/Ares/Athena等底盘系统
编译运行
1.下载Slamware ROS SDK以及ROS例程。
2.将ROS sdk中的src文件夹放入一个空的工作目录,如:catkin_ws。将ROS 例程中的slamware_ros_sample文件夹也放入src文件夹下。使用catkin工具初始化工作空间。
Code Block |
---|
cd catkin_ws/src catkin_init_workspace |
3.编译
Code Block |
---|
cd .. catkin_make |
4.配置工作空间系统环境
Code Block |
---|
source devel/setup.bash |
5.启动slamware_ros_sdk_server_node节点
Code Block |
---|
roslaunch slamware_ros_sdk slamware_ros_sdk_server_node.launch ip_address:=10.6.128.141 //如果是AP模式,ip_address是192.168.11.1 |
6.重新打开一个终端窗口,重复第4步,并启动view_slamware_ros_sdk_server_node节点
Code Block |
---|
roslaunch slamware_ros_sdk view_slamware_ros_sdk_server_node.launch |
7.重新打开一个终端窗口,重复第4步,并启动display_virtual_lines_node节点
Code Block |
---|
roslaunch slamware_ros_sample display_virtual_lines.launch |
8.在Rviz中配置添加显示Marker信息。点击Rviz左下角的Add,在弹出的窗口中,选择Marker,点击OK。成功后,会如下图,在Displays加入了一个Marker,虚拟墙也在界面中显示
代码描述
Code Block | ||||||
---|---|---|---|---|---|---|
| ||||||
ros::init(argc, argv, "display_virtual_lines_node"); ros::NodeHandle n; ros::Publisher pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 10); ros::Subscriber sub = n.subscribe<slamware_ros_sdk::Line2DFlt32Array>("/slamware_ros_sdk_server_node/virtual_walls", 30, virtualWallCallback); |
Code Block | ||||
---|---|---|---|---|
| ||||
visualization_msgs::Marker lines; |
Code Block | ||||
---|---|---|---|---|
| ||||
void virtualWallCallback(const slamware_ros_sdk::Line2DFlt32Array::ConstPtr & msg) { lines.points.clear(); size_t cnt = msg->lines.size(); for (size_t i = 0; i < msg->lines.size(); ++i) { geometry_msgs::Point p1; p1.x = msg->lines[i].start.x; p1.y = msg->lines[i].start.y; p1.z = 0.2; geometry_msgs::Point p2; p2.x = msg->lines[i].end.x; p2.y = msg->lines[i].end.y; p2.z = 0.2; lines.points.push_back(p1); lines.points.push_back(p2); } } |
Code Block | ||||
---|---|---|---|---|
| ||||
lines.id = 1; lines.header.frame_id = "slamware_map"; lines.type = visualization_msgs::Marker::LINE_LIST; lines.ns = "lines"; lines.action = visualization_msgs::Marker::ADD; lines.pose.orientation.w = 1.0; lines.scale.x = 0.1; lines.color.r = 1.0; lines.color.a = 1.0; |
Code Block | ||||
---|---|---|---|---|
| ||||
ros::Rate r(30); while(running) { lines.header.stamp = ros::Time::now(); pub.publish(lines); r.sleep(); } |