Analyzes diagnostic messages about Nao's joints from nao_diagnostic/nao_diagnostic_updater. More...
#include <naoqi_joints_analyzer.h>
Classes | |
struct | JointData |
Public Member Functions | |
bool | analyze (const boost::shared_ptr< StatusItem > item) |
std::string | getName () const |
std::string | getPath () const |
bool | init (const std::string base_name, const ros::NodeHandle &n) |
bool | match (const std::string name) |
NaoqiJointsAnalyzer () | |
std::vector< boost::shared_ptr < diagnostic_msgs::DiagnosticStatus > > | report () |
~NaoqiJointsAnalyzer () | |
Private Types | |
typedef std::map< std::string, JointData > | JointsMapType |
Private Member Functions | |
template<typename T > | |
void | addValue (boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > joint_stat, const std::string &key, const T &value) const |
Static Private Member Functions | |
static bool | compareByTemperature (const NaoqiJointsAnalyzer::JointData &a, const NaoqiJointsAnalyzer::JointData &b) |
Private Attributes | |
JointsMapType | m_joints |
boost::shared_ptr< StatusItem > | m_jointsMasterItem |
ros::Time | m_lastSeen |
std::string | m_niceName |
std::string | m_path |
boost::shared_ptr< StatusItem > | m_statusItems |
Analyzes diagnostic messages about Nao's joints from nao_diagnostic/nao_diagnostic_updater.
Definition at line 51 of file naoqi_joints_analyzer.h.
typedef std::map<std::string, JointData> diagnostic_aggregator::NaoqiJointsAnalyzer::JointsMapType [private] |
Definition at line 77 of file naoqi_joints_analyzer.h.
void diagnostic_aggregator::NaoqiJointsAnalyzer::addValue | ( | boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > | joint_stat, |
const std::string & | key, | ||
const T & | value | ||
) | const [private] |
bool diagnostic_aggregator::NaoqiJointsAnalyzer::analyze | ( | const boost::shared_ptr< StatusItem > | item | ) | [virtual] |
Implements diagnostic_aggregator::Analyzer.
static bool diagnostic_aggregator::NaoqiJointsAnalyzer::compareByTemperature | ( | const NaoqiJointsAnalyzer::JointData & | a, |
const NaoqiJointsAnalyzer::JointData & | b | ||
) | [static, private] |
std::string diagnostic_aggregator::NaoqiJointsAnalyzer::getName | ( | ) | const [inline, virtual] |
Implements diagnostic_aggregator::Analyzer.
Definition at line 62 of file naoqi_joints_analyzer.h.
std::string diagnostic_aggregator::NaoqiJointsAnalyzer::getPath | ( | ) | const [inline, virtual] |
Implements diagnostic_aggregator::Analyzer.
Definition at line 59 of file naoqi_joints_analyzer.h.
bool diagnostic_aggregator::NaoqiJointsAnalyzer::init | ( | const std::string | base_name, |
const ros::NodeHandle & | n | ||
) | [virtual] |
Implements diagnostic_aggregator::Analyzer.
bool diagnostic_aggregator::NaoqiJointsAnalyzer::match | ( | const std::string | name | ) | [virtual] |
Implements diagnostic_aggregator::Analyzer.
std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > diagnostic_aggregator::NaoqiJointsAnalyzer::report | ( | ) | [virtual] |
Implements diagnostic_aggregator::Analyzer.
Definition at line 78 of file naoqi_joints_analyzer.h.
boost::shared_ptr<StatusItem> diagnostic_aggregator::NaoqiJointsAnalyzer::m_jointsMasterItem [private] |
Definition at line 68 of file naoqi_joints_analyzer.h.
Definition at line 70 of file naoqi_joints_analyzer.h.
std::string diagnostic_aggregator::NaoqiJointsAnalyzer::m_niceName [private] |
Definition at line 67 of file naoqi_joints_analyzer.h.
std::string diagnostic_aggregator::NaoqiJointsAnalyzer::m_path [private] |
Definition at line 67 of file naoqi_joints_analyzer.h.
boost::shared_ptr<StatusItem> diagnostic_aggregator::NaoqiJointsAnalyzer::m_statusItems [private] |
Definition at line 69 of file naoqi_joints_analyzer.h.