RViz学习笔记(三) - Markers: 点和线(C++)
1 介绍
上一节我们学习了怎么发送简单的形状到rviz,现在我们要放松一些更加复杂的东西。可以发送的所有东西,可以看这里
2 使用点、线纹和线列表
POINTS, LINE_STRIP 和 LINE_LIST三种marker全都使用了visualization_msgs/Marker消息的points成员。POINTS 类型就是在每个点增加一个点(这句式……)。LINE_STRIP类型把每个点作为一组连接的线的顶点( where point 0 is connected to point 1, 1 to 2, 2 to 3, etc.)。LINE_LIST类型为没对点创建不互相连接的线( i.e. point 0 to 1, 2 to 3, etc)。
2.1 源码
#include <ros/ros.h>
#include <visualization_msgs/Marker.h>
#include <cmath>
int main( int argc, char** argv )
{
ros::init(argc, argv, "points_and_lines");
ros::NodeHandle n;
ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 10);
ros::Rate r(30);
float f = 0.0;
while (ros::ok())
{
visualization_msgs::Marker points, line_strip, line_list;
points.header.frame_id = line_strip.header.frame_id = line_list.header.frame_id = "/my_frame";
points.header.stamp = line_strip.header.stamp = line_list.header.stamp = ros::Time::now();
points.ns = line_strip.ns = line_list.ns = "points_and_lines";
points.action = line_strip.action = line_list.action = visualization_msgs::Marker::ADD;
points.pose.orientation.w = line_strip.pose.orientation.w = line_list.pose.orientation.w = 1.0;
points.id = 0;
line_strip.id = 1;
line_list.id = 2;
points.type = visualization_msgs::Marker::POINTS;
line_strip.type = visualization_msgs::Marker::LINE_STRIP;
line_list.type = visualization_msgs::Marker::LINE_LIST;
// POINTS markers use x and y scale for width/height respectively
points.scale.x = 0.2;
points.scale.y = 0.2;
// LINE_STRIP/LINE_LIST markers use only the x component of scale, for the line width
line_strip.scale.x = 0.1;
line_list.scale.x = 0.1;
// Points are green
points.color.g = 1.0f;
points.color.a = 1.0;
// Line strip is blue
line_strip.color.b = 1.0;
line_strip.color.a = 1.0;
// Line list is red
line_list.color.r = 1.0;
line_list.color.a = 1.0;
// Create the vertices for the points and lines
for (uint32_t i = 0; i < 100; ++i)
{
float y = 5 * sin(f + i / 100.0f * 2 * M_PI);
float z = 5 * cos(f + i / 100.0f * 2 * M_PI);
geometry_msgs::Point p;
p.x = (int32_t)i - 50;
p.y = y;
p.z = z;
points.points.push_back(p);
line_strip.points.push_back(p);
// The line list needs two points for each line
line_list.points.push_back(p);
p.z += 1.0;
line_list.points.push_back(p);
}
marker_pub.publish(points);
marker_pub.publish(line_strip);
marker_pub.publish(line_list);
r.sleep();
f += 0.04;
}
}
2.2 源码解析
整体效果就是创建一个……额,看最后的图片吧。
visualization_msgs::Marker points, line_strip, line_list;
points.header.frame_id = line_strip.header.frame_id = line_list.header.frame_id = "/my_frame";
points.header.stamp = line_strip.header.stamp = line_list.header.stamp = ros::Time::now();
points.ns = line_strip.ns = line_list.ns = "points_and_lines";
points.action = line_strip.action = line_list.action = visualization_msgs::Marker::ADD;
points.pose.orientation.w = line_strip.pose.orientation.w = line_list.pose.orientation.w = 1.0;
这里我们创建了三个visualization_msgs/Marker类型的message,并且初始化里他们的共享数据。我们只设定了pose的成员w为1,其他值没有设置,默认为0.
points.id = 0;
line_strip.id = 1;
line_list.id = 2;
我们为三个marker分配了不同的id。前面设置了namespace为points_and_lines保证了它们不会与别的相同id的东西冲突。
points.type = visualization_msgs::Marker::POINTS;
line_strip.type = visualization_msgs::Marker::LINE_STRIP;
line_list.type = visualization_msgs::Marker::LINE_LIST;
这里我们设置了marker的类型。
// POINTS markers use x and y scale for width/height respectively
points.scale.x = 0.2;
points.scale.y = 0.2;
// LINE_STRIP/LINE_LIST markers use only the x component of scale, for the line width
line_strip.scale.x = 0.1;
line_list.scale.x = 0.1;
scale成员在这里对于不同的marker类型代表了不同的含义。POINTS marker将x,y分别用作宽和高。LINE_STRIP marker和LINE_LIST marker只需要x,定义线的宽度,scale的单位是米。
// Points are green
points.color.g = 1.0f;
points.color.a = 1.0;
// Line strip is blue
line_strip.color.b = 1.0;
line_strip.color.a = 1.0;
// Line list is red
line_list.color.r = 1.0;
line_list.color.a = 1.0;
这里我们定义了三种marker的颜色。
// Create the vertices for the points and lines
for (uint32_t i = 0; i < 100; ++i)
{
float y = 5 * sin(f + i / 100.0f * 2 * M_PI);
float z = 5 * cos(f + i / 100.0f * 2 * M_PI);
geometry_msgs::Point p;
p.x = (int32_t)i - 50;
p.y = y;
p.z = z;
points.points.push_back(p);
line_strip.points.push_back(p);
// The line list needs two points for each line
line_list.points.push_back(p);
p.z += 1.0;
line_list.points.push_back(p);
}
我们使用sine和cosine生成一个螺旋线。POINTS 和 LINE_STRIP marker一个顶点只需要一个point,LINE_LIST需要两个。
2.3 显示marker
编辑CMakeLists.txt文件,在最后加上:
add_executable(points_and_lines src/points_and_lines.cpp)
target_link_libraries(points_and_lines ${catkin_LIBRARIES})
然后 回到工作区:
cd
cd catkin_ws_me
这是我的工作区。
然后编译:
catkin_make
然后启动rviz:
$ rosrun rviz rviz &
记得把Fixed Frame改成 /my_frame,并且add一个marker,才能正常显示。
启动发送程序:
$ rosrun using_markers points_and_lines
然后会看到这样一个动态的东西,有什么问题可以看上一个教程:
螺旋线