37 #include <OGRE/OgreHardwarePixelBuffer.h> 49 ros::message_traits::datatype<std_msgs::Float32>(),
50 "std_msgs::Float32 topic to subscribe to.",
54 "Show value on plotter",
58 ros::message_traits::datatype<std_msgs::Float32>(),
61 "width of the plotter window",
66 "height of the plotter window",
71 "left of the plotter window",
75 "top of the plotter window",
84 "max value, used only if auto scale is disabled",
88 "min value, used only if auto scale is disabled",
91 "foreground color", QColor(25, 255, 240),
95 "foreground alpha", 0.7,
96 "alpha belnding value for foreground",
101 "background color", QColor(0, 0, 0),
105 "backround alpha", 0.0,
106 "alpha belnding value for background",
111 "linewidth of the plot",
117 "show border or not",
120 "text size of the caption",
125 "show caption",
true,
126 "show caption or not",
129 "update interval", 0.04,
130 "update interval of the plotter",
137 "change the color automatically",
143 "only used if auto color change is set to True.",
186 static int count = 0;
188 ss <<
"Plotter2DDisplayObject" << count++;
228 double r2 = (r - 0.3) / 0.7;
242 for (
int i = 0; i <
overlay_->getTextureWidth(); i++) {
243 for (
int j = 0; j <
overlay_->getTextureHeight(); j++) {
244 Hud.setPixel(i, j, bg_color.rgba());
249 QPainter painter( &Hud );
250 painter.setRenderHint(QPainter::Antialiasing,
true);
251 painter.setPen(QPen(fg_color,
line_width_, Qt::SolidLine));
253 uint16_t
w =
overlay_->getTextureWidth();
260 double v_prev = (margined_max_value -
buffer_[i - 1]) / (margined_max_value - margined_min_value);
261 double v = (margined_max_value -
buffer_[i]) / (margined_max_value - margined_min_value);
263 double u = i / (
float)buffer_length_;
266 v_prev = std::max(std::min(v_prev, 1.0), 0.0);
267 u_prev = std::max(std::min(u_prev, 1.0), 0.0);
268 v = std::max(std::min(v, 1.0), 0.0);
269 u = std::max(std::min(u, 1.0), 0.0);
271 uint16_t x_prev = (int)(u_prev * w);
272 uint16_t
x = (int)(u * w);
273 uint16_t y_prev = (int)(v_prev * h);
274 uint16_t
y = (int)(v * h);
275 painter.drawLine(x_prev, y_prev, x, y);
279 painter.drawLine(0, 0, 0, h);
280 painter.drawLine(0, h, w, h);
281 painter.drawLine(w, h, w, 0);
282 painter.drawLine(w, 0, 0, 0);
286 QFont
font = painter.font();
289 painter.setFont(font);
291 Qt::AlignCenter | Qt::AlignVCenter,
295 QFont
font = painter.font();
296 font.setPointSize(w / 4);
298 painter.setFont(font);
299 std::ostringstream ss;
300 ss << std::fixed << std::setprecision(2) <<
buffer_[
buffer_.size() - 1];
301 painter.drawText(0, 0, w, h,
302 Qt::AlignCenter | Qt::AlignVCenter,
330 buffer_[buffer_length_ - 1] = msg->data;
331 if (min_value > msg->data) {
332 min_value = msg->data;
334 if (max_value < msg->
data) {
335 max_value = msg->data;
374 if (topic_name.length() > 0 && topic_name !=
"/") {
539 return (top_ < y && top_ + texture_height_ > y &&
540 left_ < x && left_ + texture_width_ > x);
virtual QColor getColor() const
virtual bool setValue(const QVariant &new_value)
rviz::FloatProperty * fg_alpha_property_
rviz::IntProperty * top_property_
rviz::BoolProperty * auto_color_change_property_
rviz::BoolProperty * show_caption_property_
virtual void processMessage(const std_msgs::Float32::ConstPtr &msg)
rviz::BoolProperty * auto_scale_property_
virtual QImage getQImage(unsigned int width, unsigned int height)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
rviz::IntProperty * height_property_
virtual int getInt() const
virtual void setPosition(int x, int y)
rviz::FloatProperty * update_interval_property_
virtual float getFloat() const
void updateUpdateInterval()
rviz::ColorProperty * bg_color_property_
rviz::FloatProperty * max_value_property_
rviz::IntProperty * left_property_
virtual void onInitialize()
std::vector< double > buffer_
virtual bool getBool() const
OverlayObject::Ptr overlay_
rviz::BoolProperty * show_border_property_
virtual void update(float wall_dt, float ros_dt)
rviz::FloatProperty * min_value_property_
rviz::IntProperty * buffer_length_property_
void updateAutoColorChange()
rviz::RosTopicProperty * update_topic_property_
virtual void initializeBuffer()
rviz::FloatProperty * bg_alpha_property_
rviz::ColorProperty * max_color_property_
rviz::ColorProperty * fg_color_property_
rviz::IntProperty * text_size_property_
virtual void unsubscribe()
rviz::BoolProperty * show_value_property_
virtual void movePosition(int x, int y)
virtual bool isInRegion(int x, int y)
virtual ~Plotter2DDisplay()
rviz::IntProperty * line_width_property_
std::string getTopicStd() const
rviz::IntProperty * width_property_
virtual QString getName() const