3 #include "visualization_msgs/Marker.h" 
    4 #include "visualization_msgs/MarkerArray.h" 
    7 #include <geometry_msgs/TransformStamped.h> 
   12 void emitRow(
const std::string& type_name,
 
   20              bool frame_locked = 
true,
 
   21              const std::string& frame_id = std::string(
"base_link"),
 
   26   static uint32_t count = 0;
 
   27   for (
int i = -5; i <= 5; ++i)
 
   29     visualization_msgs::Marker marker;
 
   30     marker.header.frame_id = frame_id;
 
   32     marker.header.stamp = ros_time;
 
   33     marker.ns = 
"marker_test_" + type_name;
 
   36     marker.action = visualization_msgs::Marker::ADD;
 
   37     marker.pose.position.x = x_pos;
 
   38     marker.pose.position.y = (i * 2);
 
   39     marker.pose.position.z = 0;
 
   40     marker.pose.orientation.x = 0.0;
 
   41     marker.pose.orientation.y = 0.0;
 
   42     marker.pose.orientation.z = 0.0;
 
   43     marker.pose.orientation.w = 1.0;
 
   50     marker.color.a = float(i + 5) / 10.0;
 
   52     marker.lifetime = lifetime;
 
   53     marker.frame_locked = frame_locked;
 
   54     if (type == visualization_msgs::Marker::TEXT_VIEW_FACING)
 
   56       marker.text = 
"This is some text\nthis is a new line\nthis is another line\nand another with utf8 " 
   57                     "symbols: äöüÄÖÜ\na really really really really really really really really really " 
   59       marker.scale.x = marker.scale.y = 0.0;
 
   61     else if (type == visualization_msgs::Marker::POINTS)
 
   65     else if (type == visualization_msgs::Marker::MESH_RESOURCE)
 
   67       marker.mesh_resource = 
"package://pr2_description/meshes/base_v0/base.dae";
 
   68       marker.mesh_use_embedded_materials = (i > int((count / 12) % 5));
 
   78   static uint32_t counter = 0;
 
   87   emitRow(
"cubes_frame_locked", visualization_msgs::Marker::CUBE, x_pos, 1.0, 1.0, 0.0, 
ros::Duration(),
 
   96   emitRow(
"arrows_with_lifetime", visualization_msgs::Marker::ARROW, x_pos, 0.0, 1.0, 0.0,
 
   99   emitRow(
"cubes_with_lifetime", visualization_msgs::Marker::CUBE, x_pos, 0.0, 0.0, 1.0,
 
  102   emitRow(
"spheres_with_lifetime", visualization_msgs::Marker::SPHERE, x_pos, 1.0, 0.0, 0.0,
 
  105   emitRow(
"cylinder_with_lifetime", visualization_msgs::Marker::CYLINDER, x_pos, 0.0, 1.0, 0.0,
 
  108   emitRow(
"text_view_facing", visualization_msgs::Marker::TEXT_VIEW_FACING, x_pos, 1.0, 1.0, 1.0,
 
  111   emitRow(
"mesh_resource", visualization_msgs::Marker::MESH_RESOURCE, x_pos, 0.0, 1.0, 1.0,
 
  115   emitRow(
"invalid_scales", visualization_msgs::Marker::CUBE, x_pos, 0.0, 1.0, 1.0, 
ros::Duration(),
 
  120     for (
int i = -5; i <= 5; ++i)
 
  122       visualization_msgs::Marker marker;
 
  123       marker.header.frame_id = 
"base_link";
 
  125       marker.ns = 
"marker_test_arrow_by_points";
 
  127       marker.type = visualization_msgs::Marker::ARROW;
 
  128       marker.action = visualization_msgs::Marker::ADD;
 
  129       marker.pose.orientation.x = 0.0;
 
  130       marker.pose.orientation.y = 0.0;
 
  131       marker.pose.orientation.z = 0.0;
 
  132       marker.pose.orientation.w = 1.0;
 
  133       marker.pose.position.x = x_pos;
 
  134       marker.pose.position.y = i * 2;
 
  135       marker.scale.x = 0.25;
 
  136       marker.scale.y = 0.5;
 
  137       marker.color.r = 0.0;
 
  138       marker.color.g = 1.0;
 
  139       marker.color.b = 1.0;
 
  140       marker.color.a = 1.0;
 
  141       marker.frame_locked = 
true;
 
  143       if (counter % 2 == 0)
 
  145         marker.points.resize(0);
 
  149         marker.points.resize(2);
 
  150         marker.points[0].x = 0.0f;
 
  151         marker.points[0].y = 0.0f;
 
  152         marker.points[0].z = 0.0f;
 
  153         marker.points[1].x = 1.0f;
 
  154         marker.points[1].y = 0.0f;
 
  155         marker.points[1].z = 0.0f;
 
  164     visualization_msgs::Marker marker;
 
  165     marker.header.frame_id = 
"base_link";
 
  167     marker.ns = 
"marker_test_cube_list";
 
  169     marker.type = visualization_msgs::Marker::CUBE_LIST;
 
  170     marker.action = visualization_msgs::Marker::ADD;
 
  171     marker.pose.orientation.x = 0.0;
 
  172     marker.pose.orientation.y = 0.0;
 
  173     marker.pose.orientation.z = 0.0;
 
  174     marker.pose.orientation.w = 1.0;
 
  175     marker.pose.position.x = x_pos;
 
  176     marker.scale.x = 0.05;
 
  177     marker.scale.y = 0.05;
 
  178     marker.scale.z = 0.05;
 
  179     marker.color.r = 1.0;
 
  180     marker.color.g = 1.0;
 
  181     marker.color.b = 0.0;
 
  182     marker.color.a = 1.0;
 
  183     marker.frame_locked = 
true;
 
  185     for (
int x = 0; x < 10; ++x)
 
  187       for (
int y = 0; y < 10; ++y)
 
  189         for (
int z = 0; z < 10; ++z)
 
  191           geometry_msgs::Point p;
 
  196           marker.points.push_back(p);
 
  206     visualization_msgs::Marker marker;
 
  207     marker.header.frame_id = 
"base_link";
 
  209     marker.ns = 
"marker_test_cube_list_color_per";
 
  211     marker.type = visualization_msgs::Marker::CUBE_LIST;
 
  212     marker.action = visualization_msgs::Marker::ADD;
 
  213     marker.pose.orientation.x = 0.0;
 
  214     marker.pose.orientation.y = 0.0;
 
  215     marker.pose.orientation.z = 0.0;
 
  216     marker.pose.orientation.w = 1.0;
 
  217     marker.pose.position.x = x_pos;
 
  218     marker.scale.x = 0.05;
 
  219     marker.scale.y = 0.05;
 
  220     marker.scale.z = 0.05;
 
  221     marker.color.r = 1.0;
 
  222     marker.color.g = 1.0;
 
  223     marker.color.b = 0.0;
 
  224     marker.color.a = 1.0;
 
  225     marker.frame_locked = 
true;
 
  227     for (
int x = 0; x < 10; ++x)
 
  229       for (
int y = 0; y < 10; ++y)
 
  231         for (
int z = 0; z < 10; ++z)
 
  233           geometry_msgs::Point p;
 
  238           marker.points.push_back(p);
 
  240           std_msgs::ColorRGBA c;
 
  245           marker.colors.push_back(c);
 
  255     visualization_msgs::Marker marker;
 
  256     marker.header.frame_id = 
"base_link";
 
  258     marker.ns = 
"marker_test_point_list_alpha_per";
 
  260     marker.action = visualization_msgs::Marker::ADD;
 
  261     marker.pose.orientation.x = 0.0;
 
  262     marker.pose.orientation.y = 0.0;
 
  263     marker.pose.orientation.z = 0.0;
 
  264     marker.pose.orientation.w = 1.0;
 
  265     marker.pose.position.x = x_pos;
 
  266     marker.scale.x = 0.05;
 
  267     marker.scale.y = 0.05;
 
  268     marker.scale.z = 0.05;
 
  269     marker.color.r = 1.0;
 
  270     marker.color.g = 1.0;
 
  271     marker.color.b = 0.0;
 
  272     marker.color.a = 1.0;
 
  273     marker.frame_locked = 
true;
 
  275     for (
int type = visualization_msgs::Marker::CUBE_LIST; type <= visualization_msgs::Marker::POINTS;
 
  279       marker.pose.position.x += 0.5;
 
  281       if (type == visualization_msgs::Marker::POINTS)
 
  282         marker.scale.z = 0.0;
 
  284       for (
int y = 0; y < 10; ++y)
 
  286         geometry_msgs::Point p;
 
  291         marker.points.push_back(p);
 
  293         std_msgs::ColorRGBA c;
 
  297         c.a = (float)y * 0.1 + 0.1;
 
  298         marker.colors.push_back(c);
 
  307     visualization_msgs::Marker marker;
 
  308     marker.header.frame_id = 
"base_link";
 
  310     marker.ns = 
"marker_test_sphere_list";
 
  312     marker.type = visualization_msgs::Marker::SPHERE_LIST;
 
  313     marker.action = visualization_msgs::Marker::ADD;
 
  314     marker.pose.orientation.x = 0.0;
 
  315     marker.pose.orientation.y = 0.0;
 
  316     marker.pose.orientation.z = 0.0;
 
  317     marker.pose.orientation.w = 1.0;
 
  318     marker.pose.position.x = x_pos;
 
  319     marker.scale.x = 0.05;
 
  320     marker.scale.y = 0.05;
 
  321     marker.scale.z = 0.05;
 
  322     marker.color.r = 1.0;
 
  323     marker.color.g = 1.0;
 
  324     marker.color.b = 1.0;
 
  325     marker.color.a = 1.0;
 
  326     marker.frame_locked = 
true;
 
  328     for (
int x = 0; x < 10; ++x)
 
  330       for (
int y = 0; y < 10; ++y)
 
  332         for (
int z = 0; z < 1; ++z)
 
  334           geometry_msgs::Point p;
 
  339           marker.points.push_back(p);
 
  341           std_msgs::ColorRGBA c;
 
  346           marker.colors.push_back(c);
 
  356     visualization_msgs::Marker marker;
 
  357     marker.header.frame_id = 
"base_link";
 
  359     marker.ns = 
"marker_test_points";
 
  361     marker.type = visualization_msgs::Marker::POINTS;
 
  362     marker.action = visualization_msgs::Marker::ADD;
 
  363     marker.pose.orientation.x = 0.0;
 
  364     marker.pose.orientation.y = 0.0;
 
  365     marker.pose.orientation.z = 0.0;
 
  366     marker.pose.orientation.w = 1.0;
 
  367     marker.pose.position.x = x_pos;
 
  368     marker.scale.x = 0.02;
 
  369     marker.scale.y = 0.02;
 
  370     marker.scale.z = 0.0;
 
  371     marker.color.r = 1.0;
 
  372     marker.color.g = 0.0;
 
  373     marker.color.b = 1.0;
 
  374     marker.color.a = 1.0;
 
  375     marker.frame_locked = 
true;
 
  377     for (
int x = 0; x < 10; ++x)
 
  379       for (
int y = 0; y < 10; ++y)
 
  381         for (
int z = 0; z < 10; ++z)
 
  383           geometry_msgs::Point p;
 
  388           marker.points.push_back(p);
 
  398     visualization_msgs::Marker marker;
 
  399     marker.header.frame_id = 
"base_link";
 
  401     marker.ns = 
"marker_test_points_color_per";
 
  403     marker.type = visualization_msgs::Marker::POINTS;
 
  404     marker.action = visualization_msgs::Marker::ADD;
 
  405     marker.pose.orientation.x = 0.0;
 
  406     marker.pose.orientation.y = 0.0;
 
  407     marker.pose.orientation.z = 0.0;
 
  408     marker.pose.orientation.w = 1.0;
 
  409     marker.pose.position.x = x_pos;
 
  410     marker.scale.x = 0.02;
 
  411     marker.scale.y = 0.02;
 
  412     marker.scale.z = 0.0;
 
  413     marker.color.r = 1.0;
 
  414     marker.color.g = 0.0;
 
  415     marker.color.b = 1.0;
 
  416     marker.color.a = 1.0;
 
  417     marker.frame_locked = 
true;
 
  419     for (
int x = 0; x < 10; ++x)
 
  421       for (
int y = 0; y < 10; ++y)
 
  423         for (
int z = 0; z < 10; ++z)
 
  425           geometry_msgs::Point p;
 
  430           marker.points.push_back(p);
 
  432           std_msgs::ColorRGBA c;
 
  437           marker.colors.push_back(c);
 
  448     visualization_msgs::Marker marker;
 
  449     marker.header.frame_id = 
"base_link";
 
  451     marker.ns = 
"marker_test_line_list";
 
  453     marker.type = visualization_msgs::Marker::LINE_LIST;
 
  454     marker.action = visualization_msgs::Marker::ADD;
 
  455     marker.pose.position.x = 0.0;
 
  456     marker.pose.position.y = 0.0;
 
  457     marker.pose.position.z = 0.0;
 
  458     marker.pose.orientation.x = 0.0;
 
  459     marker.pose.orientation.y = 0.0;
 
  460     marker.pose.orientation.z = 0.0;
 
  461     marker.pose.orientation.w = 1.0;
 
  462     marker.pose.position.x = x_pos;
 
  463     marker.scale.x = 0.1;
 
  464     marker.color.r = 1.0;
 
  465     marker.color.a = 1.0;
 
  466     marker.frame_locked = 
true;
 
  468     for (
int i = 0; i <= count; ++i)
 
  470       geometry_msgs::Point p1, p2;
 
  472       p1.y = (i - count / 2) * 2;
 
  475       p2.y = (i - count / 2) * 2;
 
  477       marker.points.push_back(p1);
 
  478       marker.points.push_back(p2);
 
  487     visualization_msgs::Marker marker;
 
  488     marker.header.frame_id = 
"base_link";
 
  490     marker.ns = 
"marker_test_line_list_color_per";
 
  492     marker.type = visualization_msgs::Marker::LINE_LIST;
 
  493     marker.action = visualization_msgs::Marker::ADD;
 
  494     marker.pose.position.x = 0.0;
 
  495     marker.pose.position.y = 0.0;
 
  496     marker.pose.position.z = 0.0;
 
  497     marker.pose.orientation.x = 0.0;
 
  498     marker.pose.orientation.y = 0.0;
 
  499     marker.pose.orientation.z = 0.0;
 
  500     marker.pose.orientation.w = 1.0;
 
  501     marker.pose.position.x = x_pos;
 
  502     marker.scale.x = 0.1;
 
  503     marker.color.r = 1.0;
 
  504     marker.color.a = 1.0;
 
  505     marker.frame_locked = 
true;
 
  507     for (
int i = 0; i <= count; ++i)
 
  509       geometry_msgs::Point p1, p2;
 
  511       p1.y = (i - count / 2) * 2;
 
  514       p2.y = (i - count / 2) * 2;
 
  516       marker.points.push_back(p1);
 
  517       marker.points.push_back(p2);
 
  519       std_msgs::ColorRGBA c;
 
  520       float pct = (float)i / (
float)count;
 
  521       c.r = pct * 1.0 + (1 - pct) * 0.0;
 
  522       c.g = pct * 0.0 + (1 - pct) * 0.0;
 
  523       c.b = pct * 0.0 + (1 - pct) * 1.0;
 
  526       marker.colors.push_back(c);
 
  527       marker.colors.push_back(c);
 
  535     visualization_msgs::Marker marker;
 
  536     marker.header.frame_id = 
"base_link";
 
  538     marker.ns = 
"marker_test_line_strip";
 
  540     marker.type = visualization_msgs::Marker::LINE_STRIP;
 
  541     marker.action = visualization_msgs::Marker::ADD;
 
  542     marker.pose.position.x = 0.0;
 
  543     marker.pose.position.y = 0.0;
 
  544     marker.pose.position.z = 0.0;
 
  545     marker.pose.orientation.x = 0.0;
 
  546     marker.pose.orientation.y = 0.0;
 
  547     marker.pose.orientation.z = 0.0;
 
  548     marker.pose.orientation.w = 1.0;
 
  549     marker.pose.position.x = x_pos;
 
  550     marker.scale.x = 0.1;
 
  551     marker.color.g = 1.0;
 
  552     marker.color.a = 1.0;
 
  553     marker.frame_locked = 
true;
 
  555     for (
int i = -5; i <= 5; ++i)
 
  557       geometry_msgs::Point p;
 
  561       marker.points.push_back(p);
 
  570     visualization_msgs::Marker marker;
 
  571     marker.header.frame_id = 
"base_link";
 
  573     marker.ns = 
"marker_test_line_strip_color_per";
 
  575     marker.type = visualization_msgs::Marker::LINE_STRIP;
 
  576     marker.action = visualization_msgs::Marker::ADD;
 
  577     marker.pose.position.x = 0.0;
 
  578     marker.pose.position.y = 0.0;
 
  579     marker.pose.position.z = 0.0;
 
  580     marker.pose.orientation.x = 0.0;
 
  581     marker.pose.orientation.y = 0.0;
 
  582     marker.pose.orientation.z = 0.0;
 
  583     marker.pose.orientation.w = 1.0;
 
  584     marker.pose.position.x = x_pos;
 
  585     marker.scale.x = 0.1;
 
  586     marker.color.g = 1.0;
 
  587     marker.color.a = 1.0;
 
  588     marker.frame_locked = 
true;
 
  590     for (
int i = -5; i < 5; ++i)
 
  592       geometry_msgs::Point p;
 
  596       marker.points.push_back(p);
 
  598       std_msgs::ColorRGBA c;
 
  599       float pct = (i + 5) / 10.0;
 
  600       c.r = pct * 0.0 + (1 - pct) * 0.0;
 
  601       c.g = pct * 1.0 + (1 - pct) * 0.0;
 
  602       c.b = pct * 0.0 + (1 - pct) * 1.0;
 
  605       marker.colors.push_back(c);
 
  614     visualization_msgs::Marker marker;
 
  615     marker.header.frame_id = 
"base_link";
 
  617     marker.ns = 
"marker_test_triangle_list";
 
  619     marker.type = visualization_msgs::Marker::TRIANGLE_LIST;
 
  620     marker.action = visualization_msgs::Marker::ADD;
 
  621     marker.pose.position.x = 0.0;
 
  622     marker.pose.position.y = 0.0;
 
  623     marker.pose.position.z = 0.0;
 
  624     marker.pose.orientation.x = 0.0;
 
  625     marker.pose.orientation.y = 0.0;
 
  626     marker.pose.orientation.z = 0.0;
 
  627     marker.pose.orientation.w = 1.0;
 
  628     marker.pose.position.x = x_pos;
 
  629     marker.scale.x = 1.0;
 
  630     marker.scale.y = 1.0;
 
  631     marker.scale.z = 1.0;
 
  632     marker.color.g = 1.0;
 
  633     marker.color.a = 1.0;
 
  634     marker.frame_locked = 
true;
 
  636     for (
int x = 0; x < 10; ++x)
 
  638       for (
int y = 0; y < 10; ++y)
 
  640         for (
int z = 0; z < 10; ++z)
 
  642           geometry_msgs::Point p;
 
  647           geometry_msgs::Point p2 = p;
 
  650           geometry_msgs::Point p3 = p;
 
  654           marker.points.push_back(p);
 
  655           marker.points.push_back(p2);
 
  656           marker.points.push_back(p3);
 
  658           std_msgs::ColorRGBA c;
 
  663           marker.colors.push_back(c);
 
  664           marker.colors.push_back(c);
 
  665           marker.colors.push_back(c);
 
  676     visualization_msgs::Marker marker;
 
  677     marker.header.frame_id = 
"base_link";
 
  679     marker.ns = 
"marker_test_mesh_color_change";
 
  681     marker.type = visualization_msgs::Marker::MESH_RESOURCE;
 
  682     marker.action = visualization_msgs::Marker::ADD;
 
  683     marker.pose.position.x = 0.0;
 
  684     marker.pose.position.y = 0.0;
 
  685     marker.pose.position.z = 0.0;
 
  686     marker.pose.orientation.x = 0.0;
 
  687     marker.pose.orientation.y = 0.0;
 
  688     marker.pose.orientation.z = 0.0;
 
  689     marker.pose.orientation.w = 1.0;
 
  690     marker.pose.position.x = x_pos;
 
  691     marker.scale.x = 1.0;
 
  692     marker.scale.y = 1.0;
 
  693     marker.scale.z = 1.0;
 
  694     marker.color.r = float(counter % 255) / 255;
 
  695     marker.color.g = float((counter * 3) % 255) / 255;
 
  696     marker.color.b = float((counter * 10) % 255) / 255;
 
  697     marker.color.a = 1.0;
 
  698     marker.frame_locked = 
true;
 
  699     marker.mesh_resource = 
"package://pr2_description/meshes/base_v0/base.dae";
 
  700     marker.mesh_use_embedded_materials = 
false;
 
  710   static uint32_t counter = 0;
 
  713   geometry_msgs::TransformStamped 
t;
 
  715   t.transform.translation = 
tf2::toMsg(tf2::Vector3(0.0, 0.0, (counter % 1000) * 0.01));
 
  717   t.header.frame_id = 
"base_link";
 
  718   t.child_frame_id = 
"my_link";
 
  722   t.transform.translation = 
tf2::toMsg(tf2::Vector3(0.0, 0.0, 0.0));
 
  724   q.
setRPY(M_PI * 0.25, M_PI * 0.25, 0.0);
 
  726   t.header.frame_id = 
"base_link";
 
  727   t.child_frame_id = 
"rotate_base_link";
 
  734 int main(
int argc, 
char** argv)