Class MapCanvas

Inheritance Relationships

Base Type

  • public QGLWidget

Class Documentation

class MapCanvas : public QGLWidget

Public Functions

explicit MapCanvas(QWidget *parent = nullptr)
~MapCanvas() override
void InitializeTf(std::shared_ptr<tf2_ros::Buffer> tf)
void AddPlugin(MapvizPluginPtr plugin, int order)
void RemovePlugin(MapvizPluginPtr plugin)
void SetFixedFrame(const std::string &frame)
void SetTargetFrame(const std::string &frame)
void ToggleFixOrientation(bool on)
void ToggleRotate90(bool on)
void ToggleEnableAntialiasing(bool on)
void ToggleUseLatestTransforms(bool on)
void UpdateView()
void ReorderDisplays()
void ResetLocation()
QPointF MapGlCoordToFixedFrame(const QPointF &point)
QPointF FixedFrameToMapGlCoord(const QPointF &point)
double frameRate() const
inline float ViewScale() const
inline float OffsetX() const
inline float OffsetY() const
inline void setCanvasAbleToMove(bool assigning)
void leaveEvent(QEvent *e) override
inline void SetViewScale(float scale)
inline void SetOffsetX(float x)
inline void SetOffsetY(float y)
inline void SetBackground(const QColor &color)
inline void CaptureFrames(bool enabled)
inline bool CopyCaptureBuffer(uchar *buffer)

Copies the current capture buffer into the target buffer. The target buffer must already be initialized to a size of: height * width * 4

Parameters:

buffer – An initialize buffer to copy data into

Returns:

false if the current capture buffer is empty

inline bool CopyCaptureBuffer(std::vector<uint8_t> &buffer)

Resizes a vector to be large enough to hold the current capture buffer and then copies the capture buffer into it.

Parameters:

buffer – A vector to copy the capture buffer into.

Returns:

false if the current capture buffer is empty

void CaptureFrame(bool force = false)

Public Slots

void setFrameRate(const double fps)

Signals

void Hover(double x, double y, double scale)

Protected Functions

void initializeGL() override
void initGlBlending()
void pushGlMatrices()
void popGlMatrices()
void resizeGL(int w, int h) override
void paintEvent(QPaintEvent *event) override
void wheelEvent(QWheelEvent *e) override
void mousePressEvent(QMouseEvent *e) override
void mouseReleaseEvent(QMouseEvent *e) override
void mouseMoveEvent(QMouseEvent *e) override
void keyPressEvent(QKeyEvent *e) override
void Recenter()
void TransformTarget(QPainter *painter)
void Zoom(float factor)
void InitializePixelBuffers()

Protected Attributes

bool canvas_able_to_move_ = true
bool has_pixel_buffers_
int32_t pixel_buffer_size_
GLuint pixel_buffer_ids_[2]
int32_t pixel_buffer_index_
bool capture_frames_
bool initialized_
bool fix_orientation_
bool rotate_90_
bool enable_antialiasing_
QTimer frame_rate_timer_
QColor bg_color_
Qt::MouseButton mouse_button_
bool mouse_pressed_
int mouse_x_
int mouse_y_
int mouse_previous_y_
bool mouse_hovering_
int mouse_hover_x_
int mouse_hover_y_
double offset_x_
double offset_y_
double drag_x_
double drag_y_
float view_center_x_
float view_center_y_
float view_scale_
float view_left_
float view_right_
float view_top_
float view_bottom_
float scene_left_
float scene_right_
float scene_top_
float scene_bottom_
std::string fixed_frame_
std::string target_frame_
std::shared_ptr<tf2_ros::Buffer> tf_buf_
tf2::Stamped<tf2::Transform> transform_
QTransform qtransform_
std::list<MapvizPluginPtr> plugins_
std::vector<uint8_t> capture_buffer_