36 #include <jsk_topic_tools/color_utils.h> 
   45                                               "color to draw the toruses",
 
   48                                               "alpha value to draw the toruses",
 
   51                                             "torus uv dimension setting",
 
   54                                                   "change the color of the toruses automatically",
 
   57                                                    "show normal direction",
 
   79       std_msgs::ColorRGBA ros_color = jsk_topic_tools::colorCategory20(index);
 
   80       return QColor(ros_color.r * 255.0, ros_color.g * 255.0, ros_color.b * 255.0,
 
  144         Ogre::SceneNode* scene_node = 
scene_node_->createChildSceneNode();
 
  162     for (
size_t i = 0; 
i < 
msg->toruses.size(); 
i++) {
 
  163       if (!
msg->toruses[
i].failure) {
 
  172                                            int large_dimension, 
int small_dimension,
 
  174                                            Ogre::Vector3 
pos, Ogre::Quaternion 
q,
 
  175                                            std::vector<Triangle> &triangles,
 
  176                                            std::vector<Ogre::Vector3> &vertices,
 
  177                                            std::vector<Ogre::Vector3> &normals
 
  180     for (
int i = 0; 
i < large_dimension; 
i ++){
 
  181       float target_circle_x = 
large_radius * cos( ( 
i * 1.0/ large_dimension) * 2 * 
PI) ;
 
  182       float target_circle_y = 
large_radius * sin( ( 
i * 1.0 / large_dimension) * 2 * 
PI) ;
 
  183       for (
int j = 0; j < small_dimension; j++){
 
  184         Ogre::Vector3 new_point;
 
  185         new_point.x = target_circle_x + 
small_radius * cos ( (j * 1.0 / small_dimension) * 2 * 
PI) * cos( ( 
i * 1.0/ large_dimension) * 2 * 
PI);
 
  186         new_point.y = target_circle_y + 
small_radius * cos ( (j * 1.0/ small_dimension) * 2 * 
PI) * sin( ( 
i * 1.0/ large_dimension) * 2 * 
PI);
 
  187         new_point.z = 
small_radius * sin ( (j * 1.0/ small_dimension) * 2 * 
PI);
 
  190         new_point = 
q * new_point;
 
  193         vertices.push_back(new_point);
 
  196         Ogre::Vector3 normal;
 
  197         normal.x = 
small_radius * cos ( (j * 1.0 / small_dimension) * 2 * 
PI) * cos( ( 
i * 1.0/ large_dimension) * 2 * 
PI);
 
  198         normal.y = 
small_radius * cos ( (j * 1.0/ small_dimension) * 2 * 
PI) * sin( ( 
i * 1.0/ large_dimension) * 2 * 
PI);
 
  199         normal.z = 
small_radius * sin ( (j * 1.0/ small_dimension) * 2 * 
PI);
 
  201         normals.push_back(normal);
 
  206     for(
int i = 0; 
i < large_dimension; 
i++){
 
  207       for(
int j = 0; j < small_dimension; j++){
 
  208         int target_index = 
i * large_dimension + j;
 
  209         int next_index = target_index + 1;
 
  210         if(next_index >= small_dimension * large_dimension)
 
  212         int next_circle_target_index = target_index + large_dimension;
 
  213         if (next_circle_target_index >= large_dimension*small_dimension)
 
  214           next_circle_target_index -= large_dimension*small_dimension;
 
  215         int prev_circle_next_index = target_index - large_dimension + 1;
 
  216         if (prev_circle_next_index < 0)
 
  217           prev_circle_next_index += large_dimension*small_dimension;
 
  219         t1.
v1 = target_index;
 
  221         t1.
v2 = next_circle_target_index;
 
  223         t2.
v1 = target_index;
 
  225         t2.
v3 = prev_circle_next_index;
 
  226         triangles.push_back(t1);
 
  227         triangles.push_back(t2);
 
  255     for (
size_t i = 0; 
i < 
msg->toruses.size(); 
i++) {
 
  256       jsk_recognition_msgs::Torus torus = 
msg->toruses[
i];
 
  262       Ogre::Vector3 position;
 
  263       Ogre::Quaternion quaternion;
 
  271           std::ostringstream oss;
 
  272           oss << 
"Error transforming pose";
 
  273           oss << 
" from frame '" << torus.header.frame_id << 
"'";
 
  274           oss << 
" to frame '" << qPrintable(
fixed_frame_) << 
"'";
 
  281       std::vector<Triangle> triangles;
 
  282       std::vector<Ogre::Vector3> vertices;
 
  283       std::vector<Ogre::Vector3> normals;
 
  288                             triangles, vertices, normals);
 
  290       shape->estimateVertexCount(vertices.size());
 
  291       shape->beginTriangles();
 
  292       for (std::size_t j = 0 ; j < vertices.size() ; ++j)
 
  293         shape->addVertex(vertices[j], normals[j]);
 
  294       for (std::size_t j = 0 ; j < triangles.size() ; ++j)
 
  295         shape->addTriangle(triangles[j].v1, triangles[j].v2, triangles[j].v3);
 
  296       shape->endTriangles();
 
  298       shape->setColor(color.red() / 255.0,
 
  299                       color.green() / 255.0,
 
  300                       color.blue() / 255.0,
 
  304         Ogre::Vector3 normal;
 
  308         normal.x = 0;      normal.y = 0;      normal.z = 1;
 
  312                                     color.green() / 255.0,
 
  313                                     color.blue() / 255.0,