37 #include <OGRE/OgreHardwarePixelBuffer.h>
45 :
rviz::Display(), min_value_(0.0), max_value_(0.0)
49 ros::message_traits::datatype<std_msgs::Float32>(),
50 "std_msgs::Float32 topic to subscribe to.",
54 "Show value on plotter",
55 this, SLOT(updateShowValue()));
58 ros::message_traits::datatype<std_msgs::Float32>(),
59 this, SLOT(updateBufferSize()));
61 "width of the plotter window",
62 this, SLOT(updateWidth()));
63 width_property_->setMin(1);
64 width_property_->setMax(2000);
66 "height of the plotter window",
67 this, SLOT(updateHeight()));
68 height_property_->setMin(1);
69 height_property_->setMax(2000);
71 "left of the plotter window",
75 "top of the plotter window",
81 this, SLOT(updateAutoScale()));
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",
112 this, SLOT(updateLineWidth()));
113 line_width_property_->setMin(1);
114 line_width_property_->setMax(1000);
117 "show border or not",
118 this, SLOT(updateShowBorder()));
120 "text size of the caption",
122 auto_text_size_in_plot_property_ =
new rviz::BoolProperty(
"auto text size in plot",
true,
123 "automatiacally adjust text size of the value in plot",
124 this, SLOT(updateAutoTextSizeInPlot()));
126 "text size of the value in plot",
127 this, SLOT(updateTextSizeInPlot()));
131 "show caption",
true,
132 "show caption or not",
135 "update interval", 0.04,
136 "update interval of the plotter",
137 this, SLOT(updateUpdateInterval()));
138 update_interval_property_->setMin(0.0);
139 update_interval_property_->setMax(100);
143 "change the color automatically",
149 "only used if auto color change is set to True.",
192 static int count = 0;
194 ss <<
"Plotter2DDisplayObject" <<
count++;
195 overlay_.reset(
new OverlayObject(ss.str()));
236 double r2 = (
r - 0.3) / 0.7;
250 for (
int i = 0; i <
overlay_->getTextureWidth(); i++) {
251 for (
int j = 0; j <
overlay_->getTextureHeight(); j++) {
252 Hud.setPixel(i, j,
bg_color.rgba());
257 QPainter painter( &Hud );
258 painter.setRenderHint(QPainter::Antialiasing,
true);
261 uint16_t
w =
overlay_->getTextureWidth();
268 double v_prev = (margined_max_value -
buffer_[i - 1]) / (margined_max_value - margined_min_value);
269 double v = (margined_max_value -
buffer_[i]) / (margined_max_value - margined_min_value);
274 v_prev = std::max(std::min(v_prev, 1.0), 0.0);
275 u_prev = std::max(std::min(u_prev, 1.0), 0.0);
276 v = std::max(std::min(v, 1.0), 0.0);
277 u = std::max(std::min(u, 1.0), 0.0);
279 uint16_t x_prev = (int)(u_prev *
w);
280 uint16_t
x = (int)(u *
w);
281 uint16_t y_prev = (int)(v_prev * h);
282 uint16_t
y = (int)(v * h);
283 painter.drawLine(x_prev, y_prev,
x,
y);
287 painter.drawLine(0, 0, 0, h);
288 painter.drawLine(0, h,
w, h);
289 painter.drawLine(
w, h,
w, 0);
290 painter.drawLine(
w, 0, 0, 0);
294 QFont
font = painter.font();
297 painter.setFont(
font);
299 Qt::AlignCenter | Qt::AlignVCenter,
303 QFont
font = painter.font();
305 font.setPointSize(
w / 4);
310 painter.setFont(
font);
311 std::ostringstream ss;
312 ss << std::fixed << std::setprecision(2) <<
buffer_[
buffer_.size() - 1];
313 painter.drawText(0, 0,
w, h,
314 Qt::AlignCenter | Qt::AlignVCenter,
343 if (min_value >
msg->data) {
344 min_value =
msg->data;
346 if (max_value < msg->data) {
347 max_value =
msg->data;
386 if (topic_name.length() > 0 && topic_name !=
"/") {
566 return (top_ < y && top_ + texture_height_ >
y &&
567 left_ < x && left_ + texture_width_ >
x);