38 #include <OGRE/OgreMaterialManager.h>
39 #include <OGRE/OgreTextureManager.h>
40 #include <OGRE/OgreTexture.h>
41 #include <OGRE/OgreTechnique.h>
42 #include <OGRE/OgreHardwarePixelBuffer.h>
51 :
rviz::Display(), update_required_(false), first_time_(true), data_(0.0)
55 ros::message_traits::datatype<std_msgs::Float32>(),
56 "std_msgs::Float32 topic to subscribe to.",
57 this, SLOT( updateTopic() ));
59 "size of the plotter window",
60 this, SLOT(updateSize()));
62 "left of the plotter window",
63 this, SLOT(updateLeft()));
65 "top of the plotter window",
66 this, SLOT(updateTop()));
70 this, SLOT(updateFGColor()));
73 "alpha belnding value for foreground",
74 this, SLOT(updateFGAlpha()));
77 "alpha belnding value for foreground for indicator",
78 this, SLOT(updateFGAlpha2()));
82 this, SLOT(updateBGColor()));
85 "alpha belnding value for background",
86 this, SLOT(updateBGAlpha()));
90 this, SLOT(updateTextSize()));
91 show_caption_property_
94 this, SLOT(updateShowCaption()));
97 "max value of pie chart",
98 this, SLOT(updateMaxValue()));
101 "min value of pie chart",
102 this, SLOT(updateMinValue()));
103 auto_color_change_property_
106 "change the color automatically",
107 this, SLOT(updateAutoColorChange()));
111 "only used if auto color change is set to True.",
112 this, SLOT(updateMaxColor()));
117 "only used if auto color change is set to True.",
118 this, SLOT(updateMedColor()));
120 max_color_threshold_property_
122 "change the max color at threshold",
123 this, SLOT(updateMaxColorThreshold()));
125 med_color_threshold_property_
127 "change the med color at threshold ",
128 this, SLOT(updateMedColorThreshold()));
130 clockwise_rotate_property_
133 "change the rotate direction",
134 this, SLOT(updateClockwiseRotate()));
137 PieChartDisplay::~PieChartDisplay()
139 if (overlay_->isVisible()) {
142 delete update_topic_property_;
143 delete fg_color_property_;
144 delete bg_color_property_;
145 delete fg_alpha_property_;
146 delete fg_alpha2_property_;
147 delete bg_alpha_property_;
148 delete top_property_;
149 delete left_property_;
150 delete size_property_;
151 delete min_value_property_;
152 delete max_value_property_;
153 delete max_color_property_;
154 delete med_color_property_;
155 delete text_size_property_;
156 delete show_caption_property_;
159 void PieChartDisplay::onInitialize()
161 static int count = 0;
163 ss <<
"PieChartDisplayObject" <<
count++;
164 overlay_.reset(
new OverlayObject(ss.str()));
178 updateAutoColorChange();
181 updateMaxColorThreshold();
182 updateMedColorThreshold();
183 updateClockwiseRotate();
184 overlay_->updateTextureSize(texture_size_, texture_size_ + caption_offset_);
188 void PieChartDisplay::update(
float wall_dt,
float ros_dt)
190 if (update_required_) {
191 update_required_ =
false;
192 overlay_->updateTextureSize(texture_size_, texture_size_ + caption_offset_);
193 overlay_->setPosition(left_, top_);
194 overlay_->setDimensions(overlay_->getTextureWidth(),
195 overlay_->getTextureHeight());
200 void PieChartDisplay::processMessage(
const std_msgs::Float32::ConstPtr& msg)
202 boost::mutex::scoped_lock
lock(mutex_);
204 if (!overlay_->isVisible()) {
207 if (data_ !=
msg->data || first_time_) {
210 update_required_ =
true;
214 void PieChartDisplay::drawPlot(
double val)
218 if (auto_color_change_) {
220 = std::min(1.0, fabs((val - min_value_) / (max_value_ - min_value_)));
222 double r2 = (
r - 0.6) / 0.4;
223 fg_color.setRed((max_color_.red() - fg_color_.red()) * r2
225 fg_color.setGreen((max_color_.green() - fg_color_.green()) * r2
226 + fg_color_.green());
227 fg_color.setBlue((max_color_.blue() - fg_color_.blue()) * r2
230 if (max_color_threshold_ != 0) {
231 if (
r > max_color_threshold_) {
233 fg_color.setGreen(max_color_.green());
234 fg_color.setBlue(max_color_.blue());
237 if (med_color_threshold_ != 0) {
238 if (max_color_threshold_ >
r and
r > med_color_threshold_ ) {
240 fg_color.setGreen(med_color_.green());
241 fg_color.setBlue(med_color_.blue());
250 fg_color2.setAlpha(fg_alpha2_);
252 int width = overlay_->getTextureWidth();
253 int height = overlay_->getTextureHeight();
257 QPainter painter( &Hud );
258 painter.setRenderHint(QPainter::Antialiasing,
true);
260 const int outer_line_width = 5;
261 const int value_line_width = 10;
262 const int value_indicator_line_width = 2;
263 const int value_padding = 5;
265 const int value_aabb_offset
266 = outer_line_width + value_padding + value_line_width / 2;
268 painter.setPen(QPen(
fg_color, outer_line_width, Qt::SolidLine));
270 painter.drawEllipse(outer_line_width / 2, outer_line_width / 2,
271 width - outer_line_width ,
272 height - outer_line_width - caption_offset_);
274 painter.setPen(QPen(fg_color2, value_indicator_line_width, Qt::SolidLine));
275 painter.drawEllipse(value_aabb_offset, value_aabb_offset,
276 width - value_aabb_offset * 2,
277 height - value_aabb_offset * 2 - caption_offset_);
279 const double ratio = (val - min_value_) / (max_value_ - min_value_);
280 const double rotate_direction = clockwise_rotate_ ? -1.0 : 1.0;
281 const double ratio_angle = ratio * 360.0 * rotate_direction;
282 const double start_angle_offset = -90;
283 painter.setPen(QPen(
fg_color, value_line_width, Qt::SolidLine));
284 painter.drawArc(QRectF(value_aabb_offset, value_aabb_offset,
285 width - value_aabb_offset * 2,
286 height - value_aabb_offset * 2 - caption_offset_),
287 start_angle_offset * 16 ,
289 QFont
font = painter.font();
290 font.setPointSize(text_size_);
292 painter.setFont(
font);
293 painter.setPen(QPen(
fg_color, value_line_width, Qt::SolidLine));
294 std::ostringstream
s;
295 s << std::fixed << std::setprecision(2) << val;
296 painter.drawText(0, 0, width, height - caption_offset_,
297 Qt::AlignCenter | Qt::AlignVCenter,
302 painter.drawText(0, height - caption_offset_, width, caption_offset_,
303 Qt::AlignCenter | Qt::AlignVCenter,
314 void PieChartDisplay::subscribe()
316 std::string topic_name = update_topic_property_->getTopicStd();
317 if (topic_name.length() > 0 && topic_name !=
"/") {
319 sub_ = n.
subscribe(topic_name, 1, &PieChartDisplay::processMessage,
this);
324 void PieChartDisplay::unsubscribe()
329 void PieChartDisplay::onEnable()
336 void PieChartDisplay::onDisable()
342 void PieChartDisplay::updateSize()
344 boost::mutex::scoped_lock
lock(mutex_);
345 texture_size_ = size_property_->getInt();
346 update_required_ =
true;
349 void PieChartDisplay::updateTop()
351 top_ = top_property_->getInt();
352 update_required_ =
true;
355 void PieChartDisplay::updateLeft()
357 left_ = left_property_->getInt();
358 update_required_ =
true;
361 void PieChartDisplay::updateBGColor()
363 bg_color_ = bg_color_property_->getColor();
364 update_required_ =
true;
368 void PieChartDisplay::updateFGColor()
370 fg_color_ = fg_color_property_->getColor();
371 update_required_ =
true;
375 void PieChartDisplay::updateFGAlpha()
377 fg_alpha_ = fg_alpha_property_->getFloat() * 255.0;
378 update_required_ =
true;
382 void PieChartDisplay::updateFGAlpha2()
384 fg_alpha2_ = fg_alpha2_property_->getFloat() * 255.0;
385 update_required_ =
true;
390 void PieChartDisplay::updateBGAlpha()
392 bg_alpha_ = bg_alpha_property_->getFloat() * 255.0;
393 update_required_ =
true;
397 void PieChartDisplay::updateMinValue()
399 min_value_ = min_value_property_->getFloat();
400 update_required_ =
true;
404 void PieChartDisplay::updateMaxValue()
406 max_value_ = max_value_property_->getFloat();
407 update_required_ =
true;
411 void PieChartDisplay::updateTextSize()
413 boost::mutex::scoped_lock
lock(mutex_);
414 text_size_ = text_size_property_->getInt();
416 font.setPointSize(text_size_);
417 caption_offset_ = QFontMetrics(
font).height();
418 update_required_ =
true;
422 void PieChartDisplay::updateShowCaption()
424 show_caption_ = show_caption_property_->getBool();
425 update_required_ =
true;
430 void PieChartDisplay::updateTopic()
436 void PieChartDisplay::updateAutoColorChange()
438 auto_color_change_ = auto_color_change_property_->getBool();
439 if (auto_color_change_) {
440 max_color_property_->show();
441 med_color_property_->show();
442 max_color_threshold_property_->show();
443 med_color_threshold_property_->show();
446 max_color_property_->hide();
447 med_color_property_->hide();
448 max_color_threshold_property_->hide();
449 med_color_threshold_property_->hide();
451 update_required_ =
true;
455 void PieChartDisplay::updateMaxColor()
457 max_color_ = max_color_property_->getColor();
458 update_required_ =
true;
462 void PieChartDisplay::updateMedColor()
464 med_color_ = med_color_property_->getColor();
465 update_required_ =
true;
469 void PieChartDisplay::updateMaxColorThreshold()
471 max_color_threshold_ = max_color_threshold_property_->getFloat();
472 update_required_ =
true;
475 void PieChartDisplay::updateMedColorThreshold()
477 med_color_threshold_ = med_color_threshold_property_->getFloat();
478 update_required_ =
true;
481 void PieChartDisplay::updateClockwiseRotate()
483 clockwise_rotate_ = clockwise_rotate_property_->getBool();
484 update_required_ =
true;
488 bool PieChartDisplay::isInRegion(
int x,
int y)
490 return (top_ < y && top_ + texture_size_ >
y &&
491 left_ < x && left_ + texture_size_ >
x);
494 void PieChartDisplay::movePosition(
int x,
int y)
500 void PieChartDisplay::setPosition(
int x,
int y)
502 top_property_->setValue(
y);
503 left_property_->setValue(
x);