30 #ifndef MAPVIZ_MAP_CANVAS_H_ 31 #define MAPVIZ_MAP_CANVAS_H_ 39 #include <boost/shared_ptr.hpp> 43 #include <QMouseEvent> 44 #include <QWheelEvent> 166 void Hover(
double x,
double y,
double scale);
186 void Zoom(
float factor);
256 #endif // MAPVIZ_MAP_CANVAS_H_ void mouseMoveEvent(QMouseEvent *e)
void CaptureFrames(bool enabled)
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)
void SetFixedFrame(const std::string &frame)
int32_t pixel_buffer_index_
TFSIMD_FORCE_INLINE const tfScalar & y() const
void SetBackground(const QColor &color)
void setCanvasAbleToMove(bool assigning)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
bool canvas_able_to_move_
int32_t pixel_buffer_size_
bool enable_antialiasing_
void wheelEvent(QWheelEvent *e)
void mouseReleaseEvent(QMouseEvent *e)
GLuint pixel_buffer_ids_[2]
QPointF FixedFrameToMapGlCoord(const QPointF &point)
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_
TFSIMD_FORCE_INLINE const tfScalar & w() const
bool CopyCaptureBuffer(uchar *buffer)
void ToggleUseLatestTransforms(bool on)
void SetTargetFrame(const std::string &frame)
std::list< MapvizPluginPtr > plugins_
void ToggleFixOrientation(bool on)
void paintEvent(QPaintEvent *event)
void SetViewScale(float scale)
void mousePressEvent(QMouseEvent *e)
void AddPlugin(MapvizPluginPtr plugin, int order)
bool CopyCaptureBuffer(std::vector< uint8_t > &buffer)
MapCanvas(QWidget *parent=0)