Skip to content

Commit 2a44a17

Browse files
author
Aaron Roller
authored
Merge pull request #143 from AutoModality/AM-695/error-methods
feat: error reporting with message AM-695/error-methods
2 parents 2873032 + a9a50ae commit 2a44a17

4 files changed

Lines changed: 83 additions & 39 deletions

File tree

include/super_lib/am_life_cycle.h

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,7 @@ class AMLifeCycle
6161
void destroy();
6262
void cleanup();
6363
void sendNodeUpdate();
64+
void error(std::string message, std::string error_code, bool forced = false);
6465

6566
protected:
6667
std::string node_name_;
@@ -140,8 +141,15 @@ class AMLifeCycle
140141
* @param error_code provides a reference for the developer to correlate log output to the originating error.
141142
* @param forced terminal error that will not allow any tolerance
142143
*/
144+
[[deprecated("use errorTolerant or errorTerminal with message")]]
143145
void error(std::string error_code="NNLW",bool forced = false);
144146

147+
/** Reports an error for immediate shutdown without any tolerance. */
148+
void errorTerminal(std::string message, std::string error_code);
149+
150+
/** Reports an error, but may not shutdown the system if tolerance is allowed.*/
151+
void errorTolerant(std::string message, std::string error_code);
152+
145153
/**
146154
* @brief Function to be defined by the user.
147155
* Called at any time and transitions to UNCONFIGURED or FINALIZED.
@@ -185,6 +193,10 @@ class AMLifeCycle
185193
* */
186194
AMStatReset& configureHzStats(AMStatReset& stats);
187195

196+
/** Called periodically by a timer defaulting to 1 second.
197+
* Useful for checking health regularly, but not during
198+
* callbacks which can affect performance and be too granular
199+
*/
188200
virtual void heartbeatCB(const ros::TimerEvent& event);
189201

190202
void lifecycleCB(const brain_box_msgs::LifeCycleCommand::ConstPtr msg);

rostest/error_forced/error_forced_rostest.cpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -9,14 +9,20 @@ class LifeCycleErrorTest : public RostestBase, public am::AMLifeCycle
99
LifeCycleErrorTest() :
1010
RostestBase()
1111
{}
12+
13+
14+
void onConfigure()
15+
{
16+
//do nothing...stay in configure
17+
}
1218
};
1319

1420
TEST_F(LifeCycleErrorTest, testStatus_Error)
1521
{
16-
waitUntil(LifeCycleState::UNCONFIGURED);
22+
waitUntil(LifeCycleState::CONFIGURING,"3K3K");
1723
ASSERT_EQ(LifeCycleStatus::OK,getStatus());
18-
error("NNAQ",true);
19-
waitUntil(LifeCycleState::ERROR_PROCESSING);
24+
errorTerminal("forcing error during configuration", "NNAQ");
25+
waitUntil(LifeCycleState::ERROR_PROCESSING,"NAKW");
2026
waitUntil(LifeCycleStatus::ERROR,"IUIU");
2127
}
2228

src/am_super/am_super.cpp

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -304,37 +304,37 @@ class AMSuper : AMLifeCycle
304304
SuperNodeMediator::SuperNodeInfo& nr = it->second;
305305
if (!nr.online)
306306
{
307-
ROS_INFO_STREAM("manifested node '" << node_name << "' came online");
307+
ROS_INFO_STREAM("manifested node '" << node_name << "' came online [PGPG]");
308308
nr.online = true;
309309
nodes_changed = true;
310310
}
311311
if (nr.state != state)
312312
{
313-
ROS_INFO_STREAM(node_name << " changed state to = " << life_cycle_mediator_.stateToString(state));
313+
ROS_INFO_STREAM(node_name << " changed state to = " << life_cycle_mediator_.stateToString(state) << " [38S8]");
314314
nr.state = state;
315315
nodes_changed = true;
316316
}
317317
if (nr.status != status)
318318
{
319-
ROS_INFO_STREAM(node_name << " changed status to = " << life_cycle_mediator_.statusToString(status));
319+
ROS_INFO_STREAM(node_name << " changed status to = " << life_cycle_mediator_.statusToString(status) << " [09SI]");
320320
nr.status = status;
321321
nodes_changed = true;
322322
if(nr.manifested && nr.status == LifeCycleStatus::ERROR)
323323
{
324324
supervisor_.status_error = true;
325-
ROS_ERROR_STREAM("Manifested node " << nr.name << " changed status to ERROR. Shutting down nodes..");
325+
ROS_ERROR_STREAM("Manifested node " << nr.name << " changed status to ERROR. Shutting down nodes... [JHRE]");
326326
}
327327
}
328328
if (nr.pid != pid)
329329
{
330330
//process id = 0 observed to be a node coming online. -1 appears to be offline
331331
if(pid == 0)
332332
{
333-
ROS_INFO_STREAM(node_name << " process is alive");
333+
ROS_INFO_STREAM(node_name << " process is alive [UIRE]");
334334
}
335335
else
336336
{
337-
ROS_WARN_STREAM(node_name << " changed process id from: " << nr.pid << " to: " << pid);
337+
ROS_WARN_STREAM(node_name << " changed process id from: " << nr.pid << " to: " << pid << " [WNEW]");
338338
}
339339
nr.pid = pid;
340340
nodes_changed = true;
@@ -623,12 +623,13 @@ class AMSuper : AMLifeCycle
623623
ROS_WARN_STREAM("actual" << actual_platform.maker);
624624
if(!node_mediator_.isCorrectPlatform(required_platform,actual_platform))
625625
{
626-
ROS_ERROR_STREAM("Platform required: `"
627-
<< node_mediator_.platformVariantToConfig(required_platform)
628-
<< "` actual: `"
629-
<< node_mediator_.platformVariantToConfig(actual_platform)
630-
<< "` [PO90]");
631-
error("NSK2",true); //force failure since this is not recoverable
626+
std::stringstream message;
627+
message << "Platform required: `"
628+
<< node_mediator_.platformVariantToConfig(required_platform)
629+
<< "` actual: `"
630+
<< node_mediator_.platformVariantToConfig(actual_platform)
631+
;
632+
errorTerminal(message.str(),"NSK2"); //force failure since this is not recoverable
632633
}
633634
else
634635
{
@@ -647,8 +648,7 @@ class AMSuper : AMLifeCycle
647648
param("platform/actual",actual_platform_param,not_provided);
648649
if(actual_platform_param == not_provided)
649650
{
650-
ROS_ERROR_STREAM("param `/am_super/platform/actual` must provide the platform running");
651-
error("NNS9",true);
651+
errorTerminal("param `/am_super/platform/actual` must provide the platform running","NNS9");
652652
return;
653653
}
654654
node_mediator_.platformConfigToVariant(actual_platform_param,actual_platform);

src/super_lib/am_life_cycle.cpp

Lines changed: 48 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -103,7 +103,7 @@ void AMLifeCycle::lifecycleCB(const brain_box_msgs::LifeCycleCommand::ConstPtr m
103103
configure();
104104
break;
105105
case LifeCycleCommand::CREATE:
106-
ROS_WARN_STREAM("illegal command " << life_cycle_mediator_.commandToString(LifeCycleCommand::CREATE));
106+
ROS_WARN_STREAM("illegal command " << life_cycle_mediator_.commandToString(LifeCycleCommand::CREATE) << " [7YT8]");
107107
break;
108108
case LifeCycleCommand::DEACTIVATE:
109109
transition("deactivate", LifeCycleState::ACTIVE, LifeCycleState::DEACTIVATING, LifeCycleState::INACTIVE,
@@ -124,17 +124,17 @@ void AMLifeCycle::transition(std::string transition_name, LifeCycleState initial
124124
{
125125
if (life_cycle_info_.state == initial_state)
126126
{
127-
ROS_INFO_STREAM(transition_name << ", current state: " << life_cycle_mediator_.stateToString(life_cycle_info_.state));
127+
ROS_INFO_STREAM(transition_name << ", current state: " << life_cycle_mediator_.stateToString(life_cycle_info_.state) << " [ASWU]");
128128
setState(transition_state);
129129
on_function();
130130
}
131131
else if (life_cycle_info_.state == transition_state || life_cycle_info_.state == final_state)
132132
{
133-
ROS_DEBUG_STREAM("ignoring redundant " << transition_name);
133+
ROS_DEBUG_STREAM("ignoring redundant " << transition_name << " [0393]");
134134
}
135135
else
136136
{
137-
ROS_WARN_STREAM("received illegal " << transition_name << " in state " << life_cycle_mediator_.stateToString(life_cycle_info_.state));
137+
ROS_WARN_STREAM("received illegal " << transition_name << " in state " << life_cycle_mediator_.stateToString(life_cycle_info_.state) << " [JGV5]");
138138
}
139139
}
140140

@@ -237,12 +237,12 @@ void AMLifeCycle::destroy()
237237
{
238238
if (life_cycle_mediator_.illegalDestroy(life_cycle_info_))
239239
{
240-
ROS_INFO_STREAM("received illegal activate in state " << life_cycle_mediator_.stateToString(life_cycle_info_.state));
240+
ROS_INFO_STREAM("received illegal activate in state " << life_cycle_mediator_.stateToString(life_cycle_info_.state) << " [45RT]");
241241
}
242242
/* This condition is hit only if state equals FINALIZED. Checking SHUTTING_DOWN is redundant */
243243
else
244244
{
245-
ROS_INFO_STREAM("current state: " << life_cycle_mediator_.stateToString(life_cycle_info_.state));
245+
ROS_INFO_STREAM("current state: " << life_cycle_mediator_.stateToString(life_cycle_info_.state) << " [RE45]");
246246
onDestroy();
247247
}
248248
}
@@ -273,27 +273,50 @@ bool AMLifeCycle::withinConfigureTolerance()
273273
}
274274
return tolerated;
275275
}
276+
276277
void AMLifeCycle::error(std::string error_code, bool forced)
277278
{
278-
std::string error_code_message=" [" + error_code + "] ";
279-
if (!forced && life_cycle_mediator_.redundantError(life_cycle_info_))
280-
{
281-
ROS_WARN_STREAM("Error called again, but previously reported." << error_code_message);
282-
}
283-
else if(!forced && withinConfigureTolerance())
279+
error("[GSHY]",error_code,forced);
280+
}
281+
282+
void AMLifeCycle::error(std::string message, std::string error_code, bool forced)
283+
{
284+
std::string error_code_message = "Error[" + error_code + "] ";
285+
if(withinConfigureTolerance() && !forced)
284286
{
285-
ROS_WARN_STREAM_THROTTLE(throttle_info_.warn_throttle_s,"Ignoring error" << error_code_message << "during configure tolerance of " << configure_tolerance_s << " seconds [GFRT]");
287+
ROS_WARN_STREAM_THROTTLE(throttle_info_.warn_throttle_s,"Ignoring tolerant error for (" << configure_tolerance_s << "s) `" << message << "` " << error_code_message << "[GFRT]");
286288
}
287289
else
288290
{
289-
std::string forced_prefix = forced?"Forced ":"";
290-
ROS_ERROR_STREAM(forced_prefix << "Error" << error_code_message << "called while in: " << life_cycle_mediator_.stateToString(life_cycle_info_.state) << " [R45Y]" );
291-
setState(LifeCycleState::ERROR_PROCESSING);
292-
setStatus(LifeCycleStatus::ERROR);
293-
onError();
291+
std::string forced_prefix = forced?"Terminal ":"";
292+
std::string repeat_prefix = "";
293+
//only change the state if
294+
if(!life_cycle_mediator_.redundantError(life_cycle_info_))
295+
{
296+
setState(LifeCycleState::ERROR_PROCESSING);
297+
setStatus(LifeCycleStatus::ERROR);
298+
onError();
299+
}
300+
else
301+
{
302+
repeat_prefix = "Repeated ";
303+
}
304+
std::string error_explanation=forced_prefix + repeat_prefix + error_code_message;
305+
ROS_ERROR_STREAM(message << " -> " << error_explanation << " [R45Y]" );
294306
}
295307
}
296308

309+
310+
void AMLifeCycle::errorTerminal(std::string message, std::string error_code)
311+
{
312+
error(message,error_code,true);
313+
}
314+
315+
void AMLifeCycle::errorTolerant(std::string message, std::string error_code)
316+
{
317+
error(message,error_code,false);
318+
}
319+
297320
void AMLifeCycle::onError()
298321
{
299322
logState();
@@ -350,11 +373,15 @@ void AMLifeCycle::addStatistics(diagnostic_updater::DiagnosticStatusWrapper& dsw
350373
LifeCycleStatus status = stats_list_.process(throttle_info_.warn_throttle_s, throttle_info_.error_throttle_s);
351374
if(life_cycle_mediator_.statusError(status))
352375
{
353-
error("PQAE");
376+
errorTolerant("Stats reporting error","PQAE");
354377
}
355378
else
356379
{
357-
setStatus(status);
380+
//only report status if not already errored
381+
if(!life_cycle_mediator_.redundantError(life_cycle_info_))
382+
{
383+
setStatus(status);
384+
}
358385

359386
//configuring is a special case where tolerance for errors is allowed
360387
if(getState() == LifeCycleState::CONFIGURING)
@@ -478,9 +505,8 @@ bool AMLifeCycle::setStatus(const LifeCycleStatus status)
478505
//if we are in error and want to leave it
479506
if(life_cycle_info_.status == LifeCycleStatus::ERROR && status != LifeCycleStatus::ERROR)
480507
{
481-
ROS_WARN_STREAM_THROTTLE(getThrottle(), "requested to change status from ERROR to " << life_cycle_mediator_.statusToString(status));
508+
ROS_WARN_STREAM_THROTTLE(getThrottle(), "requested to change status from ERROR to " << life_cycle_mediator_.statusToString(status) << " [DFRE]");
482509
}
483-
484510
else if (life_cycle_mediator_.setStatus(status, life_cycle_info_))
485511
{
486512
sendNodeUpdate();

0 commit comments

Comments
 (0)