rviz_2d_overlay_plugins
Loading...
Searching...
No Matches
overlay_utils.hpp
1// -*- mode: c++ -*-
2/*********************************************************************
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2022, Team Spatzenhirn
6 * Copyright (c) 2014, JSK Lab
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/o2r other materials provided
18 * with the distribution.
19 * * Neither the name of the JSK Lab nor the names of its
20 * contributors may be used to endorse or promote products derived
21 * from this software without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *********************************************************************/
36
37#ifndef RVIZ_2D_OVERLAY_PLUGINS_OVERLAY_UTILS_HPP
38#define RVIZ_2D_OVERLAY_PLUGINS_OVERLAY_UTILS_HPP
39
40#include <OgreHardwarePixelBuffer.h>
41#include <OgreMaterialManager.h>
42#include <OgreTechnique.h>
43#include <OgreTexture.h>
44#include <OgreTextureManager.h>
45#include <Overlay/OgreOverlay.h>
46#include <Overlay/OgreOverlayContainer.h>
47#include <Overlay/OgreOverlayElement.h>
48#include <Overlay/OgreOverlayManager.h>
49#include <Overlay/OgrePanelOverlayElement.h>
50#include <QColor>
51#include <QImage>
52#include <memory>
53#include <string>
54
55#include "rviz_2d_overlay_msgs/msg/overlay_text.hpp"
56
57namespace rviz_2d_overlay_plugins {
58 class OverlayObject;
59
61 public:
62 ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer);
63 virtual ~ScopedPixelBuffer();
64 virtual Ogre::HardwarePixelBufferSharedPtr getPixelBuffer();
65 virtual QImage getQImage(unsigned int width, unsigned int height);
66 virtual QImage getQImage(OverlayObject &overlay);
67 virtual QImage getQImage(unsigned int width, unsigned int height, QColor &bg_color);
68 virtual QImage getQImage(OverlayObject &overlay, QColor &bg_color);
69
70 protected:
71 Ogre::HardwarePixelBufferSharedPtr pixel_buffer_;
72 };
73
74 enum class VerticalAlignment : uint8_t {
75 CENTER = rviz_2d_overlay_msgs::msg::OverlayText::CENTER,
76 TOP = rviz_2d_overlay_msgs::msg::OverlayText::TOP,
77 BOTTOM = rviz_2d_overlay_msgs::msg::OverlayText::BOTTOM,
78 };
79
80 enum class HorizontalAlignment : uint8_t {
81 LEFT = rviz_2d_overlay_msgs::msg::OverlayText::LEFT,
82 RIGHT = rviz_2d_overlay_msgs::msg::OverlayText::RIGHT,
83 CENTER = rviz_2d_overlay_msgs::msg::OverlayText::CENTER
84 };
85
93 public:
94 using SharedPtr = std::shared_ptr<OverlayObject>;
95
96 OverlayObject(const std::string &name);
97 virtual ~OverlayObject();
98
99 virtual std::string getName() const;
100 virtual void hide();
101 virtual void show();
102 virtual bool isTextureReady() const;
103 virtual void updateTextureSize(unsigned int width, unsigned int height);
104 virtual ScopedPixelBuffer getBuffer();
105 virtual void setPosition(double hor_dist, double ver_dist,
106 HorizontalAlignment hor_alignment = HorizontalAlignment::LEFT,
107 VerticalAlignment ver_alignment = VerticalAlignment::TOP);
108 virtual void setDimensions(double width, double height);
109 virtual bool isVisible() const;
110 virtual unsigned int getTextureWidth() const;
111 virtual unsigned int getTextureHeight() const;
112
113 protected:
114 const std::string name_;
115 Ogre::Overlay *overlay_;
116 Ogre::PanelOverlayElement *panel_;
117 Ogre::MaterialPtr panel_material_;
118 Ogre::TexturePtr texture_;
119 };
120} // namespace rviz_2d_overlay_plugins
121
122#endif // RVIZ_2D_OVERLAY_PLUGINS_OVERLAY_UTILS_HPP
Definition overlay_utils.hpp:92
Definition overlay_utils.hpp:60