Go to the documentation of this file.
   30 #ifndef MAPVIZ_MAP_CANVAS_H_ 
   31 #define MAPVIZ_MAP_CANVAS_H_ 
   39 #include <boost/shared_ptr.hpp> 
   43 #include <QMouseEvent> 
   44 #include <QWheelEvent> 
  165     void Hover(
double x, 
double y, 
double scale);
 
  185     void Zoom(
float factor);
 
  255 #endif  // MAPVIZ_MAP_CANVAS_H_ 
  
bool CopyCaptureBuffer(uchar *buffer)
void InitializePixelBuffers()
boost::shared_ptr< tf::TransformListener > tf_
std::string target_frame_
QPointF FixedFrameToMapGlCoord(const QPointF &point)
void resizeGL(int w, int h)
bool enable_antialiasing_
void ToggleRotate90(bool on)
void mouseReleaseEvent(QMouseEvent *e)
void SetBackground(const QColor &color)
QPointF MapGlCoordToFixedFrame(const QPointF &point)
tf::StampedTransform transform_
void mousePressEvent(QMouseEvent *e)
void mouseMoveEvent(QMouseEvent *e)
void CaptureFrame(bool force=false)
void RemovePlugin(MapvizPluginPtr plugin)
void setCanvasAbleToMove(bool assigning)
void InitializeTf(boost::shared_ptr< tf::TransformListener > tf)
Qt::MouseButton mouse_button_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void setFrameRate(const double fps)
std::list< MapvizPluginPtr > plugins_
void SetFixedFrame(const std::string &frame)
int32_t pixel_buffer_size_
void wheelEvent(QWheelEvent *e)
void TransformTarget(QPainter *painter)
int32_t pixel_buffer_index_
void leaveEvent(QEvent *e)
void ToggleFixOrientation(bool on)
void SetViewScale(float scale)
void paintEvent(QPaintEvent *event)
void CaptureFrames(bool enabled)
bool CopyCaptureBuffer(std::vector< uint8_t > &buffer)
void keyPressEvent(QKeyEvent *e)
void ToggleEnableAntialiasing(bool on)
GLuint pixel_buffer_ids_[2]
void SetTargetFrame(const std::string &frame)
bool canvas_able_to_move_
void Hover(double x, double y, double scale)
void AddPlugin(MapvizPluginPtr plugin, int order)
std::vector< uint8_t > capture_buffer_
MapCanvas(QWidget *parent=0)
mapviz
Author(s): Marc Alban
autogenerated on Sun Sep 8 2024 02:27:09