VoronoiGraphVisual.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <OGRE/OgreVector3.h>
31 #include <OGRE/OgreSceneNode.h>
32 #include <OGRE/OgreSceneManager.h>
33 
34 #include <rviz/ogre_helpers/line.h>
35 #include <tuw_multi_robot_msgs/Vertex.h>
37 
38 namespace tuw_multi_robot_rviz
39 {
40 
41 VoronoiGraphVisual::VoronoiGraphVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
42 {
43  scene_manager_ = scene_manager;
44 
45  // Ogre::SceneNode s form a tree, with each node storing the
46  // transform (position and orientation) of itself relative to its
47  // parent. Ogre does the math of combining those transforms when it
48  // is time to render.
49  //
50  // Here we create a node to store the pose of the MarkerDetection's header frame
51  // relative to the RViz fixed frame.
52  frame_node_ = parent_node->createChildSceneNode();
53 
54  // initialize global variables
55  colorPath_ = Ogre::ColourValue(255, 0, 0);
56  scalePoint_ = 0.1;
57  scalePath_ = 1;
58 }
59 
61 {
62  // Destroy the frame node since we don't need it anymore.
63  scene_manager_->destroySceneNode(frame_node_);
64 }
65 
66 void VoronoiGraphVisual::setMessage(const tuw_multi_robot_msgs::Graph::ConstPtr &msg)
67 {
68  static double timeOld_;
69  if (timeOld_ == msg->header.stamp.toSec())
70  {
71  return;
72  }
73  timeOld_ = msg->header.stamp.toSec();
74 
75  pathLine.resize(msg->vertices.size());
76  crossingShape.resize(pathLine.size() * 2);
77  for (size_t i = 0; i < pathLine.size(); ++i)
78  {
79  tuw_multi_robot_msgs::Vertex seg = msg->vertices[i];
80  geometry_msgs::Point p1 = seg.path.front();
81  geometry_msgs::Point p2 = seg.path.back();
82 
83  // Ogre::Quaternion rotation = Ogre::Quaternion ( Ogre::Radian( (*spline_)(i / (double)pointsNrPath_ )(2) + atan2(v_y, v_x) ), Ogre::Vector3::UNIT_Z );
84 
85  Ogre::Quaternion rotation;
86  rotation.x = 1;
87  rotation.y = 0;
88  rotation.z = 0;
89  rotation.w = 0;
90  Ogre::Quaternion rotation2 = Ogre::Quaternion(Ogre::Radian(-Ogre::Math::PI / 2.), Ogre::Vector3::UNIT_Y);
91 
93  pathLine[i]->setColor(colorPath_);
94  pathLine[i]->setPoints(Ogre::Vector3((p1.x) * msg->resolution + msg->origin.position.x, (p1.y) * msg->resolution + msg->origin.position.y, p1.z * msg->resolution + msg->origin.position.z), Ogre::Vector3((p2.x) * msg->resolution + msg->origin.position.x, (p2.y) * msg->resolution + msg->origin.position.y, p2.z * msg->resolution + msg->origin.position.z));
95  pathLine[i]->setScale(Ogre::Vector3(scalePath_, scalePath_, scalePath_));
96 
98  crossingShape[2 * i]->setColor(colorPath_);
99  crossingShape[2 * i]->setPosition(Ogre::Vector3((p1.x) * msg->resolution + msg->origin.position.x, (p1.y) * msg->resolution + msg->origin.position.y, p1.z * msg->resolution + msg->origin.position.z));
100  crossingShape[2 * i]->setOrientation(rotation * rotation2);
101  crossingShape[2 * i]->setScale(Ogre::Vector3(scalePoint_, scalePoint_, scalePoint_));
102 
104  crossingShape[2 * i + 1]->setColor(colorPath_);
105  crossingShape[2 * i + 1]->setPosition(Ogre::Vector3((p2.x) * msg->resolution + msg->origin.position.x, (p2.y) * msg->resolution + msg->origin.position.y, p2.z * msg->resolution + msg->origin.position.z));
106  crossingShape[2 * i + 1]->setOrientation(rotation * rotation2);
107  crossingShape[2 * i + 1]->setScale(Ogre::Vector3(scalePoint_, scalePoint_, scalePoint_));
108  }
109 }
110 
111 // Position is passed through to the SceneNode.
112 void VoronoiGraphVisual::setFramePosition(const Ogre::Vector3 &position)
113 {
114  frame_node_->setPosition(position);
115 }
116 
117 // Orientation is passed through to the SceneNode.
118 void VoronoiGraphVisual::setFrameOrientation(const Ogre::Quaternion &orientation)
119 {
120  frame_node_->setOrientation(orientation);
121 }
122 
123 // Color is passed through to the Shape object.
124 void VoronoiGraphVisual::setPathColor(Ogre::ColourValue color)
125 {
126  colorPath_ = color;
127  for (auto &pathXYi : pathLine)
128  {
129  pathXYi->setColor(colorPath_);
130  }
131 }
132 
134 {
135  scalePoint_ = scale;
136  for (auto &pathThetai : crossingShape)
137  {
138  pathThetai->setScale(Ogre::Vector3(scalePoint_, scalePoint_, scalePoint_));
139  }
140 }
141 
143 {
144  scalePath_ = scale;
145  for (auto &pathThetai : pathLine)
146  {
147  pathThetai->setScale(Ogre::Vector3(scalePath_, scalePath_, scalePath_));
148  }
149 }
150 
151 } // namespace tuw_multi_robot_rviz
std::vector< boost::shared_ptr< rviz::Shape > > crossingShape
void setFrameOrientation(const Ogre::Quaternion &orientation)
void setFramePosition(const Ogre::Vector3 &position)
VoronoiGraphVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
std::vector< boost::shared_ptr< rviz::Line > > pathLine
void setMessage(const tuw_multi_robot_msgs::Graph::ConstPtr &msg)
void setPathColor(Ogre::ColourValue color)


tuw_multi_robot_rviz
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:40