g2o
Namespaces | Macros | Functions
libviewer
Collaboration diagram for libviewer:

Namespaces

 g2o
 
 g2o::opengl
 

Macros

#define G2O_OPENGL_API
 

Functions

void g2o::opengl::drawBox (GLfloat l, GLfloat w, GLfloat h)
 
void g2o::opengl::drawPlane (GLfloat l, GLfloat w)
 
void g2o::opengl::drawSphere (GLfloat radius)
 
void g2o::opengl::drawEllipsoid (GLfloat r1, GLfloat r2, GLfloat r3)
 
void g2o::opengl::drawCone (GLfloat radius, GLfloat height)
 
void g2o::opengl::drawDisk (GLfloat radius)
 
void g2o::opengl::drawCylinder (GLfloat radius, GLfloat height)
 
void g2o::opengl::drawPyramid (GLfloat length, GLfloat height)
 
void g2o::opengl::drawRangeRing (GLfloat range, GLfloat fov, GLfloat range_width)
 
void g2o::opengl::drawSlice (GLfloat radius, GLfloat height, GLfloat fov, int slices_per_circle)
 
void g2o::opengl::drawPoseBox ()
 
void g2o::opengl::drawArrow2D (float len, float head_width, float head_len)
 
void g2o::opengl::drawPoint (float pointSize)
 

Detailed Description

Macro Definition Documentation

#define G2O_OPENGL_API

Definition at line 44 of file opengl_primitives.h.

Function Documentation

void G2O_OPENGL_API g2o::opengl::drawArrow2D ( float  len,
float  head_width,
float  head_len 
)

draw a 2D arrow along the x axis with the given len

Definition at line 59 of file opengl_primitives.cpp.

Referenced by g2o::VertexSE2WriteGnuplotAction::operator()(), g2o::EdgeSE2WriteGnuplotAction::operator()(), and g2o::VertexSE3WriteGnuplotAction::operator()().

60 {
61  glBegin(GL_LINES);
62  glVertex2f(0.f, 0.f);
63  glVertex2f(len, 0.f);
64  glEnd();
65 
66  glNormal3f(0.f,0.f,1.f);
67  glBegin(GL_TRIANGLES);
68  glVertex2f(len, 0.f);
69  glVertex2f(len - head_len, 0.5f*head_width);
70  glVertex2f(len - head_len, -0.5f*head_width);
71  glEnd();
72 }
void G2O_OPENGL_API g2o::opengl::drawBox ( GLfloat  l,
GLfloat  w,
GLfloat  h 
)

draw a box that is centered in the current coordinate frame

Parameters
llength of the box (x dimension)
wwidth of the box (y dimension)
hheight of the box (z dimension)

Definition at line 108 of file opengl_primitives.cpp.

Referenced by g2o::opengl::drawPoseBox(), g2o::CacheSE3Offset::setOffsetParam(), and g2o::VertexTag::write().

109 {
110  GLfloat sx = l*0.5f;
111  GLfloat sy = w*0.5f;
112  GLfloat sz = h*0.5f;
113 
114  glBegin(GL_QUADS);
115  // bottom
116  glNormal3f( 0.0f, 0.0f,-1.0f);
117  glVertex3f(-sx, -sy, -sz);
118  glVertex3f(-sx, sy, -sz);
119  glVertex3f(sx, sy, -sz);
120  glVertex3f(sx, -sy, -sz);
121  // top
122  glNormal3f( 0.0f, 0.0f,1.0f);
123  glVertex3f(-sx, -sy, sz);
124  glVertex3f(-sx, sy, sz);
125  glVertex3f(sx, sy, sz);
126  glVertex3f(sx, -sy, sz);
127  // back
128  glNormal3f(-1.0f, 0.0f, 0.0f);
129  glVertex3f(-sx, -sy, -sz);
130  glVertex3f(-sx, sy, -sz);
131  glVertex3f(-sx, sy, sz);
132  glVertex3f(-sx, -sy, sz);
133  // front
134  glNormal3f( 1.0f, 0.0f, 0.0f);
135  glVertex3f(sx, -sy, -sz);
136  glVertex3f(sx, sy, -sz);
137  glVertex3f(sx, sy, sz);
138  glVertex3f(sx, -sy, sz);
139  // left
140  glNormal3f( 0.0f, -1.0f, 0.0f);
141  glVertex3f(-sx, -sy, -sz);
142  glVertex3f(sx, -sy, -sz);
143  glVertex3f(sx, -sy, sz);
144  glVertex3f(-sx, -sy, sz);
145  //right
146  glNormal3f( 0.0f, 1.0f, 0.0f);
147  glVertex3f(-sx, sy, -sz);
148  glVertex3f(sx, sy, -sz);
149  glVertex3f(sx, sy, sz);
150  glVertex3f(-sx, sy, sz);
151  glEnd();
152 }
void G2O_OPENGL_API g2o::opengl::drawCone ( GLfloat  radius,
GLfloat  height 
)

draw a cone

Definition at line 186 of file opengl_primitives.cpp.

References g2o::opengl::GLUWrapper::getQuadradic().

187 {
188  glPushMatrix();
189  glRotatef(-90.f, 1.f, 0.f, 0.f);
190  glTranslatef(0.f, 0.f, - height/2.0f);
191  gluCylinder(GLUWrapper::getQuadradic(), radius, 0.f, height, 32, 1);
192  gluDisk(GLUWrapper::getQuadradic(), 0, radius, 32, 1);
193  glPopMatrix();
194 }
void G2O_OPENGL_API g2o::opengl::drawCylinder ( GLfloat  radius,
GLfloat  height 
)

draw a (closed) cylinder

Parameters
radiusthe radius of the cylinder
heightthe height of the cylinder

Definition at line 196 of file opengl_primitives.cpp.

References g2o::opengl::GLUWrapper::getQuadradic().

197 {
198  glPushMatrix();
199  glRotatef(-90, 1.f, 0.f, 0.f);
200  glTranslatef(0.f, 0.f, + height/2.0f);
201  gluDisk(GLUWrapper::getQuadradic(), 0.f, radius, 32, 1);
202  glTranslatef(0, 0, - height);
203  gluCylinder(GLUWrapper::getQuadradic(), radius, radius, height, 32, 1);
204  glRotatef(180, 1.f, 0.f, 0.f);
205  gluDisk(GLUWrapper::getQuadradic(), 0, radius, 32, 1);
206  glPopMatrix();
207 }
void G2O_OPENGL_API g2o::opengl::drawDisk ( GLfloat  radius)

draw a disk

Definition at line 209 of file opengl_primitives.cpp.

References g2o::opengl::GLUWrapper::getQuadradic().

210 {
211  glRotatef(90, 0.f, 1.f, 0.f);
212  gluDisk(GLUWrapper::getQuadradic(), 0, radius, 32, 1);
213 }
void G2O_OPENGL_API g2o::opengl::drawEllipsoid ( GLfloat  r1,
GLfloat  r2,
GLfloat  r3 
)

draw a ellipsoid whose center is in the origin of the current coordinate frame

Parameters
r1radius along x axis
r2radius along y axis
r3radius along z axis

Definition at line 173 of file opengl_primitives.cpp.

References g2o::opengl::GLUWrapper::getQuadradic().

174 {
175  GLboolean hasNormalization = glIsEnabled(GL_NORMALIZE);
176  if (!hasNormalization)
177  glEnable(GL_NORMALIZE);
178  glPushMatrix();
179  glScalef(r1, r2, r3);
180  gluSphere(GLUWrapper::getQuadradic(), 1.0f, 32, 32);
181  glPopMatrix();
182  if (!hasNormalization)
183  glDisable(GL_NORMALIZE);
184 }
void G2O_OPENGL_API g2o::opengl::drawPlane ( GLfloat  l,
GLfloat  w 
)

draw a plane in x-y dimension with a height of zero

Parameters
llength in x
wwidth in y

Definition at line 154 of file opengl_primitives.cpp.

155 {
156  GLfloat sx = l*0.5f;
157  GLfloat sy = w*0.5f;
158 
159  glBegin(GL_QUADS);
160  glNormal3f( 0.0f, 0.0f, 1.0f);
161  glVertex3f(-sx, -sy, 0.f);
162  glVertex3f(-sx, sy, 0.f);
163  glVertex3f(sx, sy, 0.f);
164  glVertex3f(sx, -sy, 0.f);
165  glEnd();
166 }
void G2O_OPENGL_API g2o::opengl::drawPoint ( float  pointSize)

draw a point in the origin, having a size of pointSize

Definition at line 301 of file opengl_primitives.cpp.

Referenced by g2o::VertexPointXYWriteGnuplotAction::operator()(), and g2o::VertexPointXYZ::write().

301  {
302  glPointSize(pointSize);
303  glBegin(GL_POINTS);
304  glVertex3f(0,0,0);
305  glEnd();
306  }
void G2O_OPENGL_API g2o::opengl::drawPoseBox ( )

draws a box used to represent a 6d pose

Definition at line 74 of file opengl_primitives.cpp.

References g2o::opengl::drawBox().

75 {
76  glPushMatrix();
77  glScalef(0.5f,1.f,1.f);
78  glPushMatrix();
79  glScalef(1.f,0.25f,0.5f);
80  glTranslatef(-0.5f,0.5f,0.f);
81  glColor3f(1.0f, 0.3f, 0.3f);
82  drawBox(1.f, 1.f, 1.f);
83  glPopMatrix();
84 
85  glPushMatrix();
86  glScalef(1.f,0.25f,0.5f);
87  glTranslatef(-0.5f,-0.5f,0.f);
88  glColor3f(1.0f, 0.1f, 0.1f);
89  drawBox(1.f, 1.f, 1.f);
90  glPopMatrix();
91 
92  glPushMatrix();
93  glScalef(1.f,0.25f,0.5f);
94  glTranslatef(+0.5f,0.5f,0.f);
95  glColor3f(0.3f, 0.3f, 1.0f);
96  drawBox(1.f, 1.f, 1.f);
97  glPopMatrix();
98 
99  glPushMatrix();
100  glScalef(1.f,0.25f,0.5f);
101  glTranslatef(+0.5f,-0.5f,0.f);
102  glColor3f(0.1f, 0.1f, 1.f);
103  drawBox(1.f, 1.f, 1.f);
104  glPopMatrix();
105  glPopMatrix();
106 }
void drawBox(GLfloat l, GLfloat w, GLfloat h)
void G2O_OPENGL_API g2o::opengl::drawPyramid ( GLfloat  length,
GLfloat  height 
)

draw a pyramid

Definition at line 215 of file opengl_primitives.cpp.

References g2o::opengl::GLUWrapper::getQuadradic().

Referenced by g2o::CacheCamera::updateImpl().

216 {
217  glPushMatrix();
218  glTranslatef(0.f, 0.f, - height/2.0f);
219  glRotatef(45, 0.f, 0.f, 1.f);
220  gluCylinder(GLUWrapper::getQuadradic(), length, 0.f, height, 4, 1);
221  gluDisk(GLUWrapper::getQuadradic(), 0, length, 4, 1);
222  glPopMatrix();
223 }
void G2O_OPENGL_API g2o::opengl::drawRangeRing ( GLfloat  range,
GLfloat  fov,
GLfloat  range_width = 0.05 
)

draw a range ring

Parameters
rangethe range (radius) of the partial ring
fovField Of View of the range sensor
range_widthspecify how thick the ring should be drawn

Definition at line 225 of file opengl_primitives.cpp.

References g2o::opengl::GLUWrapper::getQuadradic().

226 {
227  glPushMatrix();
228  glRotatef((fov/2.0f) - 90, 0.f, 0.f, 1.f);
229  gluPartialDisk(GLUWrapper::getQuadradic(), range, range + range_width, 32, 1, 0.f, fov);
230  glPopMatrix();
231 }
void G2O_OPENGL_API g2o::opengl::drawSlice ( GLfloat  radius,
GLfloat  height,
GLfloat  fov,
int  slices_per_circle = 32 
)

draw a slice of a cylinder (approximated with slices_per_circle triangles for the complete circle)

Parameters
radiusthe radius of the cylinder
heightthe height of the cylinder
fovthe "fov" of the slice (om degree)
slices_per_circlethe number of triangle used to approximate the fulle circle

Definition at line 233 of file opengl_primitives.cpp.

References M_PI.

234 {
235  double fov_rad = fov/180.*M_PI; // convert to rad
236  int num_slices = int(slices_per_circle * (fov_rad / (2*M_PI))) + 1;
237  double angle_step = fov_rad / num_slices;
238  double angle_step_half = angle_step * 0.5;
239 
240  GLfloat height_half = height * 0.5f;
241  GLfloat lower_z = -height_half;
242  GLfloat upper_z = height_half;
243 
244  GLfloat last_x = float(std::cos(-fov_rad * 0.5f) * radius);
245  GLfloat last_y = float(std::sin(-fov_rad * 0.5f) * radius);
246 
247  glPushMatrix();
248  glBegin(GL_TRIANGLES);
249  glNormal3f((float)std::sin(-fov_rad * 0.5), (float)-std::cos(-fov_rad * 0.5), 0.f);
250  glVertex3f(0.f, 0.f, upper_z);
251  glVertex3f(0.f, 0.f, lower_z);
252  glVertex3f(last_x, last_y, upper_z);
253  glVertex3f(last_x, last_y, upper_z);
254  glVertex3f(last_x, last_y, lower_z);
255  glVertex3f(0.f, 0.f, lower_z);
256 
257  double start_angle = -0.5*fov_rad + angle_step;
258  double angle = start_angle;
259  for (int i = 0; i < num_slices; ++i) {
260  GLfloat x = float(std::cos(angle) * radius);
261  GLfloat y = float(std::sin(angle) * radius);
262  GLfloat front_normal_x = (float)std::cos(angle + angle_step_half);
263  GLfloat front_normal_y = (float)std::sin(angle + angle_step_half);
264 
265  // lower triangle
266  glNormal3f(0.f, 0.f, -1.f);
267  glVertex3f(0.f, 0.f, lower_z);
268  glVertex3f(x, y, lower_z);
269  glVertex3f(last_x, last_y, lower_z);
270  // upper
271  glNormal3f(0.f, 0.f, 1.f);
272  glVertex3f(0.f, 0.f, upper_z);
273  glVertex3f(x, y, upper_z);
274  glVertex3f(last_x, last_y, upper_z);
275  //front rectangle (we use two triangles)
276  glNormal3f(front_normal_x, front_normal_y, 0.f);
277  glVertex3f(last_x, last_y, upper_z);
278  glVertex3f(last_x, last_y, lower_z);
279  glVertex3f(x, y, upper_z);
280  glVertex3f(x, y, upper_z);
281  glVertex3f(x, y, lower_z);
282  glVertex3f(last_x, last_y, lower_z);
283 
284  last_x = x;
285  last_y = y;
286  angle += angle_step;
287  }
288 
289  glNormal3f(float(-std::sin(fov_rad * 0.5)), float(std::cos(fov_rad * 0.5)), -0.f);
290  glVertex3f(0.f, 0.f, upper_z);
291  glVertex3f(0.f, 0.f, lower_z);
292  glVertex3f(last_x, last_y, upper_z);
293  glVertex3f(last_x, last_y, upper_z);
294  glVertex3f(last_x, last_y, lower_z);
295  glVertex3f(0.f, 0.f, lower_z);
296 
297  glEnd();
298  glPopMatrix();
299 }
#define M_PI
Definition: misc.h:34
void G2O_OPENGL_API g2o::opengl::drawSphere ( GLfloat  radius)

draw a sphere whose center is in the origin of the current coordinate frame

Parameters
radiusthe radius of the sphere

Definition at line 168 of file opengl_primitives.cpp.

References g2o::opengl::GLUWrapper::getQuadradic().

169 {
170  gluSphere(GLUWrapper::getQuadradic(), radius, 32, 32);
171 }