45 return a->DrawOrder() < b->DrawOrder();
49 QGLWidget(QGLFormat(QGL::SampleBuffers), parent),
50 has_pixel_buffers_(false),
51 pixel_buffer_size_(0),
52 pixel_buffer_index_(0),
53 capture_frames_(false),
55 fix_orientation_(false),
57 enable_antialiasing_(true),
58 mouse_button_(Qt::NoButton),
59 mouse_pressed_(false),
63 mouse_hovering_(false),
83 setMouseTracking(
true);
90 setFocusPolicy(Qt::StrongFocus);
110 int32_t buffer_size = width() * height() * 4;
121 glBufferDataARB(GL_PIXEL_PACK_BUFFER_ARB, buffer_size, 0, GL_STREAM_READ_ARB);
123 glBufferDataARB(GL_PIXEL_PACK_BUFFER_ARB, buffer_size, 0, GL_STREAM_READ_ARB);
124 glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, 0);
133 GLenum err = glewInit();
136 ROS_ERROR(
"Error: %s\n", glewGetErrorString(err));
141 std::string extensions = (
const char*)glGetString(GL_EXTENSIONS);
142 has_pixel_buffers_ = extensions.find(
"GL_ARB_pixel_buffer_object") != std::string::npos;
145 glClearColor(0.58
f, 0.56
f, 0.5
f, 1);
148 glEnable(GL_MULTISAMPLE);
149 glEnable(GL_POINT_SMOOTH);
150 glEnable(GL_LINE_SMOOTH);
151 glEnable(GL_POLYGON_SMOOTH);
152 glHint(GL_LINE_SMOOTH_HINT, GL_NICEST);
153 glHint(GL_POINT_SMOOTH_HINT, GL_NICEST);
154 glHint(GL_POLYGON_SMOOTH_HINT, GL_NICEST);
158 glDisable(GL_MULTISAMPLE);
159 glDisable(GL_POINT_SMOOTH);
160 glDisable(GL_LINE_SMOOTH);
161 glDisable(GL_POLYGON_SMOOTH);
171 glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
172 glDepthFunc(GL_NEVER);
173 glDisable(GL_DEPTH_TEST);
184 glPixelStorei(GL_PACK_ALIGNMENT, 4);
194 glReadPixels(0, 0, width(), height(), GL_BGRA, GL_UNSIGNED_BYTE, 0);
196 GLubyte*
data =
reinterpret_cast<GLubyte*
>(glMapBufferARB(GL_PIXEL_PACK_BUFFER_ARB, GL_READ_ONLY_ARB));
203 glUnmapBufferARB(GL_PIXEL_PACK_BUFFER_ARB);
205 glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, 0);
209 int32_t buffer_size = width() * height() * 4;
213 glReadPixels(0, 0, width(), height(), GL_BGRA, GL_UNSIGNED_BYTE, &
capture_buffer_[0]);
225 p.setRenderHints(QPainter::Antialiasing |
226 QPainter::TextAntialiasing |
227 QPainter::SmoothPixmapTransform |
228 QPainter::HighQualityAntialiasing,
230 p.beginNativePainting();
234 glMatrixMode(GL_MODELVIEW);
239 glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
257 std::list<MapvizPluginPtr>::iterator it;
267 if ((*it)->SupportsPainting())
269 p.endNativePainting();
271 p.beginNativePainting();
278 glMatrixMode(GL_MODELVIEW);
280 p.endNativePainting();
285 glMatrixMode(GL_TEXTURE);
287 glMatrixMode(GL_PROJECTION);
289 glMatrixMode(GL_MODELVIEW);
291 glPushAttrib(GL_ALL_ATTRIB_BITS);
297 glMatrixMode(GL_MODELVIEW);
299 glMatrixMode(GL_PROJECTION);
301 glMatrixMode(GL_TEXTURE);
307 float numDegrees = e->delta() / -8;
309 Zoom(numDegrees / 10.0);
331 std::list<MapvizPluginPtr>::iterator it;
340 bool invertible =
true;
341 return qtransform_.inverted(&invertible).map(point);
367 case Qt::MiddleButton:
374 case Qt::RightButton:
378 Zoom(((
float)diff) / 10.0
f);
390 double x = center_x + (e->x() - width() / 2.0) *
view_scale_;
391 double y = center_y + (height() / 2.0 - e->y()) *
view_scale_;
406 Q_EMIT
Hover(0, 0, 0);
412 std::list<MapvizPluginPtr>::iterator it;
415 (*it)->SetTargetFrame(frame);
443 format.setSwapInterval(1);
446 this->setFormat(format);
451 std::list<MapvizPluginPtr>::iterator it;
454 (*it)->SetUseLatestTransforms(on);
489 bool success =
false;
507 double roll, pitch, yaw;
510 glRotatef(-yaw * 57.2957795, 0, 0, 1);
523 qtransform_ = qtransform_.scale(1, -1);
524 painter->setWorldTransform(qtransform_,
false);
571 glViewport(0, 0, width(), height());
572 glMatrixMode(GL_PROJECTION);
576 qtransform_ = QTransform::fromTranslate(width() / 2.0, height() / 2.0).
604 ROS_ERROR(
"Invalid frame rate: %f", fps);
static const long double _half_pi
void mouseMoveEvent(QMouseEvent *e)
QPointF MapGlCoordToFixedFrame(const QPointF &point)
void RemovePlugin(MapvizPluginPtr plugin)
void setFrameRate(const double fps)
void TransformTarget(QPainter *painter)
void CaptureFrame(bool force=false)
void resizeGL(int w, int h)
std::vector< uint8_t > capture_buffer_
boost::shared_ptr< tf::TransformListener > tf_
void keyPressEvent(QKeyEvent *e)
void leaveEvent(QEvent *e)
void InitializeTf(boost::shared_ptr< tf::TransformListener > tf)
Qt::MouseButton mouse_button_
tf::StampedTransform transform_
void ToggleEnableAntialiasing(bool on)
TFSIMD_FORCE_INLINE const tfScalar & getY() const
void SetFixedFrame(const std::string &frame)
TFSIMD_FORCE_INLINE const tfScalar & y() const
int32_t pixel_buffer_index_
bool compare_plugins(MapvizPluginPtr a, MapvizPluginPtr b)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
int32_t pixel_buffer_size_
bool enable_antialiasing_
void wheelEvent(QWheelEvent *e)
void mouseReleaseEvent(QMouseEvent *e)
GLuint pixel_buffer_ids_[2]
static Quaternion createQuaternionFromYaw(double yaw)
QPointF FixedFrameToMapGlCoord(const QPointF &point)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
#define ROS_ERROR_THROTTLE(period,...)
void InitializePixelBuffers()
TFSIMD_FORCE_INLINE const tfScalar & x() const
void ToggleRotate90(bool on)
void Hover(double x, double y, double scale)
std::string target_frame_
void ToggleUseLatestTransforms(bool on)
void SetTargetFrame(const std::string &frame)
std::list< MapvizPluginPtr > plugins_
TFSIMD_FORCE_INLINE const tfScalar & getX() const
void ToggleFixOrientation(bool on)
void paintEvent(QPaintEvent *event)
void SetViewScale(float scale)
void mousePressEvent(QMouseEvent *e)
void AddPlugin(MapvizPluginPtr plugin, int order)
MapCanvas(QWidget *parent=0)