48 disable_controller_warnings_(false)
65 vector<pr2_mechanism_msgs::JointStatistics>::const_iterator it;
66 for (it = mechMsg->joint_statistics.begin(); it != mechMsg->joint_statistics.end(); ++it)
75 vector<pr2_mechanism_msgs::ControllerStatistics>::const_iterator c_it;
76 for (c_it = mechMsg->controller_statistics.begin(); c_it != mechMsg->controller_statistics.end(); ++c_it)
87 diagnostic_msgs::DiagnosticArray array;
90 map<string, boost::shared_ptr<JointStats> >::iterator it;
92 array.status.push_back(*(it->second->toDiagStat()));
95 map<string, boost::shared_ptr<ControllerStats> >::iterator c_it;
96 unsigned int num_controllers = 0;
97 vector<string> erase_controllers;
100 if (c_it->second->shouldDiscard())
101 erase_controllers.push_back(c_it->first);
103 array.status.push_back(*(c_it->second->toDiagStat()));
106 for (
unsigned int i=0; i<erase_controllers.size(); i++)
110 if (num_controllers == 0)
113 stat.name =
"Controller: No controllers loaded in controller manager";
114 array.status.push_back(stat);
122 int main(
int argc,
char **argv)
124 ros::init(argc, argv,
"pr2_mechanism_diagnostics");
131 while (ctrlJntPub.
ok())
140 ROS_FATAL(
"Controllers/Joint to Diagnostics node caught exception. Aborting. %s", e.what());
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void mechCallback(const pr2_mechanism_msgs::MechanismStatistics::ConstPtr &mechMsg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publishes diagnostics for controllers, joints from pr2_mechanism_msgs/MechanismStatistics message...
bool disable_controller_warnings_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Subscriber mech_st_sub_
int main(int argc, char **argv)
std::map< std::string, boost::shared_ptr< JointStats > > joint_stats
ROSCPP_DECL void spinOnce()
std::map< std::string, boost::shared_ptr< ControllerStats > > controller_stats
CtrlJntDiagnosticPublisher()