40 #include <boost/algorithm/string.hpp> 41 #include <boost/format.hpp> 43 #include <OGRE/OgreHardwarePixelBuffer.h> 44 #include <OGRE/OgreMaterialManager.h> 45 #include <OGRE/OgreTexture.h> 47 #include <QFontDatabase> 49 #include <QStaticText> 50 #include <QTextDocument> 56 texture_width_(0), texture_height_(0),
60 bg_color_(0, 0, 0, 0),
61 fg_color_(255, 255, 255, 255.0),
62 require_update_texture_(false)
66 ros::message_traits::datatype<std_msgs::String>(),
67 "std_msgs::String topic to subscribe to.",
70 "Overtake Position Properties",
false,
71 "overtake position properties specified by message such as left, top and font",
74 "Overtake Color Properties",
false,
75 "overtake color properties specified by message such as foreground/background color and alpha",
78 "Align Bottom",
false,
79 "align text with the bottom of the overlay region",
112 "Foreground Color", QColor(25, 255, 240),
116 "Foreground Alpha", 0.8,
"Foreground Alpha",
121 "Background Color", QColor(0, 0, 0),
125 "Background Alpha", 0.8,
"Background Alpha",
130 QFontDatabase database;
133 "font",
"DejaVu Sans Mono",
189 if (topic_name.length() > 0 && topic_name !=
"/")
242 QPainter painter( &Hud );
243 painter.setRenderHint(QPainter::Antialiasing,
true);
245 uint16_t
w =
overlay_->getTextureWidth();
246 uint16_t h =
overlay_->getTextureHeight();
251 QFont
font(
font_.length() > 0 ?
font_.c_str():
"Liberation Sans");
254 painter.setFont(
font);
256 if (
text_.length() > 0)
258 std::string color_wrapped_text
259 = (boost::format(
"<span style=\"color: rgba(%2%, %3%, %4%, %5%)\">%1%</span>")
262 QStaticText static_text(
263 boost::algorithm::replace_all_copy(color_wrapped_text,
"\n",
"<br >").c_str());
264 static_text.setTextWidth(w);
267 painter.drawStaticText(0, 0, static_text);
271 QStaticText only_wrapped_text(color_wrapped_text.c_str());
272 QFontMetrics fm(painter.fontMetrics());
273 QRect text_rect = fm.boundingRect(0, 0, w, h,
274 Qt::TextWordWrap | Qt::AlignLeft | Qt::AlignTop,
275 only_wrapped_text.text().remove(QRegExp(
"<[^>]*>")));
276 painter.drawStaticText(0, h - text_rect.height(), static_text);
286 (
const std_msgs::String::ConstPtr& msg)
294 static int count = 0;
296 ss <<
"StringDisplayObject" << count++;
482 ROS_FATAL(
"Unexpected error at selecting font index %d.", font_index);
502 return (top_ < y && top_ + texture_height_ > y &&
503 left_ < x && left_ + texture_width_ > x);
virtual QColor getColor() const
virtual bool setValue(const QVariant &new_value)
void updateOvertakeColorProperties()
rviz::EnumProperty * font_property_
rviz::IntProperty * top_property_
rviz::IntProperty * left_property_
virtual QImage getQImage(unsigned int width, unsigned int height)
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
rviz::ColorProperty * fg_color_property_
rviz::BoolProperty * overtake_color_properties_property_
virtual int getInt() const
rviz::IntProperty * text_size_property_
void updateOvertakePositionProperties()
virtual float getFloat() const
QStringList font_families_
virtual bool getBool() const
virtual void unsubscribe()
virtual bool isInRegion(int x, int y)
virtual void setPosition(int x, int y)
virtual void addOption(const QString &option, int value=0)
bool overtake_color_properties_
virtual void onInitialize()
rviz::ColorProperty * bg_color_property_
rviz::IntProperty * width_property_
rviz::BoolProperty * align_bottom_property_
rviz::BoolProperty * overtake_position_properties_property_
OverlayObject::Ptr overlay_
rviz::IntProperty * line_width_property_
rviz::RosTopicProperty * update_topic_property_
virtual void movePosition(int x, int y)
rviz::FloatProperty * bg_alpha_property_
bool overtake_position_properties_
std::string getTopicStd() const
virtual int getOptionInt()
virtual void update(float wall_dt, float ros_dt)
bool require_update_texture_
rviz::IntProperty * height_property_
rviz::FloatProperty * fg_alpha_property_
void processMessage(const std_msgs::String::ConstPtr &msg)