Skip to content

Commit 79ccde1

Browse files
author
Format Bot
committed
style: Applied ROS C++ Style Guide
1 parent b3ebd45 commit 79ccde1

File tree

4 files changed

+111
-119
lines changed

4 files changed

+111
-119
lines changed

include/am_super/state_mediator.h

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -7,33 +7,31 @@
77

88
namespace am
99
{
10-
1110
/**
12-
* Provides all logic about system State allowing the State objects
13-
* to be simply data objects. Allows the ROS node to hold the state of the
14-
* system, but delegates all logic to here improving readability, encapsulation
11+
* Provides all logic about system State allowing the State objects
12+
* to be simply data objects. Allows the ROS node to hold the state of the
13+
* system, but delegates all logic to here improving readability, encapsulation
1514
* and ability to test.
16-
*
15+
*
1716
* This class is stateless, but non-static allowing extension to change behavior
18-
* if different deployments warrant different behavior.
17+
* if different deployments warrant different behavior.
1918
*/
2019
class StateMediator
2120
{
22-
2321
public:
2422
StateMediator();
2523

26-
/** An indicator that the string is not valid.
24+
/** An indicator that the string is not valid.
2725
* Instead of throwing an exception which causes difficult to debug seg faults
28-
* or returning an empty string creating a mystery of what why something is missing.
26+
* or returning an empty string creating a mystery of what why something is missing.
2927
**/
3028
static constexpr std::string_view INVALID_STRING = "INVALID";
3129

3230
/** See https://automodality.atlassian.net/wiki/spaces/AMROS/pages/929234949/AMROS+System+States
3331
* @return true if the new state is acceptable to follow the current.
3432
*/
3533
bool allowsTransition(SuperState from, SuperState to);
36-
34+
3735
/**
3836
* @return a vector of all states in order of declaration, excluding LastState which is used for enum iteration
3937
*/

src/am_super/am_super.cpp

Lines changed: 12 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -764,28 +764,29 @@ class AMSuper
764764
{
765765
ROS_INFO_STREAM("request change system state from: " << stateToString(system_state_)
766766
<< " to: " << stateToString(state));
767-
bool legal = state_mediator_.allowsTransition(system_state_,state);
767+
bool legal = state_mediator_.allowsTransition(system_state_, state);
768768

769769
if (!legal)
770770
{
771-
ROS_ERROR_STREAM("illegal state transition from "
772-
<< stateToString(system_state_) << " to " << stateToString(state));
771+
ROS_ERROR_STREAM("illegal state transition from " << stateToString(system_state_) << " to "
772+
<< stateToString(state));
773773
}
774774
else
775775
{
776-
//send lifecycle updates for selected state transitions
777-
switch(state){
776+
// send lifecycle updates for selected state transitions
777+
switch (state)
778+
{
778779
case SuperState::READY:
779-
ROS_INFO_STREAM("sending CONFIGURE to all nodes");
780-
sendLifeCycleCommand(AMLifeCycle::BROADCAST_NODE_NAME, LifeCycleCommand::CONFIGURE);
780+
ROS_INFO_STREAM("sending CONFIGURE to all nodes");
781+
sendLifeCycleCommand(AMLifeCycle::BROADCAST_NODE_NAME, LifeCycleCommand::CONFIGURE);
781782
break;
782783
case SuperState::ARMING:
783-
ROS_INFO_STREAM("sending ACTIVATE to all nodes");
784-
sendLifeCycleCommand(AMLifeCycle::BROADCAST_NODE_NAME, LifeCycleCommand::ACTIVATE);
784+
ROS_INFO_STREAM("sending ACTIVATE to all nodes");
785+
sendLifeCycleCommand(AMLifeCycle::BROADCAST_NODE_NAME, LifeCycleCommand::ACTIVATE);
785786
break;
786787
}
787-
788-
//persist given state as the new current state
788+
789+
// persist given state as the new current state
789790
system_state_ = state;
790791

791792
reportSystemState();

src/am_super/state_mediator.cpp

Lines changed: 37 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -2,46 +2,47 @@
22

33
namespace am
44
{
5-
6-
const std::map<SuperState, std::vector<SuperState>> transitions_ =
7-
{
8-
{ SuperState::OFF, {SuperState::BOOTING} },
9-
{ SuperState::BOOTING, {SuperState::READY} },
10-
{ SuperState::READY, {SuperState::ARMING} },
11-
{ SuperState::ARMING, {SuperState::ARMED} },
12-
{ SuperState::ARMED, {SuperState::AUTO, SuperState::ABORT} },
13-
{ SuperState::AUTO, {SuperState::READY,SuperState::SEMI_AUTO,SuperState::HOLD,SuperState::ABORT,SuperState::MANUAL} },
14-
{ SuperState::SEMI_AUTO, {SuperState::AUTO,SuperState::HOLD,SuperState::ABORT,SuperState::MANUAL} },
15-
{ SuperState::HOLD, {SuperState::ABORT,SuperState::MANUAL} },
16-
{ SuperState::ABORT, {SuperState::READY,SuperState::MANUAL} },
17-
{ SuperState::MANUAL, {SuperState::READY} },
18-
{ SuperState::SHUTDOWN, {SuperState::OFF} },
5+
const std::map<SuperState, std::vector<SuperState>> transitions_ = {
6+
{ SuperState::OFF, { SuperState::BOOTING } },
7+
{ SuperState::BOOTING, { SuperState::READY } },
8+
{ SuperState::READY, { SuperState::ARMING } },
9+
{ SuperState::ARMING, { SuperState::ARMED } },
10+
{ SuperState::ARMED, { SuperState::AUTO, SuperState::ABORT } },
11+
{ SuperState::AUTO,
12+
{ SuperState::READY, SuperState::SEMI_AUTO, SuperState::HOLD, SuperState::ABORT, SuperState::MANUAL } },
13+
{ SuperState::SEMI_AUTO, { SuperState::AUTO, SuperState::HOLD, SuperState::ABORT, SuperState::MANUAL } },
14+
{ SuperState::HOLD, { SuperState::ABORT, SuperState::MANUAL } },
15+
{ SuperState::ABORT, { SuperState::READY, SuperState::MANUAL } },
16+
{ SuperState::MANUAL, { SuperState::READY } },
17+
{ SuperState::SHUTDOWN, { SuperState::OFF } },
1918
};
2019

21-
const std::map<SuperState, std::string_view> state_strings_ =
22-
{
23-
{ SuperState::OFF, "OFF" },
24-
{ SuperState::BOOTING, "BOOTING" },
25-
{ SuperState::READY, "READY" },
26-
{ SuperState::ARMING, "ARMING" },
27-
{ SuperState::ARMED, "ARMED" },
28-
{ SuperState::AUTO, "AUTO" },
29-
{ SuperState::SEMI_AUTO, "SEMI_AUTO" },
30-
{ SuperState::HOLD, "HOLD" },
31-
{ SuperState::ABORT, "ABORT" },
32-
{ SuperState::MANUAL, "MANUAL" },
33-
{ SuperState::SHUTDOWN, "SHUTDOWN" },
20+
const std::map<SuperState, std::string_view> state_strings_ = {
21+
{ SuperState::OFF, "OFF" },
22+
{ SuperState::BOOTING, "BOOTING" },
23+
{ SuperState::READY, "READY" },
24+
{ SuperState::ARMING, "ARMING" },
25+
{ SuperState::ARMED, "ARMED" },
26+
{ SuperState::AUTO, "AUTO" },
27+
{ SuperState::SEMI_AUTO, "SEMI_AUTO" },
28+
{ SuperState::HOLD, "HOLD" },
29+
{ SuperState::ABORT, "ABORT" },
30+
{ SuperState::MANUAL, "MANUAL" },
31+
{ SuperState::SHUTDOWN, "SHUTDOWN" },
3432
};
3533

36-
StateMediator::StateMediator(){
34+
StateMediator::StateMediator()
35+
{
3736
}
3837

3938
bool StateMediator::allowsTransition(SuperState from, SuperState to)
4039
{
4140
bool legal = false;
42-
if(transitions_.count(from) > 0){
41+
if (transitions_.count(from) > 0)
42+
{
4343
std::vector<SuperState> allowed = transitions_.at(from);
44-
if(std::find(allowed.begin(),allowed.end(),to) != allowed.end()){
44+
if (std::find(allowed.begin(), allowed.end(), to) != allowed.end())
45+
{
4546
legal = true;
4647
}
4748
}
@@ -51,20 +52,22 @@ bool StateMediator::allowsTransition(SuperState from, SuperState to)
5152
std::vector<SuperState> StateMediator::allSuperStates()
5253
{
5354
std::vector<SuperState> all;
54-
for ( int enumIndex = (int) SuperState::OFF; enumIndex <= (int) SuperState::LAST_STATE; enumIndex++ )
55+
for (int enumIndex = (int)SuperState::OFF; enumIndex <= (int)SuperState::LAST_STATE; enumIndex++)
5556
{
5657
SuperState state = static_cast<SuperState>(enumIndex);
5758
all.push_back(state);
5859
}
5960
return all;
6061
}
6162

62-
6363
std::string_view StateMediator::stateToString(SuperState state)
6464
{
65-
if(state_strings_.count(state) > 0){
65+
if (state_strings_.count(state) > 0)
66+
{
6667
return state_strings_.at(state);
67-
}else{
68+
}
69+
else
70+
{
6871
return INVALID_STRING;
6972
}
7073
}

0 commit comments

Comments
 (0)