Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion path_planning/nodes/pole_finder_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import rospy

from path_planning.states.go_to_depth import GoToDepthState
from path_planning.pole_finder_demo_states import ColoredPoleFinderState, ColoredPoleApproacherState
from path_planning.states.pole_finder_demo_states import ColoredPoleFinderState, ColoredPoleApproacherState
from path_planning.state_machines.markov_chain_state_machine import MarkovChainStateMachine
from path_planning.state_machines.timed_state_machine import TimedStateMachine
from path_planning.state_executor import StateExecutor
Expand Down
2 changes: 1 addition & 1 deletion path_planning/nodes/thruster_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

machine = SequentialStateMachine('thruster_test', [WaitingState(20),
ThrusterTestState(thruster_count=8,
thrust_amplitude=8, thrust_period=5),
amplitude=8, period=5),
WaitingState(10)])

Tree.create_flowchart(machine, 'thruster-test')
Expand Down
1 change: 1 addition & 0 deletions path_planning/src/path_planning/state_executor.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ def run(self):
"""
This function will execute the state and block until it terminates.
"""
print(f'StateExecutor starting to execute top level state: {repr(self.state)}')
self.state.initialize(ros_time(), self.controls, self.sub_state, self.world_state, self.sensors)

while not rospy.is_shutdown():
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,17 @@ def __init__(self, name, decision_state, success_state, failure_state, success_c
self.idx = 0
self.completed = False

def state_name(self):
return self.name + '/' + self.states[self.idx].state_name()
def __repr__(self):
return f'BranchingStateMachine({self.name}, {repr(self.states[0])}, {repr(self.states[1])}, ' \
f'{repr(self.states[2])}, success_code={self.success_code})'

def __str__(self):
return f'BranchingStateMachine({self.name})'

def initialize(self, t, controls, sub_state, world_state, sensors):
self.idx = 0
self.completed = False
print(self.state_name(), 'starting to execute')
print(self, 'starting to execute')
self.states[self.idx].initialize(t, controls, sub_state, world_state, sensors)

def process(self, t, controls, sub_state, world_state, sensors):
Expand All @@ -38,7 +42,7 @@ def process(self, t, controls, sub_state, world_state, sensors):

self.idx = 1 if state.exit_code() == self.success_code else 2
new_state = self.states[self.idx]
print(self.name, 'switching from', state.state_name(), 'to', new_state.state_name())
print(self.name, 'switching from', state, 'to', new_state)
new_state.initialize(t, controls, sub_state, world_state, sensors)
new_state.process(t, controls, sub_state, world_state, sensors)
else:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,18 @@ def __init__(self, name, states, state_mapping_dictionaries, starting_index=0):
self.idx = starting_index
self.completed = False

def state_name(self):
return self.name + '/' + self.states[self.idx].state_name()
def __repr__(self):
states_str = ', '.join([repr(state) for state in self.states])
return f'MarkovChainStateMachine({self.name}, [{states_str}], {repr(self.state_mapping_dictionaries)}, ' \
f'starting_index={self.starting_index})'

def __str__(self):
return f'MarkovChainStateMachine({self.name})'

def initialize(self, t, controls, sub_state, world_state, sensors):
self.idx = self.starting_index
self.completed = False
print(self.state_name(), 'starting to execute a markov chain with', len(self.states), 'states')
print(self, 'starting to execute a markov chain with', len(self.states), 'states')
self.states[self.idx].initialize(t, controls, sub_state, world_state, sensors)

def process(self, t, controls, sub_state, world_state, sensors):
Expand All @@ -48,7 +53,7 @@ def process(self, t, controls, sub_state, world_state, sensors):
new_idx = self.state_mapping_dictionaries[self.idx][state.exit_code()]
if new_idx == HALT:
self.completed = True
print(self.name, 'completed via', state.state_name(), 'sub-state!')
print(self.name, 'completed via', state, 'sub-state!')
return

# Only manually finalize the state if it is not the last one
Expand All @@ -57,7 +62,7 @@ def process(self, t, controls, sub_state, world_state, sensors):

self.idx = new_idx
new_state = self.states[self.idx]
print(self.name, 'switching from', state.state_name(), 'to', new_state.state_name())
print(self, 'switching from', state, 'to', new_state)
new_state.initialize(t, controls, sub_state, world_state, sensors)
new_state.process(t, controls, sub_state, world_state, sensors)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,18 +25,19 @@ def __init__(self, name, states, daemon_states=None):
self.completed = False
self.finalized_states = [False] * (len(self.states) + len(self.daemon_states))

def state_name(self):
return self.name + \
'/[' + \
', '.join(state.state_name() for state in self.states if not state.has_completed()) + \
', '.join(state.state_name() + ' (daemon)' for state in self.daemon_states if not state.has_completed()) + \
']'
def __repr__(self):
states_str = ', '.join([repr(state) for state in self.states])
daemon_states_str = ', '.join([repr(state) for state in self.daemon_states])
return f'ParallelStateMachine({self.name}, [{states_str}], [{daemon_states_str}])'

def __str__(self):
return f'ParallelStateMachine({self.name})'

def initialize(self, t, controls, sub_state, world_state, sensors):
self.completed = False
self.finalized_states = [False] * (len(self.states) + len(self.daemon_states))

print(self.state_name(), 'starting to execute', len(self.states), 'states and',
print(self, 'starting to execute', len(self.states), 'states and',
len(self.daemon_states), 'daemon states in parallel')
for state in self.states + self.daemon_states:
state.initialize(t, controls, sub_state, world_state, sensors)
Expand All @@ -61,16 +62,16 @@ def has_completed(self):
for state in self.states:
if not state.has_completed():
return False
print(self.state_name(), 'completed!')
print(self, 'completed!')
return True

def exit_code(self):
# return the exit code of the last non-daemon state
return self.states[-1].exit_code()

def get_tree(self, depth=0):
return Tree(name=self.name,
children=[child.get_tree(depth=depth+1) for child in self.states],
daemon=[child.get_tree(depth=depth+1) for child in self.daemon_states],
def get_tree(self, depth=0, verbose=False):
return Tree(name=str(self),
children=[child.get_tree(depth + 1, verbose) for child in self.states],
daemon=[child.get_tree(depth + 1, verbose) for child in self.daemon_states],
nodeType="ParallelState",
depth=depth)
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,18 @@ def __init__(self, name, states):
self.idx = 0
self.completed = False

def state_name(self):
return self.name + '/' + self.states[self.idx].state_name()
def __repr__(self):
states_str = ', '.join([repr(state) for state in self.states])
return f'SequentialStateMachine({self.name}, [{states_str}])'

def __str__(self):
return f'SequentialStateMachine({self.name})'

def initialize(self, t, controls, sub_state, world_state, sensors):
self.idx = 0
self.completed = False

print(self.state_name(), 'starting to execute', len(self.states), 'states sequentially')
print(self, 'starting to execute', len(self.states), 'states sequentially')
self.states[self.idx].initialize(t, controls, sub_state, world_state, sensors)

def process(self, t, controls, sub_state, world_state, sensors):
Expand All @@ -40,7 +44,7 @@ def process(self, t, controls, sub_state, world_state, sensors):

self.idx += 1
new_state = self.states[self.idx]
print(self.name, 'switching from', state.state_name(), 'to', new_state.state_name())
print(self.name, 'switching from', state, 'to', new_state)
new_state.initialize(t, controls, sub_state, world_state, sensors)
new_state.process(t, controls, sub_state, world_state, sensors)

Expand All @@ -54,8 +58,8 @@ def exit_code(self):
# return the exit code of the last state
return self.states[-1].exit_code()

def get_tree(self, depth=0):
return Tree(name=self.name,
children=[child.get_tree(depth=depth+1) for child in self.states],
def get_tree(self, depth=0, verbose=False):
return Tree(name=str(self),
children=[child.get_tree(depth + 1, verbose) for child in self.states],
nodeType="SequentialState",
depth=depth)
Original file line number Diff line number Diff line change
Expand Up @@ -14,20 +14,24 @@ def __init__(self, state, timeout, timeout_exit_code=10):
self.timed_out = False
self.timeout_exit_code = timeout_exit_code

def state_name(self):
return 'timeout_wrapper/' + self.state.state_name()
def __repr__(self):
return f'TimedStateMachine({repr(self.state)}, timeout={self.timeout}, ' \
f'timeout_exit_code={self.timeout_exit_code})'

def __str__(self):
return f'TimedStateMachine(timeout={self.timeout}, timeout_exit_code={self.timeout_exit_code})'

def initialize(self, t, controls, sub_state, world_state, sensors):
self.start_time = t
self.timed_out = False

print(self.state_name(), 'starting to execute with timeout of', self.timeout, 'seconds')
print(self, 'starting to execute with timeout of', self.timeout, 'seconds')
self.state.initialize(t, controls, sub_state, world_state, sensors)

def process(self, t, controls, sub_state, world_state, sensors):
if t - self.start_time > self.timeout:
self.timed_out = True
print(self.state.state_name(), 'timed out after', self.timeout, 'seconds!')
print(self.state, 'timed out after', self.timeout, 'seconds!')
else:
self.state.process(t, controls, sub_state, world_state, sensors)

Expand Down
11 changes: 6 additions & 5 deletions path_planning/src/path_planning/state_tree.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,15 @@ class Tree:
"""

@staticmethod
def create_flowchart(state, file_name='test', popup=True):
def create_flowchart(state, file_name='test', verbose=False, popup=True):
"""
:@param state: The root state to use to generate the flowchart.
:@param file_name: The file name (without the extension) to save the flowchart PDF with.
:@param popup: If True, then the flowchart will popup so that can be seen immediately.
:param state: The root state to use to generate the flowchart.
:param file_name: The file name (without the extension) to save the flowchart PDF with.
:param verbose: If True, then repr will be used for leaf states instead of str.
:param popup: If True, then the flowchart will popup so that it can be seen immediately.
"""
path = rospkg.RosPack().get_path('path_planning') + f'/node_flowcharts/{file_name}.gv'
state.get_tree().render_graph(path, popup)
state.get_tree(verbose).render_graph(path, popup)
print('Flowchart generated!')

def __init__(self, name, nodeType, children=None, daemon=None, depth=0, number=1):
Expand Down
20 changes: 8 additions & 12 deletions path_planning/src/path_planning/states/barrel_roll.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,7 @@ def __init__(self, positive_dir=True):
self.completed = False # True once the sub has stabilized and completed the barrel roll

def __repr__(self):
return self.state_name()

@staticmethod
def state_name():
return "barrel_roll"
return f'BarrelRoll(positive_dir={self.positive_dir})'

def initialize(self, t, controls, sub_state, world_state, sensors):
self.crossed_90 = False
Expand All @@ -34,7 +30,7 @@ def initialize(self, t, controls, sub_state, world_state, sensors):
print('Sub not in valid position to start barrel roll!')
controls.halt_and_catch_fire()
return
print(self.state_name(), 'starting to barrel roll in',
print(self, 'starting to barrel roll in',
'positive' if self.positive_dir else 'negative', 'x direction')

def process(self, t, controls, sub_state, world_state, sensors):
Expand All @@ -47,39 +43,39 @@ def process(self, t, controls, sub_state, world_state, sensors):
if not self.crossed_90:
if np.pi / 2 < roll < np.pi:
self.crossed_90 = True
print(self.state_name(), 'completed 90 degrees!')
print(self, 'completed 90 degrees!')
target_angle = roll + np.pi / 2
elif not self.crossed_270:
if 3 * np.pi / 2 < roll < 2 * np.pi:
self.crossed_270 = True
print(self.state_name(), 'completed 270 degrees!')
print(self, 'completed 270 degrees!')
target_angle = 0
else:
target_angle = roll + np.pi / 2
else:
# If within 5 deg of level and |roll_rate| < 2 deg/s
if self.is_stable(roll, roll_rate):
self.completed = True
print(self.state_name(), 'completed barrel roll!')
print(self, 'completed barrel roll!')
# target angle was already set to 0, so we don't need to send it again
return
else:
if not self.crossed_90:
if np.pi < roll < 3 * np.pi / 2:
self.crossed_90 = True
print(self.state_name(), 'completed 90 degrees!')
print(self, 'completed 90 degrees!')
target_angle = roll - np.pi / 2
elif not self.crossed_270:
if 0 < roll < np.pi / 2:
self.crossed_270 = True
print(self.state_name(), 'completed 270 degrees!')
print(self, 'completed 270 degrees!')
target_angle = 0
else:
target_angle = roll - np.pi / 4
else:
if self.is_stable(roll, roll_rate):
self.completed = True
print(self.state_name(), 'completed barrel roll!')
print(self, 'completed barrel roll!')
# target angle was already set to 0, so we don't need to send it again
return
controls.set_roll_goal(target_angle)
Expand Down
25 changes: 19 additions & 6 deletions path_planning/src/path_planning/states/base_state.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,20 @@ class BaseState(ABC):
Each state should define how it interacts with the depth and orientation control systems, because those are
persisted across state changes.
"""
def state_name(self):
return "base_state"

def __repr__(self):
return self.state_name()
"""
All subclasses should override this function if they accept arguments in __init__.
All of those arguments should be included in the string representation for repr,
such that eval(repr(state)) == state.
That way, repr will provide an unambiguous representation of the state.
State machines should recursively call __repr__ for any child states.

If the representation is too verbose, you can optionally also implement __str__ and provide a more human
readable representation.
As a rule of thumb, exclude any tolerance values or verbose flags from the __str__ representation.
State machines should also exclude recursive calls to child states in __str__.
"""
return f'{self.__class__.__name__}()'

def initialize(self, t, controls, sub_state, world_state, sensors):
"""
Expand Down Expand Up @@ -58,7 +67,11 @@ def exit_code(self):
"""
return 0

def get_tree(self, depth=0):
return Tree(name=self.__repr__(),
def get_tree(self, depth=0, verbose=False):
"""
:param depth:
:param verbose: If True, then repr will be used for leaf states instead of str.
"""
return Tree(name=repr(self) if verbose else str(self),
nodeType="State",
depth=depth)
7 changes: 2 additions & 5 deletions path_planning/src/path_planning/states/data_logger.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ def __init__(self, file_name='submarine-log'):
self.data_post_processing_funcs = []

def __repr__(self):
return self.state_name()
return f'DataLogger(file_name={self.file_name})'

def add_data_post_processing_func(self, data_post_processing_func):
"""
Expand All @@ -38,13 +38,10 @@ def shutdown_hook(self):
if not self.completed and len(self.data) > 0:
self.save_data()

def state_name(self):
return "data_logger"

def initialize(self, t, controls, sub_state, world_state, sensors):
self.completed = False
self.data = []
print(self.state_name(), 'starting to log data')
print(self, 'starting to log data')

def process(self, t, controls, sub_state, world_state, sensors):
# for now just log the depth
Expand Down
5 changes: 1 addition & 4 deletions path_planning/src/path_planning/states/exit_code_state.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,7 @@ def __init__(self, code):
self.code = code

def __repr__(self):
return self.state_name()

def state_name(self):
return 'exit_code'
return f'ExitCode({self.code})'

def has_completed(self):
return True
Expand Down
Loading