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.",
59 "size of the plotter window",
62 "left of the plotter window",
65 "top of the plotter window",
73 "alpha belnding value for foreground",
77 "alpha belnding value for foreground for indicator",
85 "alpha belnding value for background",
97 "max value of pie chart",
101 "min value of pie chart",
106 "change the color automatically",
111 "only used if auto color change is set to True.",
117 "change the rotate direction",
143 static int count = 0;
145 ss <<
"PieChartDisplayObject" << count++;
201 double r2 = (r - 0.6) / 0.4;
212 QColor fg_color2(fg_color);
222 QPainter painter( &Hud );
223 painter.setRenderHint(QPainter::Antialiasing,
true);
225 const int outer_line_width = 5;
226 const int value_line_width = 10;
227 const int value_indicator_line_width = 2;
228 const int value_padding = 5;
230 const int value_aabb_offset
231 = outer_line_width + value_padding + value_line_width / 2;
233 painter.setPen(QPen(fg_color, outer_line_width, Qt::SolidLine));
235 painter.drawEllipse(outer_line_width / 2, outer_line_width / 2,
236 width - outer_line_width ,
239 painter.setPen(QPen(fg_color2, value_indicator_line_width, Qt::SolidLine));
240 painter.drawEllipse(value_aabb_offset, value_aabb_offset,
241 width - value_aabb_offset * 2,
246 const double ratio_angle = ratio * 360.0 * rotate_direction;
247 const double start_angle_offset = -90;
248 painter.setPen(QPen(fg_color, value_line_width, Qt::SolidLine));
249 painter.drawArc(QRectF(value_aabb_offset, value_aabb_offset,
250 width - value_aabb_offset * 2,
252 start_angle_offset * 16 ,
254 QFont
font = painter.font();
257 painter.setFont(font);
258 painter.setPen(QPen(fg_color, value_line_width, Qt::SolidLine));
259 std::ostringstream
s;
260 s << std::fixed << std::setprecision(2) << val;
262 Qt::AlignCenter | Qt::AlignVCenter,
268 Qt::AlignCenter | Qt::AlignVCenter,
282 if (topic_name.length() > 0 && topic_name !=
"/") {
404 return (top_ < y && top_ + texture_size_ > y &&
405 left_ < x && left_ + texture_size_ > x);
virtual QColor getColor() const
rviz::BoolProperty * auto_color_change_property_
virtual bool setValue(const QVariant &new_value)
virtual void drawPlot(double val)
virtual QImage getQImage(unsigned int width, unsigned int height)
rviz::ColorProperty * fg_color_property_
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::FloatProperty * bg_alpha_property_
virtual int getInt() const
rviz::ColorProperty * bg_color_property_
virtual float getFloat() const
void updateClockwiseRotate()
OverlayObject::Ptr overlay_
virtual bool isInRegion(int x, int y)
virtual void onInitialize()
rviz::ColorProperty * max_color_property_
rviz::FloatProperty * fg_alpha_property_
virtual bool getBool() const
rviz::FloatProperty * min_value_property_
virtual void processMessage(const std_msgs::Float32::ConstPtr &msg)
virtual void setPosition(int x, int y)
virtual void movePosition(int x, int y)
rviz::FloatProperty * max_value_property_
rviz::BoolProperty * clockwise_rotate_property_
virtual ~PieChartDisplay()
rviz::RosTopicProperty * update_topic_property_
rviz::BoolProperty * show_caption_property_
rviz::FloatProperty * fg_alpha2_property_
virtual void update(float wall_dt, float ros_dt)
rviz::IntProperty * left_property_
rviz::IntProperty * top_property_
std::string getTopicStd() const
virtual void unsubscribe()
rviz::IntProperty * size_property_
rviz::IntProperty * text_size_property_
virtual QString getName() const
void updateAutoColorChange()