88#include < diagnostic_msgs/DiagnosticStatus.h>
99
1010#include < super_lib/am_stat_list.h>
11+ #include < super_lib/am_stat_reset.h>
1112#include < super_lib/am_life_cycle_types.h>
1213#include < super_lib/am_life_cycle_mediator.h>
1314
@@ -30,6 +31,18 @@ class AMLifeCycle
3031{
3132 public:
3233 static constexpr std::string_view BROADCAST_NODE_NAME = " " ;
34+
35+ /* *Specific parts of the lifecycle where nodes have responsibilities.*/
36+ LifeCycleState getState () const ;
37+
38+ /* *Simple indication of health */
39+ LifeCycleStatus getStatus () const ;
40+
41+ /* * @brief string represenation of LifeCycleState*/
42+ const std::string_view& getStateName ();
43+
44+ /* * @brief string representation of LifeCycleStatus*/
45+ const std::string_view& getStatusName ();
3346
3447 private:
3548 /* Variables to help seperate business logic from AMLifeCycle ROS */
@@ -60,6 +73,7 @@ class AMLifeCycle
6073 void destroy ();
6174 void cleanup ();
6275 void sendNodeUpdate ();
76+ void error (std::string message, std::string error_code, bool forced = false );
6377
6478 protected:
6579 std::string node_name_;
@@ -139,8 +153,15 @@ class AMLifeCycle
139153 * @param error_code provides a reference for the developer to correlate log output to the originating error.
140154 * @param forced terminal error that will not allow any tolerance
141155 */
156+ [[deprecated(" use errorTolerant or errorTerminal with message" )]]
142157 void error (std::string error_code=" NNLW" ,bool forced = false );
143158
159+ /* * Reports an error for immediate shutdown without any tolerance. */
160+ void errorTerminal (std::string message, std::string error_code);
161+
162+ /* * Reports an error, but may not shutdown the system if tolerance is allowed.*/
163+ void errorTolerant (std::string message, std::string error_code);
164+
144165 /* *
145166 * @brief Function to be defined by the user.
146167 * Called at any time and transitions to UNCONFIGURED or FINALIZED.
@@ -155,19 +176,43 @@ class AMLifeCycle
155176 virtual void onShutdown ();
156177 void doShutdown (bool success);
157178
179+ /* *Initialize statistics by adding to the list*/
158180 virtual void addStatistics (diagnostic_updater::DiagnosticStatusWrapper& dsw);
181+
182+ /* * Initialize the stats that reset once per second providing the equivalent of rostopic hz to ensure frequency of
183+ * publishing. Allows for overriding values in roslaunch configurations.
184+ * Provide the target, which is the approximate value you expect to receive. The warnings and errors will be
185+ * provided with tolerance on both sides of the target.
186+ *
187+ * Configurations key use the stats short name.
188+ *
189+ * setting a target will also set a min/max 5% warn and 10% error
190+ * no target allows for just min or just max or both.
191+ *
192+ * stats_target_sets_min_max:
193+ * hz:
194+ * target: 100 # sets min_error=90,min_warn=95,max_warn=105,max_error=110
195+ *
196+ * stats_only_min:
197+ * hz:
198+ * error:
199+ * min: 50
200+ * warn:
201+ * min: 60
202+ *
203+ *
204+ * @param stats to be configured
205+ * */
206+ AMStatReset& configureHzStats (AMStatReset& stats);
207+
208+ /* * Called periodically by a timer defaulting to 1 second.
209+ * Useful for checking health regularly, but not during
210+ * callbacks which can affect performance and be too granular
211+ */
159212 virtual void heartbeatCB (const ros::TimerEvent& event);
160213
161214 void lifecycleCB (const brain_box_msgs::LifeCycleCommand::ConstPtr msg);
162215
163- /* *Specific parts of the lifecycle where nodes have responsibilities.*/
164- LifeCycleState getState () const ;
165- /* *Simple indication of health */
166- LifeCycleStatus getStatus () const ;
167- /* * @brief string represenation of LifeCycleState*/
168- const std::string_view& getStateName ();
169- /* * @brief string representation of LifeCycleStatus*/
170- const std::string_view& getStatusName ();
171216
172217 double getThrottleS () const ;
173218 void setThrottleS (const double throttleS);
0 commit comments