介绍:
与其他显示器不同,标记显示器允许您在rviz中可视化数据,而无需了解有关解释该数据的任何信息。相反,原始对象通过visualization_msgs / Marker消息发送到显示器,使您可以显示箭头,方框,球体和线条等内容。
本教程将向您展示如何发送四种基本形状(盒子,球体,圆柱体和箭头)。我们将创建一个程序,每秒发送一个新标记,用不同的形状替换最后一个标记。
第一步:新建一个ros工作包
mkdir -p ~/catkin_2/src
catkin_create_pkg using_markers roscpp visualization_msgs
cd ~/catkin_2
catkin_make
第二步:编写basic_shapes.cpp文件
#include
#include
int main( int argc, char** argv )
{
//初始化ROS,幷且创建一个ROS::Publisher 在话题visualization_marker上面
ros::init(argc, argv, "basic_shapes");
ros::NodeHandle n;
ros::Rate r(1);
ros::Publisher marker_pub = n.advertise
// Set our initial shape type to be a cube
// 初始化形状为立方体
uint32_t shape = visualization_msgs::Marker::CUBE;
while (ros::ok())
{
//实例化一个Marker
visualization_msgs::Marker marker;
// Set the frame ID and timestamp. See the TF tutorials for information on these.
// 设置frame ID 和 时间戳
marker.header.frame_id = "/my_frame";
marker.header.stamp = ros::Time::now();
// Set the namespace and id for this marker. This serves to create a unique ID
// Any marker sent with the same namespace and id will overwrite the old one
// 为这个marker设置一个独一无二的ID,一个marker接收到相同ns和id就会用新的信息代替旧的
marker.ns = "basic_shapes";
marker.id = 0;
// Set the marker type. Initially this is CUBE, and cycles between that and SPHERE, ARROW, and CYLINDER
// 设置marker类型,初始化是立方体。将进行循环
marker.type = shape;
// Set the marker action. Options are ADD, DELETE, and new in ROS Indigo: 3 (DELETEALL)
marker.action = visualization_msgs::Marker::ADD;
// Set the pose of the marker. This is a full 6DOF pose relative to the frame/time specified in the header
// 设置marker的位置
marker.pose.position.x = 0;
marker.pose.position.y = 0;
marker.pose.position.z = 0;
marker.pose.orientation.x = 0.0;
marker.pose.orientation.y = 0.0;
marker.pose.orientation.z = 0.0;
marker.pose.orientation.w = 1.0;
// Set the scale of the marker -- 1x1x1 here means 1m on a side
// 设置marker的大小
marker.scale.x = 1.0;
marker.scale.y = 1.0;
marker.scale.z = 1.0;
// Set the color -- be sure to set alpha to something non-zero!
// 设置marker的颜色
marker.color.r = 0.0f;
marker.color.g = 1.0f;
marker.color.b = 0.0f;
marker.color.a = 1.0;
//取消自动删除
marker.lifetime = ros::Duration();
// Publish the marker
// 必须有订阅者才会发布消息
while (marker_pub.getNumSubscribers() < 1)
{
if (!ros::ok())
{
return 0;
}
ROS_WARN_ONCE("Please create a subscriber to the marker");
sleep(1);
}
marker_pub.publish(marker);
// Cycle between different shapes
// 连续改变形状
switch (shape)
{
case visualization_msgs::Marker::CUBE:
shape = visualization_msgs::Marker::SPHERE;
break;
case visualization_msgs::Marker::SPHERE:
shape = visualization_msgs::Marker::ARROW;
break;
case visualization_msgs::Marker::ARROW:
shape = visualization_msgs::Marker::CYLINDER;
break;
case visualization_msgs::Marker::CYLINDER:
shape = visualization_msgs::Marker::CUBE;
break;
}
r.sleep();
}
}
第三步:在Cmakelist.txt文件中添加依赖关系
add_executable(basic_shapes src/basic_shapes.cpp) target_link_libraries(basic_shapes ${catkin_LIBRARIES})
第四步:编译
catkin_make
source catkin_2/devel/setup.bash
第五步:运行
(一)打开roscore
rosrun roscore
(二)运行编写的发布器
rosrun using_markers basic_shapes
(三)重置rviz,运行rviz
rosmake rviz
rosrun rviz rviz
(四)在rviz中设置
添加Marker栏
且将Global Options中的Fixed Fram改为my_frame
即可得到如下图像