Skip to content

Commit e321900

Browse files
author
Aaron Roller
authored
Merge pull request #145 from AutoModality/AM-695/error-on-init
fix: error respected during init AM-695/error-on-init
2 parents 518fabd + c1a057f commit e321900

11 files changed

+136
-14
lines changed

CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -221,6 +221,8 @@ if (CATKIN_ENABLE_TESTING)
221221
error_forced
222222
error_status
223223
error_status_without_stats
224+
error_terminal_before_config
225+
error_tolerant_before_config
224226
hz_config
225227
manual_to_disarming
226228
param

include/super_lib/am_life_cycle.h

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,18 @@ class AMLifeCycle
3131
{
3232
public:
3333
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();
3446

3547
private:
3648
/* Variables to help seperate business logic from AMLifeCycle ROS */
@@ -201,14 +213,6 @@ class AMLifeCycle
201213

202214
void lifecycleCB(const brain_box_msgs::LifeCycleCommand::ConstPtr msg);
203215

204-
/**Specific parts of the lifecycle where nodes have responsibilities.*/
205-
LifeCycleState getState() const;
206-
/**Simple indication of health */
207-
LifeCycleStatus getStatus() const;
208-
/** @brief string represenation of LifeCycleState*/
209-
const std::string_view& getStateName();
210-
/** @brief string representation of LifeCycleStatus*/
211-
const std::string_view& getStatusName();
212216

213217
double getThrottleS() const;
214218
void setThrottleS(const double throttleS);

include/super_lib/am_life_cycle_mediator.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -193,8 +193,12 @@ class AMLifeCycleMediator
193193

194194
bool redundantShutdown(const AMLifeCycleMediator::LifeCycleInfo& info);
195195

196+
/** @brief return true if already in error state */
196197
bool redundantError(const AMLifeCycleMediator::LifeCycleInfo& info);
197198

199+
/** @brief return true if in UNCONFIGURED or CONFIGURING */
200+
bool unconfigured(const AMLifeCycleMediator::LifeCycleInfo& info);
201+
198202
bool illegalDestroy(const AMLifeCycleMediator::LifeCycleInfo& info);
199203

200204
private:
Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
#include <am_rostest_lib/am_rostest.h>
2+
3+
/** Shows an error that happens upon construction will be reported as an ERROR during configuration.
4+
*/
5+
class LifeCycleErrorTest : public RostestBase, public am::AMLifeCycle
6+
{
7+
protected:
8+
9+
LifeCycleErrorTest() :
10+
RostestBase()
11+
{
12+
errorTerminal("forcing error during construction", "HW8S");
13+
}
14+
15+
16+
void onConfigure()
17+
{
18+
//do nothing...stay in configure
19+
}
20+
};
21+
22+
TEST_F(LifeCycleErrorTest, testStatus_Error)
23+
{
24+
waitUntil(LifeCycleState::FINALIZED,"NAKW");
25+
waitUntil(LifeCycleStatus::ERROR,"IUIU");
26+
waitUntil(LifeCycleStatus::ERROR,"NQNE");
27+
}
28+
29+
int main(int argc, char** argv)
30+
{
31+
::testing::InitGoogleTest(&argc, argv);
32+
ros::init(argc, argv, ros::this_node::getName());
33+
34+
return RUN_ALL_TESTS();
35+
}
Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
<launch>
2+
<!-- include test file and pass in this test node name -->
3+
<include file="$(find am_super)/rostest/am_super_rostest.test">
4+
<arg name="test_name" value="error_terminal_before_config"/>
5+
</include>
6+
</launch>
Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
#include <am_rostest_lib/am_rostest.h>
2+
3+
/** Shows an error that happens upon construction will be reported as an ERROR during configuration.
4+
*/
5+
class LifeCycleErrorTest : public RostestBase, public am::AMLifeCycle
6+
{
7+
protected:
8+
9+
LifeCycleErrorTest() :
10+
RostestBase()
11+
{
12+
errorTolerant("tolerant error during construction", "HW8S");
13+
}
14+
};
15+
16+
TEST_F(LifeCycleErrorTest, testStatus_Error)
17+
{
18+
waitUntil(LifeCycleState::INACTIVE,"NAKW");
19+
waitUntil(LifeCycleStatus::OK,"NQNE");
20+
}
21+
22+
int main(int argc, char** argv)
23+
{
24+
::testing::InitGoogleTest(&argc, argv);
25+
ros::init(argc, argv, ros::this_node::getName());
26+
27+
return RUN_ALL_TESTS();
28+
}
Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
<launch>
2+
<!-- include test file and pass in this test node name -->
3+
<include file="$(find am_super)/rostest/am_super_rostest.test">
4+
<arg name="test_name" value="error_tolerant_before_config"/>
5+
</include>
6+
</launch>

rostest/platform_required_fail/platform_required_fail_rostest.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ TEST_F(PlatformRequiredFailTest, requiredPlatformDifferentThanActual)
1919
ros::param::param<string>("/am_super/platform/actual", platform_actual_param, "missing");
2020
ASSERT_EQ(platform_actual_param,"not_test");
2121

22-
waitUntil(LifeCycleState::CONFIGURING,"UIYT");
22+
2323
waitUntil(LifeCycleState::FINALIZED,"23SS");
2424
waitUntilMissionState(brain_box_msgs::VxState::SHUTDOWN,"HYUJ");
2525
}

src/super_lib/am_life_cycle.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -263,10 +263,10 @@ bool AMLifeCycle::withinConfigureTolerance()
263263
{
264264
bool tolerated = false;
265265
//outside of configuring, we have no tolerance
266-
if(life_cycle_info_.state == LifeCycleState::CONFIGURING)
266+
if(life_cycle_mediator_.unconfigured(life_cycle_info_))
267267
{
268268
ros::Duration duration_since_configure = ros::Time::now() - configure_start_time_;
269-
if (duration_since_configure <= ros::Duration(configure_tolerance_s) )
269+
if (life_cycle_info_.state == LifeCycleState::UNCONFIGURED || duration_since_configure <= ros::Duration(configure_tolerance_s) )
270270
{
271271
tolerated = true;
272272
}

src/super_lib/am_life_cycle_mediator.cpp

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -205,6 +205,19 @@ bool AMLifeCycleMediator::shutdown(const AMLifeCycleMediator::LifeCycleInfo& inf
205205
info.state == LifeCycleState::ACTIVE;
206206
}
207207

208+
bool AMLifeCycleMediator::unconfigured(const AMLifeCycleMediator::LifeCycleInfo& info)
209+
{
210+
switch (info.state)
211+
{
212+
case LifeCycleState::UNCONFIGURED:
213+
case LifeCycleState::CONFIGURING:
214+
return true;
215+
default:
216+
return false;
217+
}
218+
}
219+
220+
208221
bool AMLifeCycleMediator::redundantShutdown(const AMLifeCycleMediator::LifeCycleInfo& info)
209222
{
210223
return info.state == LifeCycleState::SHUTTING_DOWN ||
@@ -213,8 +226,7 @@ bool AMLifeCycleMediator::redundantShutdown(const AMLifeCycleMediator::LifeCycle
213226

214227
bool AMLifeCycleMediator::redundantError(const AMLifeCycleMediator::LifeCycleInfo& info)
215228
{
216-
return info.state == LifeCycleState::ERROR_PROCESSING || info.state == LifeCycleState::FINALIZED ||
217-
info.state == LifeCycleState::UNCONFIGURED;
229+
return info.state == LifeCycleState::ERROR_PROCESSING || info.state == LifeCycleState::FINALIZED;
218230
}
219231

220232
bool AMLifeCycleMediator::illegalDestroy(const AMLifeCycleMediator::LifeCycleInfo& info)

0 commit comments

Comments
 (0)