This page introduces the usage of display_virtual_lines, including how to display virtual walls in rviz.


Contents



Environment Setup

software platform

hardware platform

Choose any one below:


Sample Code Download

ROS-Sample Download Link


Compile and Run

  1. Download the Slamware ROS SDK along with ROS examples.
  2. Place the 'src' folder from the ROS SDK into an empty working directory, such as 'catkin_ws'. Also, put the 'slamware_ros_sample' folder from the ROS examples into the 'src' folder.
    mkdir -p catkin_ws/src
    cd catkin_ws/src
  3. Initialize the workspace using the Catkin tool.
    catkin_init_workspace
  4. Compile.
    cd ..
    catkin_make
  5. Set up workspace environment.
    source devel/setup.bash

  6. Launch the slamware_ros_sdk_server_node node. Select the corresponding IP according to the mode.
    roslaunch slamware_ros_sdk slamware_ros_sdk_server_node.launch ip_address:=10.6.128.141    // Station mode
    // If in AP mode, the IP address is 192.168.11.1
  7. Open another terminal, repeat step 5, and start the view_slamware_ros_sdk_server_node node.
    roslaunch slamware_ros_sdk view_slamware_ros_sdk_server_node.launch
  8. Open another terminal, repeat step 5, and start the display_virtual_lines_node node.
    roslaunch slamware_ros_sample display_virtual_lines.launch
  9. Configure and add the display of Marker information in Rviz: 
    Click 'Add' in the bottom-left corner of Rviz, then in the pop-up window, select 'Marker' and click 'OK'. Upon success, as shown in the image below, a Marker is added to Displays, and the virtual walls are also displayed in the interface.


Code Description

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);
visualization_msgs::Marker lines;
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);
    }
}
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;
ros::Rate r(30);
while(running)
    {
        lines.header.stamp = ros::Time::now();
        pub.publish(lines);

        r.sleep();
    }