diagnostics_publisher.cpp
Go to the documentation of this file.
2 
4 {
5  nh.param("expected_frequency", expected_frequency, 10.0);
6  nh.param("max_latency", max_latency, 1.0);
7  nh.param("connection_lost_timeout", connection_lost_timeout, 10.0);
8 
9  ROS_INFO("Expected frequency for diagnostics : %.2f Hz", expected_frequency);
10  ROS_INFO("Max latency acceptable for diagnostics : %.3f s", max_latency);
11  ROS_INFO("Connection lost timeout : %.3f s", connection_lost_timeout);
12 
13  diagnosticsUpdater.add("status", this,
16  "imu topic", diagnosticsUpdater,
22 }
23 
24 void DiagnosticsPublisher::setHardwareID(const std::string& hwId)
25 {
27 }
28 
30 {
31  stdImuTopicDiagnostic->tick(stamp);
32 }
33 
35  const boost::optional<ixblue_stdbin_decoder::Data::INSSystemStatus>& systemStatus,
36  const boost::optional<ixblue_stdbin_decoder::Data::INSAlgorithmStatus>&
37  algorithmStatus)
38 {
40  lastSystemStatus = systemStatus;
41  lastAlgorithmStatus = algorithmStatus;
42 }
43 
45 {
47 }
48 
51 {
52  if(!lastAlgorithmStatus.is_initialized() || !lastSystemStatus.is_initialized())
53  {
54  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No data received yet");
55  }
56  else if((ros::SteadyTime::now() - lastMessageReceivedStamp).toSec() >
58  {
59  std::stringstream ss;
60  ss << "No more data for more than " << connection_lost_timeout << " s";
61  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, ss.str());
62  }
63  else
64  {
65  const std::bitset<32> algoStatus1{lastAlgorithmStatus->status1};
66  const std::bitset<32> algoStatus2{lastAlgorithmStatus->status2};
67  const std::bitset<32> algoStatus3{lastAlgorithmStatus->status3};
68  const std::bitset<32> algoStatus4{lastAlgorithmStatus->status4};
69 
70  const std::bitset<32> systemStatus1{lastSystemStatus->status1};
71  const std::bitset<32> systemStatus2{lastSystemStatus->status2};
72  const std::bitset<32> systemStatus3{lastSystemStatus->status3};
73 
74  status.add("algorithm_status_1", algoStatus1.to_string());
75  status.add("algorithm_status_2", algoStatus2.to_string());
76  status.add("algorithm_status_3", algoStatus3.to_string());
77  status.add("algorithm_status_4", algoStatus4.to_string());
78 
79  status.add("system_status_1", systemStatus1.to_string());
80  status.add("system_status_2", systemStatus2.to_string());
81  status.add("system_status_3", systemStatus3.to_string());
82 
83  if(systemStatus1.test(
84  ixblue_stdbin_decoder::Data::INSSystemStatus::Status1::SERIAL_IN_R_ERR))
85  {
86  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
87  "Serial input error");
88  }
89  else if(systemStatus1.test(
90  ixblue_stdbin_decoder::Data::INSSystemStatus::Status1::INPUT_A_ERR))
91  {
92  // GNNS Input error on Atlans, Input A error on other systems
93  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
94  "GNSS or Input A error");
95  }
96  // TODO other system status checks
98  WAIT_FOR_POSITION))
99  {
100  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
101  "System is waiting for position");
102  }
103  else if(algoStatus1.test(
104  ixblue_stdbin_decoder::Data::INSAlgorithmStatus::Status1::ALIGNMENT))
105  {
106  status.summary(diagnostic_msgs::DiagnosticStatus::WARN,
107  "System in alignment, do not move");
108  }
109  else if(algoStatus1.test(ixblue_stdbin_decoder::Data::INSAlgorithmStatus::
110  Status1::FINE_ALIGNMENT))
111  {
112  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Fine alignment");
113  }
114  else if(algoStatus1.test(
115  ixblue_stdbin_decoder::Data::INSAlgorithmStatus::Status1::NAVIGATION))
116  {
117  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "System in navigation");
118  }
119  else
120  {
121  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "");
122  }
123  }
124 }
DiagnosticsPublisher::updateStatus
void updateStatus(const boost::optional< ixblue_stdbin_decoder::Data::INSSystemStatus > &systemStatus, const boost::optional< ixblue_stdbin_decoder::Data::INSAlgorithmStatus > &algorithmStatus)
Definition: diagnostics_publisher.cpp:34
DiagnosticsPublisher::DiagnosticsPublisher
DiagnosticsPublisher(ros::NodeHandle &nh)
Definition: diagnostics_publisher.cpp:3
DiagnosticsPublisher::frequency_tolerance
const double frequency_tolerance
Definition: diagnostics_publisher.h:32
DiagnosticsPublisher::diagnosticsUpdater
diagnostic_updater::Updater diagnosticsUpdater
Definition: diagnostics_publisher.h:37
DiagnosticsPublisher::lastMessageReceivedStamp
ros::SteadyTime lastMessageReceivedStamp
Definition: diagnostics_publisher.h:39
diagnostic_updater::TimeStampStatusParam
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
DiagnosticsPublisher::setHardwareID
void setHardwareID(const std::string &hwId)
Definition: diagnostics_publisher.cpp:24
DiagnosticsPublisher::diagnosticsTimer
ros::Timer diagnosticsTimer
Definition: diagnostics_publisher.h:36
DiagnosticsPublisher::expected_frequency
double expected_frequency
Definition: diagnostics_publisher.h:31
DiagnosticsPublisher::connection_lost_timeout
double connection_lost_timeout
Definition: diagnostics_publisher.h:34
DiagnosticsPublisher::lastAlgorithmStatus
boost::optional< ixblue_stdbin_decoder::Data::INSAlgorithmStatus > lastAlgorithmStatus
Definition: diagnostics_publisher.h:41
ros::SteadyTime::now
static SteadyTime now()
DiagnosticsPublisher::stdImuTick
void stdImuTick(const ros::Time &stamp)
Definition: diagnostics_publisher.cpp:29
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
ros::TimerEvent
DiagnosticsPublisher::stdImuTopicDiagnostic
std::unique_ptr< diagnostic_updater::TopicDiagnostic > stdImuTopicDiagnostic
Definition: diagnostics_publisher.h:38
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
diagnostic_updater::TopicDiagnostic
diagnostic_updater::Updater::update
void update()
DiagnosticsPublisher::lastSystemStatus
boost::optional< ixblue_stdbin_decoder::Data::INSSystemStatus > lastSystemStatus
Definition: diagnostics_publisher.h:40
ixblue_stdbin_decoder::Data::INSAlgorithmStatus
ros::Time
DiagnosticsPublisher::produceStatusDiagnostics
void produceStatusDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: diagnostics_publisher.cpp:49
diagnostics_publisher.h
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
DiagnosticsPublisher::max_latency
double max_latency
Definition: diagnostics_publisher.h:33
diagnostic_updater::DiagnosticStatusWrapper
ixblue_stdbin_decoder::Data::INSSystemStatus::Status2
Status2
DiagnosticsPublisher::diagTimerCallback
void diagTimerCallback(const ros::TimerEvent &)
Definition: diagnostics_publisher.cpp:44
ROS_INFO
#define ROS_INFO(...)
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::NodeHandle
diagnostic_updater::FrequencyStatusParam


ixblue_ins_driver
Author(s): Adrien BARRAL , Laure LE BRETON
autogenerated on Wed Mar 2 2022 00:24:28