72     visual_tools_->loadMarkerPub();  
    74     ROS_INFO(
"Sleeping 5 seconds before running demo");
    78     visual_tools_->deleteAllMarkers();
    79     visual_tools_->enableBatchPublishing();
    84     Eigen::Affine3d pose_copy = pose;
    85     pose_copy.translation().x() -= 0.2;
    92     Eigen::Affine3d pose1 = Eigen::Affine3d::Identity();
    93     Eigen::Affine3d pose2 = Eigen::Affine3d::Identity();
    95     pose1.translation().x() = x_location;
    97     double space_between_rows = 0.2;
   104     for (
double i = 0; i <= 1.0; i += 0.02)
   106       geometry_msgs::Vector3 scale = visual_tools_->getScale(
MEDIUM);
   107       std_msgs::ColorRGBA color = visual_tools_->getColorScale(i);
   108       visual_tools_->publishSphere(visual_tools_->convertPose(pose1), color, scale, 
"Sphere");
   113       pose1.translation().x() += step;
   115     visual_tools_->trigger();
   119     pose1.translation().x() = 0;
   120     y += space_between_rows;
   121     pose1.translation().y() = y;
   123     for (
double i = 0; i <= 1.0; i += step)
   125       visual_tools_->publishAxis(pose1);
   131       pose1.translation().x() += step;
   132       pose1 = pose1 * Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitX()) *
   133               Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitY()) *
   134               Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitZ());
   136     visual_tools_->trigger();
   140     pose1 = Eigen::Affine3d::Identity();
   141     y += space_between_rows;
   142     pose1.translation().y() = y;
   144     for (
double i = 0; i <= 1.0; i += step)
   146       visual_tools_->publishArrow(pose1, 
rvt::RAND);
   152       pose1.translation().x() += step;
   153       pose1 = pose1 * Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitZ());
   155     visual_tools_->trigger();
   159     double cuboid_max_size = 0.075;
   160     double cuboid_min_size = 0.01;
   161     pose1 = Eigen::Affine3d::Identity();
   162     pose2 = Eigen::Affine3d::Identity();
   163     y += space_between_rows;
   164     pose1.translation().y() = y;
   165     pose2.translation().y() = y;
   167     for (
double i = 0; i <= 1.0; i += step)
   170       pose2.translation().x() += i * cuboid_max_size + cuboid_min_size;
   171       pose2.translation().y() += i * cuboid_max_size + cuboid_min_size;
   172       pose2.translation().z() += i * cuboid_max_size + cuboid_min_size;
   173       visual_tools_->publishCuboid(pose1.translation(), pose2.translation(), 
rvt::RAND);
   180       pose1.translation().x() += step;
   182     visual_tools_->trigger();
   186     double line_max_size = 0.075;
   187     double line_min_size = 0.01;
   188     pose1 = Eigen::Affine3d::Identity();
   189     pose2 = Eigen::Affine3d::Identity();
   190     y += space_between_rows;
   191     pose1.translation().y() = y;
   192     pose2.translation().y() = y;
   194     for (
double i = 0; i <= 1.0; i += step)
   197       pose2.translation().x() += i * line_max_size + line_min_size;
   198       pose2.translation().y() += i * line_max_size + line_min_size;
   199       pose2.translation().z() += i * line_max_size + line_min_size;
   200       visual_tools_->publishLine(pose1.translation(), pose2.translation(), 
rvt::RAND);
   207       pose1.translation().x() += step;
   209     visual_tools_->trigger();
   213     pose1 = Eigen::Affine3d::Identity();
   214     y += space_between_rows;
   215     pose1.translation().y() = y;
   217     for (
double i = 0; i <= 1.0; i += step)
   219       visual_tools_->publishCylinder(pose1, 
rvt::RAND);
   225       pose1.translation().x() += step;
   226       pose1 = pose1 * Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitZ());
   228     visual_tools_->trigger();
   232     pose1 = Eigen::Affine3d::Identity();
   233     y += space_between_rows;
   234     pose1.translation().y() = y;
   236     double angle_step = 0.1;
   239     for (
double i = 0; i <= 1.0; i += step)
   241       visual_tools_->publishCone(pose1, M_PI / angle, 
rvt::RAND, 0.05);
   247       pose1.translation().x() += step;
   248       pose1 = pose1 * Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitZ());
   251     visual_tools_->trigger();
   255     pose1 = Eigen::Affine3d::Identity();
   256     y += space_between_rows;
   257     pose1.translation().y() = y;
   260     Eigen::Vector3d min_point, max_point;
   261     min_point << -0.05, -0.05, -0.05;
   262     max_point << 0.05, 0.05, 0.05;
   263     for (
double i = 0; i <= 1.0; i += step)
   265       visual_tools_->publishWireframeCuboid(pose1, min_point, max_point, 
rvt::RAND);
   271       pose1.translation().x() += step;
   272       pose1 = pose1 * Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitZ());
   274     visual_tools_->trigger();
   278     pose1 = Eigen::Affine3d::Identity();
   279     y += space_between_rows;
   280     pose1.translation().y() = y;
   282     double depth = 0.05, width = 0.05, height = 0.05;
   283     for (
double i = 0; i <= 1.0; i += step)
   285       visual_tools_->publishWireframeCuboid(pose1, depth, width, height, 
rvt::RAND);
   291       pose1.translation().x() += step;
   292       pose1 = pose1 * Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitZ());
   294     visual_tools_->trigger();
   298     pose1 = Eigen::Affine3d::Identity();
   299     y += space_between_rows;
   300     pose1.translation().y() = y;
   302     double max_plane_size = 0.075;
   303     double min_plane_size = 0.01;
   304     for (
double i = 0; i <= 1.0; i += step)
   306       visual_tools_->publishXYPlane(pose1, 
rvt::RED, i * max_plane_size + min_plane_size);
   307       visual_tools_->publishXZPlane(pose1, 
rvt::GREEN, i * max_plane_size + min_plane_size);
   308       visual_tools_->publishYZPlane(pose1, 
rvt::BLUE, i * max_plane_size + min_plane_size);
   314       pose1.translation().x() += step;
   316     visual_tools_->trigger();
   320     pose1 = Eigen::Affine3d::Identity();
   321     y += space_between_rows;
   322     pose1.translation().y() = y;
   324     graph_msgs::GeometryGraph graph;
   325     for (
double i = 0; i <= 1.0; i += step)
   327       graph.nodes.push_back(visual_tools_->convertPose(pose1).position);
   328       graph_msgs::Edges edges;
   331         edges.node_ids.push_back(0);
   333       graph.edges.push_back(edges);
   340       pose1.translation().x() += step;
   341       pose1.translation().z() += visual_tools_->dRand(-0.1, 0.1);
   343     visual_tools_->publishGraph(graph, 
rvt::ORANGE, 0.005);
   344     visual_tools_->trigger();
   354     pose1.translation().x() = 0;
   355     y += space_between_rows;
   356     pose1.translation().y() = y;
   357     pose1.translation().z() = 0;
   359     for (
double i = 0; i <= 1.0; i += step)
   361       visual_tools_->publishAxisLabeled(pose1, 
"label of axis");
   367       pose1.translation().x() += step;
   368       pose1 = pose1 * Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitX()) *
   369               Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitY()) *
   370               Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitZ());
   372     visual_tools_->trigger();
   376     pose1 = Eigen::Affine3d::Identity();
   377     pose2 = Eigen::Affine3d::Identity();
   378     y += space_between_rows;
   379     pose1.translation().y() = y;
   383     std::vector<rviz_visual_tools::colors> 
colors;
   385     for (
double i = 0; i < 1.0; i += step)
   387       pose1.translation().y() = y;
   388       if (++index % 2 == 0)
   390         pose1.translation().y() += step / 2.0;
   395         pose1.translation().y() -= step / 2.0;
   398       path.emplace_back(pose1.translation());
   399       pose1.translation().x() += step;
   406     visual_tools_->publishPath(path, colors);
   407     visual_tools_->trigger();
   417     Eigen::Affine3d pose1 = Eigen::Affine3d::Identity();
   418     Eigen::Affine3d pose2 = Eigen::Affine3d::Identity();
   421     std::vector<colors> 
colors;
   422     colors.push_back(
RED);
   423     colors.push_back(
GREEN);
   432     pose1.translation().x() = x_location - 0.1;
   433     visual_tools_->publishText(pose1, 
"Testing consistency of " + visual_tools_->scaleToString(scale) + 
" marker scale",
   436     pose1.translation().x() = x_location;
   444     visual_tools_->publishSphere(pose1, 
BLUE, scale);
   445     pose1.translation().y() += step;
   449     points1.emplace_back(pose1.translation());
   450     pose1.translation().x() += step;
   451     points1.emplace_back(pose1.translation());
   452     visual_tools_->publishSpheres(points1, 
BLUE, scale);
   453     pose1.translation().x() = x_location;  
   454     pose1.translation().y() += step;
   458     points1.emplace_back(pose1.translation());
   459     pose1.translation().x() += step;
   460     points1.emplace_back(pose1.translation());
   461     visual_tools_->publishSpheres(points1, colors, scale);
   462     pose1.translation().x() = x_location;  
   463     pose1.translation().y() += step;
   466     visual_tools_->publishYArrow(pose1, 
BLUE, scale);
   467     pose1.translation().y() += step;
   470     visual_tools_->publishZArrow(pose1, 
GREEN, scale);
   471     pose1.translation().y() += step;
   474     visual_tools_->publishXArrow(pose1, 
RED, scale);
   475     pose1.translation().y() += step;
   478     visual_tools_->publishArrow(pose1, 
RED, scale);
   479     pose1.translation().y() += step;
   483     pose2.translation().x() += step / 2.0;
   484     visual_tools_->publishLine(pose1, pose2, 
PURPLE, scale);
   485     pose1.translation().y() += step;
   491     pose2.translation().x() += step / 2.0;
   492     points1.emplace_back(pose1.translation());
   493     points2.emplace_back(pose2.translation());
   494     pose1.translation().x() += step / 2.0;
   497     pose2.translation().x() += step / 2.0;
   502     visual_tools_->publishLines(points1, points2, colors, scale);
   503     pose1.translation().x() = x_location;  
   504     pose1.translation().y() += step;
   512     visual_tools_->publishAxisLabeled(pose1, 
"Axis", scale);
   513     pose1.translation().y() += step;
   516     visual_tools_->publishAxis(pose1, scale);
   517     pose1.translation().y() += step;
   523     pose2.translation().x() += step / 2.0;
   524     visual_tools_->publishCylinder(pose1.translation(), pose2.translation(), 
BLUE, scale);
   525     pose1.translation().y() += step;
   532     visual_tools_->publishText(pose1, 
"Text", 
WHITE, scale, 
false);
   533     pose1.translation().y() += step;
   536     visual_tools_->trigger();
   548     Eigen::Affine3d pose1 = Eigen::Affine3d::Identity();
   549     Eigen::Affine3d pose2;
   552     pose1.translation().x() = x_location - 0.1;
   553     visual_tools_->publishText(pose1, 
"Testing sizes of marker scale", 
WHITE, 
XLARGE, 
false);
   555     pose1.translation().x() = x_location;
   556     pose2.translation().x() = x_location;
   563         visual_tools_->publishSphere(pose1, 
GREEN, scale);
   567         visual_tools_->publishSphere(pose1, 
GREY, scale);
   569       visual_tools_->publishText(pose2, 
"Size " + visual_tools_->scaleToString(scale), 
WHITE, scale, 
false);
   571       scale = 
static_cast<scales>(
static_cast<int>(scale) + 1);
   572       pose1.translation().y() += visual_tools_->getScale(scale).x + 0.1;
   575       pose2.translation().y() = pose1.translation().y();
   576       pose2.translation().x() = x_location + visual_tools_->getScale(scale).x * 1.3;
   580     visual_tools_->trigger();
   589 int main(
int argc, 
char** argv)
   591   ros::init(argc, argv, 
"visual_tools_demo");
   600   double x_location = 0;
 
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_INFO_STREAM_NAMED(name, args)
TFSIMD_FORCE_INLINE const tfScalar & y() const 
#define ROS_INFO_STREAM(args)