39 #include <OgreQuaternion.h> 
   40 #include <OgreSceneNode.h> 
   41 #include <OgreSceneManager.h> 
   46   : 
MarkerBase(owner, context, parent_node), points_(nullptr)
 
   57   ROS_ASSERT(new_message->type == visualization_msgs::Marker::POINTS ||
 
   58              new_message->type == visualization_msgs::Marker::CUBE_LIST ||
 
   59              new_message->type == visualization_msgs::Marker::SPHERE_LIST);
 
   67   Ogre::Vector3 pos, scale;
 
   68   Ogre::Quaternion orient;
 
   69   if (!
transform(new_message, pos, orient, scale))
 
   77   switch (new_message->type)
 
   79   case visualization_msgs::Marker::POINTS:
 
   83   case visualization_msgs::Marker::CUBE_LIST:
 
   87   case visualization_msgs::Marker::SPHERE_LIST:
 
   98   if (new_message->points.empty())
 
  103   float r = new_message->color.r;
 
  104   float g = new_message->color.g;
 
  105   float b = new_message->color.b;
 
  106   float a = new_message->color.a;
 
  108   bool has_per_point_color = new_message->colors.size() == new_message->points.size();
 
  110   bool has_nonzero_alpha = 
false;
 
  111   bool has_per_point_alpha = 
false;
 
  113   typedef std::vector<PointCloud::Point> V_Point;
 
  115   points.resize(new_message->points.size());
 
  116   std::vector<geometry_msgs::Point>::const_iterator it = new_message->points.begin();
 
  117   std::vector<geometry_msgs::Point>::const_iterator end = new_message->points.end();
 
  118   for (
int i = 0; it != end; ++it, ++i)
 
  120     const geometry_msgs::Point& p = *it;
 
  123     Ogre::Vector3 v(p.x, p.y, p.z);
 
  129     if (has_per_point_color)
 
  131       const std_msgs::ColorRGBA& color = new_message->colors[i];
 
  136       has_nonzero_alpha = has_nonzero_alpha || a != 0.0;
 
  137       has_per_point_alpha = has_per_point_alpha || a != 1.0;
 
  143   if (has_per_point_color)