pictogram_display.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_RVIZ_PLUGIN_PICTOGRAM_DISPLAY_H_
38 #define JSK_RVIZ_PLUGIN_PICTOGRAM_DISPLAY_H_
39 
40 #ifndef Q_MOC_RUN
41 #include <rviz/display.h>
50 #include <OGRE/OgreSceneNode.h>
51 #include <OGRE/OgreSceneManager.h>
52 #include <jsk_rviz_plugins/Pictogram.h>
53 #include "facing_visualizer.h"
54 #endif
55 
56 namespace jsk_rviz_plugins
57 {
58  void setupFont();
59  int addFont(unsigned char* data, unsigned int data_len);
60  bool isFontAwesome(std::string);
61  bool isEntypo(std::string);
62  bool isCharacterSupported(std::string character);
63  QFont getFont(std::string character);
64  QString lookupPictogramText(std::string character);
66  // PictogramObject
69  {
70  public:
71 #if ROS_VERSION_MINIMUM(1,12,0)
72  typedef std::shared_ptr<PictogramObject> Ptr;
73 #else
75 #endif
76  PictogramObject(Ogre::SceneManager* manager,
77  Ogre::SceneNode* parent,
78  double size);
79  virtual void update(float wall_dt, float ros_dt);
80  virtual void setEnable(bool enable);
81  virtual void setText(std::string text);
82  virtual void setAlpha(double alpha);
83  virtual void setColor(QColor color);
84  virtual void setSize(double size);
85  virtual void setSpeed(double speed);
86  virtual void setPose(const geometry_msgs::Pose& pose,
87  const std::string& frame_id);
88  virtual void start();
89  virtual void setContext(rviz::DisplayContext* context);
90  virtual void setAction(uint8_t action);
91  virtual void setMode(uint8_t mode);
92  virtual void setTTL(double ttl);
93  protected:
94  virtual void updatePose(float dt);
95  virtual void updateColor();
96  virtual void updateText();
97 
99  uint8_t action_;
100  geometry_msgs::Pose pose_;
101  std::string frame_id_;
104  double ttl_;
105  double speed_;
106  uint8_t mode_;
107  private:
108 
109  };
110 
111 
113  // Display to visualize pictogram on rviz
116  public rviz::MessageFilterDisplay<jsk_rviz_plugins::Pictogram>
117  {
118  Q_OBJECT
119  public:
121  virtual ~PictogramDisplay();
122  protected:
123 
125  // methods
127  virtual void onInitialize();
128  virtual void reset();
129  virtual void onEnable();
130  void processMessage(const jsk_rviz_plugins::Pictogram::ConstPtr& msg);
131  void update(float wall_dt, float ros_dt);
132 
134  // parameters
136  boost::mutex mutex_;
138  private Q_SLOTS:
139 
140  private:
141  };
142 }
143 
144 #endif
msg
QString lookupPictogramText(std::string character)
QFont getFont(std::string character)
virtual void setAlpha(double alpha)
virtual void setContext(rviz::DisplayContext *context)
boost::shared_ptr< PictogramObject > Ptr
bool isCharacterSupported(std::string character)
int addFont(unsigned char *data, unsigned int data_len)
virtual void setMode(uint8_t mode)
virtual void update(float wall_dt, float ros_dt)
virtual void setSize(double size)
bool isEntypo(std::string text)
bool isFontAwesome(std::string text)
virtual void setText(std::string text)
virtual void setSpeed(double speed)
virtual void setEnable(bool enable)
virtual void setPose(const geometry_msgs::Pose &pose, const std::string &frame_id)
virtual void setColor(QColor color)
virtual void setAction(uint8_t action)
PictogramObject(Ogre::SceneManager *manager, Ogre::SceneNode *parent, double size)


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Thu Jun 1 2023 02:45:58