37 #include <boost/algorithm/string/predicate.hpp> 38 #include <boost/lexical_cast.hpp> 48 "Topic",
"/diagnostics_agg",
49 ros::message_traits::datatype<diagnostic_msgs::DiagnosticArray>(),
50 "diagnostic_msgs::DiagnosticArray topic to subscribe to.",
54 "the parent frame_id to visualize diagnostics",
57 "diagnostics namespace",
"/",
58 "diagnostics namespace to visualize diagnostics",
62 "radius of diagnostics circle",
106 const float round_trip = 10.0;
107 Ogre::Quaternion orientation;
108 Ogre::Vector3 position;
112 position, orientation ))
114 ROS_WARN(
"Error transforming from frame '%s' to frame '%s'",
120 Ogre::Vector3 orbit_position;
128 orbit_position.z = 0;
130 else if (
axis_ == 1) {
133 orbit_position.x = 0;
135 else if (
axis_ == 2) {
138 orbit_position.y = 0;
159 msg_->setVisible(
false);
170 (
const diagnostic_msgs::DiagnosticArray::ConstPtr& msg)
177 std::set<std::string> new_namespaces;
178 for (
size_t i = 0; i < msg->status.size(); i++) {
179 new_namespaces.insert(msg->status[i].name);
182 std::set<std::string> difference_namespaces;
184 new_namespaces.begin(), new_namespaces.end(),
185 std::inserter(difference_namespaces,
186 difference_namespaces.end()));
187 if (difference_namespaces.size() != 0) {
192 difference_namespaces.clear();
193 std::set_difference(new_namespaces.begin(), new_namespaces.end(),
195 std::inserter(difference_namespaces,
196 difference_namespaces.end()));
197 if (difference_namespaces.size() != 0) {
207 const float alpha = 0.8;
208 const Ogre::ColourValue
OK(0.3568627450980392, 0.7529411764705882, 0.8705882352941177, alpha);
209 const Ogre::ColourValue
WARN(0.9411764705882353, 0.6784313725490196, 0.3058823529411765, alpha);
210 const Ogre::ColourValue
ERROR(0.8509803921568627, 0.3254901960784314, 0.30980392156862746, 0.5);
211 const Ogre::ColourValue
UNKNOWN(0.2, 0.2, 0.2, 0.5);
212 Ogre::ColourValue color;
215 for (
size_t i = 0; i < msg->status.size(); i++) {
216 diagnostic_msgs::DiagnosticStatus status = msg->status[i];
218 if (status.level == diagnostic_msgs::DiagnosticStatus::OK) {
220 message = status.message;
222 else if (status.level == diagnostic_msgs::DiagnosticStatus::WARN) {
224 message = status.message;
226 else if (status.level == diagnostic_msgs::DiagnosticStatus::ERROR) {
228 message = status.message;
246 Ogre::ColourValue font_color(color);
259 for (
size_t i = 0; i < 128 + 1; i++) {
260 Ogre::Vector3 step_position;
261 const double theta = M_PI * 2.0 / 128 * i;
265 step_position.z = 0.0;
267 else if (
axis_ == 1) {
272 else if (
axis_ == 2) {
285 msg_->setVisible(
true);
292 msg_->setVisible(
false);
343 for (std::set<std::string>::iterator it =
namespaces_.begin();
virtual void updateFontSize()
void addPoint(const Ogre::Vector3 &point)
virtual void updateLine()
rviz::FloatProperty * line_width_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)
DisplayContext * context_
virtual ~DiagnosticsDisplay()
virtual void unsubscribe()
virtual void clearOptions()
bool line_update_required_
rviz::EnumProperty * axis_property_
virtual float getFloat() const
std::string diagnostics_namespace_
virtual void processMessage(const diagnostic_msgs::DiagnosticArray::ConstPtr &msg)
virtual void update(float wall_dt, float ros_dt)
void setCharacterHeight(Ogre::Real height)
rviz::FloatProperty * font_size_property_
void addOptionStd(const std::string &option)
virtual void updateAxis()
virtual void updateRosTopic()
virtual void fillNamespaceList()
Ogre::SceneNode * scene_node_
std::string getStdString()
rviz::BillboardLine * line_
virtual void setColor(float r, float g, float b, float a)
virtual void updateDiagnosticsNamespace()
virtual void onInitialize()
virtual void addOption(const QString &option, int value=0)
virtual void updateRadius()
std::set< std::string > namespaces_
void setCaption(const Ogre::String &caption)
virtual void updateLineWidth()
virtual FrameManager * getFrameManager() const =0
rviz::RosTopicProperty * ros_topic_property_
rviz::TfFrameProperty * frame_id_property_
void setNumLines(uint32_t num)
rviz::EditableEnumProperty * diagnostics_namespace_property_
void setMaxPointsPerLine(uint32_t max)
Ogre::SceneManager * scene_manager_
virtual Ogre::SceneManager * getSceneManager() const =0
virtual void queueRender()=0
void setColor(const Ogre::ColourValue &color)
static const QString FIXED_FRAME_STRING
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void setFrameManager(FrameManager *frame_manager)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
rviz::FloatProperty * radius_property_
std::string getTopicStd() const
virtual int getOptionInt()
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void setLineWidth(float width)
Ogre::SceneNode * orbit_node_