SelectionBox.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of OctoMap - An Efficient Probabilistic 3D Mapping
3  * Framework Based on Octrees
4  * http://octomap.github.io
5  *
6  * Copyright (c) 2009-2014, K.M. Wurm and A. Hornung, University of Freiburg
7  * All rights reserved. License for the viewer octovis: GNU GPL v2
8  * http://www.gnu.org/licenses/old-licenses/gpl-2.0.txt
9  *
10  *
11  * This program is free software; you can redistribute it and/or modify
12  * it under the terms of the GNU General Public License as published by
13  * the Free Software Foundation; either version 2 of the License, or
14  * (at your option) any later version.
15  *
16  * This program is distributed in the hope that it will be useful, but
17  * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
18  * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
19  * for more details.
20  *
21  * You should have received a copy of the GNU General Public License
22  * along with this program. If not, see http://www.gnu.org/licenses/.
23  */
24 
25 // workaround for Windows
26 #define NOMINMAX
27 #include <octovis/SelectionBox.h>
28 #include <manipulatedFrame.h>
29 
30 namespace octomap{
31 
33 : m_visible(false),
34  m_minPt(0,0,0), m_maxPt(1,1,1),
35  m_arrowLength(0.2)
36 {
37 
38 
39 
40  for (unsigned i=0; i< 3; ++i){
41  m_frames.push_back(new qglviewer::ManipulatedFrame());
42  }
43 
44  for (unsigned i=0; i< 3; ++i){
45  m_frames.push_back(new qglviewer::ManipulatedFrame());
46  }
47 
51 
55 
59 
60 
61  frame(0)->setConstraint(XAxis);
62  frame(1)->setConstraint(YAxis);
63  frame(2)->setConstraint(ZAxis);
64  frame(3)->setConstraint(XAxis);
65  frame(4)->setConstraint(YAxis);
66  frame(5)->setConstraint(ZAxis);
67 
68 
69 
70 }
71 
73  delete m_frames[0];
74  delete m_frames[1];
75 }
76 
77 void SelectionBox::draw(bool withNames){
78 
79 
80  // set min/max new from grabbed frame:
81  for (unsigned i = 0; i < m_frames.size(); ++i){
82  if (frame(i)->grabsMouse()){
83  qglviewer::Vec f = frame(i)->position();
84 
85  unsigned oi = i+3;
86  float corr = m_arrowLength/2.0;
87  if (i >= 3){
88  oi = i-3;
89  corr *= -1;
90  }
91 
92  qglviewer::Vec fo = frame(oi)->position();
93 
94  unsigned ci = i%3;
95  m_minPt[ci] = std::min(f[ci] - corr, fo[ci] + corr);
96  m_maxPt[ci] = std::max(f[ci] - corr, fo[ci] + corr);
97  }
98  }
99 
100  // draw box:
101 
102  glEnable(GL_LINE_SMOOTH);
103  glLineWidth(2.);
104  glDisable(GL_LIGHTING);
105  glColor3f(0.9,0.0, 0.0);
106  glBegin(GL_LINE_LOOP); // Start drawing a line primitive
107  glVertex3f(m_minPt.x, m_minPt.y, m_minPt.z);
108  glVertex3f(m_maxPt.x, m_minPt.y, m_minPt.z);
109  glVertex3f(m_maxPt.x, m_maxPt.y, m_minPt.z);
110  glVertex3f(m_minPt.x, m_maxPt.y, m_minPt.z);
111  glEnd();
112 
113  glBegin(GL_LINE_LOOP);
114  glVertex3f(m_minPt.x, m_minPt.y, m_maxPt.z);
115  glVertex3f(m_maxPt.x, m_minPt.y, m_maxPt.z);
116  glVertex3f(m_maxPt.x, m_maxPt.y, m_maxPt.z);
117  glVertex3f(m_minPt.x, m_maxPt.y, m_maxPt.z);
118  // glVertex3f(-1.0f, -1.0f, 0.0f); // The bottom left corner
119  // glVertex3f(-1.0f, 1.0f, 0.0f); // The top left corner
120  // glVertex3f(1.0f, 1.0f, 0.0f); // The top right corner
121  // glVertex3f(1.0f, -1.0f, 0.0f); // The bottom right corner
122  glEnd();
123 
124  glBegin(GL_LINES);
125  glVertex3f(m_minPt.x, m_minPt.y, m_minPt.z);
126  glVertex3f(m_minPt.x, m_minPt.y, m_maxPt.z);
127 
128  glVertex3f(m_maxPt.x, m_minPt.y, m_minPt.z);
129  glVertex3f(m_maxPt.x, m_minPt.y, m_maxPt.z);
130 
131  glVertex3f(m_maxPt.x, m_maxPt.y, m_minPt.z);
132  glVertex3f(m_maxPt.x, m_maxPt.y, m_maxPt.z);
133 
134  glVertex3f(m_minPt.x, m_maxPt.y, m_minPt.z);
135  glVertex3f(m_minPt.x, m_maxPt.y, m_maxPt.z);
136  glEnd();
137 
138  glDisable(GL_LINE_SMOOTH);
139  glEnable(GL_LIGHTING);
140 
141 
142  // correct all arrow frames:
143 
144  for (unsigned i = 0; i < m_frames.size(); ++i){
145  qglviewer::Vec pt = m_minPt;
146  float corr = m_arrowLength/2;
147  if (i/3 == 1){
148  pt = m_maxPt;
149  corr *= -1;
150  }
151 
152  pt[i%3] += corr;
153 
154  frame(i)->setTranslation(pt);
155 
156  }
157 
158  // draw spheres in their frames:
159  // GLUquadricObj* quadric=gluNewQuadric();
160  // gluQuadricNormals(quadric, GLU_SMOOTH);
161  // glColor4f(1.0, 0.0, 0.0, 1.0);
162 
163  GLboolean lighting, colorMaterial;
164  glGetBooleanv(GL_LIGHTING, &lighting);
165  glGetBooleanv(GL_COLOR_MATERIAL, &colorMaterial);
166 
167  glDisable(GL_COLOR_MATERIAL);
168  for (unsigned i = 0; i < m_frames.size(); ++i){
169  glPushMatrix();
170  glMultMatrixd(m_frames[i]->matrix());
171  if (withNames)
172  glPushName(i);
173 
174  float length = m_arrowLength;
175  if (frame(i)->grabsMouse())
176  length *= 2;
177 
178  const float radius = length/20;
179 
180  float color[4];
181  if (i%3 == 0){ // x
182  color[0] = 1.0f; color[1] = 0.7f; color[2] = 0.7f; color[3] = 1.0f;
183  glPushMatrix();
184  glRotatef(90.0, 0.0, 1.0, 0.0);
185 
186  } else if (i%3 == 1){ // y
187  color[0] = 0.7f; color[1] = 1.0f; color[2] = 0.7f; color[3] = 1.0f;
188  glPushMatrix();
189  glRotatef(-90.0, 1.0, 0.0, 0.0);
190 
191  } else { // z
192  glPushMatrix();
193  color[0] = 0.7f; color[1] = 0.7f; color[2] = 1.0f; color[3] = 1.0f;
194  }
195  glTranslatef(0.0, 0.0, -length/2.0);
196  glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color);
197  QGLViewer::drawArrow(length, radius);
198  glPopMatrix();
199 
200 
201 
202  if (withNames)
203  glPopName();
204 
205  glPopMatrix();
206  }
207  if (colorMaterial)
208  glEnable(GL_COLOR_MATERIAL);
209  if (!lighting)
210  glDisable(GL_LIGHTING);
211 
212 
213  //gluDeleteQuadric(quadric);
214 
215 }
216 
217 void SelectionBox::getBBXMin(float& x, float& y, float& z) const {
218  x = m_minPt.x;
219  y = m_minPt.y;
220  z = m_minPt.z;
221 }
222 
223 void SelectionBox::getBBXMax(float& x, float& y, float& z) const {
224  x = m_maxPt.x;
225  y = m_maxPt.y;
226  z = m_maxPt.z;
227 }
228 
230  int frameid = -1;
231  for (unsigned i = 0; i < m_frames.size(); ++i){
232  if (frame(i)->grabsMouse()){
233  frameid = i;
234  break;
235  }
236  }
237 
238  return frameid;
239 }
240 
241 
242 void SelectionBox::drawAxis(float length) const
243 {
244  const float radius = length/20;
245 
246  GLboolean lighting, colorMaterial;
247  glGetBooleanv(GL_LIGHTING, &lighting);
248  glGetBooleanv(GL_COLOR_MATERIAL, &colorMaterial);
249 
250  glDisable(GL_COLOR_MATERIAL);
251 
252  float color[4];
253  color[0] = 0.7f; color[1] = 0.7f; color[2] = 1.0f; color[3] = 1.0f;
254  glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color);
255  QGLViewer::drawArrow(length, radius);
256 
257  color[0] = 1.0f; color[1] = 0.7f; color[2] = 0.7f; color[3] = 1.0f;
258  glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color);
259  glPushMatrix();
260  glRotatef(90.0, 0.0, 1.0, 0.0);
261  QGLViewer::drawArrow(length, radius);
262  glPopMatrix();
263 
264  color[0] = 0.7f; color[1] = 1.0f; color[2] = 0.7f; color[3] = 1.0f;
265  glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color);
266  glPushMatrix();
267  glRotatef(-90.0, 1.0, 0.0, 0.0);
268  QGLViewer::drawArrow(length, radius);
269  glPopMatrix();
270 
271  if (colorMaterial)
272  glEnable(GL_COLOR_MATERIAL);
273  if (!lighting)
274  glDisable(GL_LIGHTING);
275 }
276 
277 
278 }
int getGrabbedFrame() const
Vec position() const
Definition: frame.cpp:537
void setTranslationConstraint(Type type, const Vec &direction)
Definition: constraint.cpp:46
A ManipulatedFrame is a Frame that can be rotated and translated using the mouse. ...
void setRotationConstraint(Type type, const Vec &direction)
Definition: constraint.cpp:69
std::vector< qglviewer::ManipulatedFrame * > m_frames
Definition: SelectionBox.h:47
void draw(bool withNames=false)
const qglviewer::ManipulatedFrame * frame(unsigned short i) const
Definition: SelectionBox.h:37
void setConstraint(Constraint *const constraint)
Definition: frame.h:361
bool grabsMouse() const
Definition: mouseGrabber.h:179
qreal z
Definition: vec.h:81
qreal y
Definition: vec.h:81
qglviewer::Vec m_maxPt
Definition: SelectionBox.h:50
The Vec class represents 3D positions and 3D vectors.
Definition: vec.h:65
void drawAxis(float length=0.2f) const
void getBBXMax(float &x, float &y, float &z) const
void setTranslation(const Vec &translation)
Definition: frame.h:201
void getBBXMin(float &x, float &y, float &z) const
qglviewer::Vec m_minPt
Definition: SelectionBox.h:49
An AxisPlaneConstraint defined in the world coordinate system.
Definition: constraint.h:299
static void drawArrow(qreal length=1.0, qreal radius=-1.0, int nbSubdivisions=12)
Definition: qglviewer.cpp:3207
qreal x
Definition: vec.h:81


octovis
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Wed Jun 5 2019 19:26:39