diff --git a/path_planning/nodes/pole_finder_demo.py b/path_planning/nodes/pole_finder_demo.py index 0cc18329..b264e33c 100755 --- a/path_planning/nodes/pole_finder_demo.py +++ b/path_planning/nodes/pole_finder_demo.py @@ -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 diff --git a/path_planning/nodes/thruster_test.py b/path_planning/nodes/thruster_test.py index 7d43da1c..7a798dc8 100755 --- a/path_planning/nodes/thruster_test.py +++ b/path_planning/nodes/thruster_test.py @@ -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') diff --git a/path_planning/src/path_planning/state_executor.py b/path_planning/src/path_planning/state_executor.py index e6d879bf..1da083a1 100644 --- a/path_planning/src/path_planning/state_executor.py +++ b/path_planning/src/path_planning/state_executor.py @@ -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(): diff --git a/path_planning/src/path_planning/state_machines/branching_state_machine.py b/path_planning/src/path_planning/state_machines/branching_state_machine.py index 7b26f30a..cc616430 100644 --- a/path_planning/src/path_planning/state_machines/branching_state_machine.py +++ b/path_planning/src/path_planning/state_machines/branching_state_machine.py @@ -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): @@ -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: diff --git a/path_planning/src/path_planning/state_machines/markov_chain_state_machine.py b/path_planning/src/path_planning/state_machines/markov_chain_state_machine.py index 024b583e..826ae135 100644 --- a/path_planning/src/path_planning/state_machines/markov_chain_state_machine.py +++ b/path_planning/src/path_planning/state_machines/markov_chain_state_machine.py @@ -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): @@ -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 @@ -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) diff --git a/path_planning/src/path_planning/state_machines/parallel_state_machine.py b/path_planning/src/path_planning/state_machines/parallel_state_machine.py index b654b93f..ab5045c5 100644 --- a/path_planning/src/path_planning/state_machines/parallel_state_machine.py +++ b/path_planning/src/path_planning/state_machines/parallel_state_machine.py @@ -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) @@ -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) diff --git a/path_planning/src/path_planning/state_machines/sequential_state_machine.py b/path_planning/src/path_planning/state_machines/sequential_state_machine.py index 97ee41da..aa9a4ec4 100644 --- a/path_planning/src/path_planning/state_machines/sequential_state_machine.py +++ b/path_planning/src/path_planning/state_machines/sequential_state_machine.py @@ -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): @@ -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) @@ -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) diff --git a/path_planning/src/path_planning/state_machines/timed_state_machine.py b/path_planning/src/path_planning/state_machines/timed_state_machine.py index bd6468b7..20d01bec 100644 --- a/path_planning/src/path_planning/state_machines/timed_state_machine.py +++ b/path_planning/src/path_planning/state_machines/timed_state_machine.py @@ -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) diff --git a/path_planning/src/path_planning/state_tree.py b/path_planning/src/path_planning/state_tree.py index 525988ce..1136af65 100644 --- a/path_planning/src/path_planning/state_tree.py +++ b/path_planning/src/path_planning/state_tree.py @@ -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): diff --git a/path_planning/src/path_planning/states/barrel_roll.py b/path_planning/src/path_planning/states/barrel_roll.py index 3ea5d038..f50d83e8 100644 --- a/path_planning/src/path_planning/states/barrel_roll.py +++ b/path_planning/src/path_planning/states/barrel_roll.py @@ -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 @@ -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): @@ -47,12 +43,12 @@ 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 @@ -60,26 +56,26 @@ def process(self, t, controls, sub_state, world_state, sensors): # 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) diff --git a/path_planning/src/path_planning/states/base_state.py b/path_planning/src/path_planning/states/base_state.py index 95555c54..9b5a1960 100644 --- a/path_planning/src/path_planning/states/base_state.py +++ b/path_planning/src/path_planning/states/base_state.py @@ -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): """ @@ -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) diff --git a/path_planning/src/path_planning/states/data_logger.py b/path_planning/src/path_planning/states/data_logger.py index 36b189f1..f29c6cd7 100644 --- a/path_planning/src/path_planning/states/data_logger.py +++ b/path_planning/src/path_planning/states/data_logger.py @@ -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): """ @@ -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 diff --git a/path_planning/src/path_planning/states/exit_code_state.py b/path_planning/src/path_planning/states/exit_code_state.py index 545b4d99..9d4ce2d5 100644 --- a/path_planning/src/path_planning/states/exit_code_state.py +++ b/path_planning/src/path_planning/states/exit_code_state.py @@ -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 diff --git a/path_planning/src/path_planning/states/go_to_depth.py b/path_planning/src/path_planning/states/go_to_depth.py index 3e8285f5..2a37875c 100644 --- a/path_planning/src/path_planning/states/go_to_depth.py +++ b/path_planning/src/path_planning/states/go_to_depth.py @@ -16,15 +16,16 @@ def __init__(self, depth, tolerance=0.25, velocity_tolerance=0.1, verbose=False) self.verbose = verbose def __repr__(self): - return "{}({})".format(self.state_name(), self.depth_goal) + return f"GoToDepthState({self.depth_goal}, tolerance={self.tolerance}, " \ + f"velocity_tolerance={self.velocity_tolerance}, verbose={self.verbose})" - def state_name(self): - return "go_to_depth_state" + def __str__(self): + return f"GoToDepthState({self.depth_goal})" def initialize(self, t, controls, sub_state, world_state, sensors): self.completed = False controls.set_depth_goal(self.depth_goal) - print(self.state_name(), 'starting to go to depth', self.depth_goal, 'm') + print(self, 'starting to go to depth', self.depth_goal, 'm') def process(self, t, controls, sub_state, world_state, sensors): current_depth = sub_state.get_submarine_state().position.z @@ -35,7 +36,7 @@ def process(self, t, controls, sub_state, world_state, sensors): v_z = sub_state.get_submarine_state().velocity.z if depth_err < self.tolerance and abs(v_z) < self.velocity_tolerance: self.completed = True - print(self.state_name(), 'completed!') + print(self, 'completed!') def has_completed(self): return self.completed diff --git a/path_planning/src/path_planning/pole_finder_demo_states.py b/path_planning/src/path_planning/states/pole_finder_demo_states.py similarity index 92% rename from path_planning/src/path_planning/pole_finder_demo_states.py rename to path_planning/src/path_planning/states/pole_finder_demo_states.py index 618a858c..b569c59c 100644 --- a/path_planning/src/path_planning/pole_finder_demo_states.py +++ b/path_planning/src/path_planning/states/pole_finder_demo_states.py @@ -15,8 +15,8 @@ def __init__(self, color_low, color_high): self.num_matching_pixels = 0 - def state_name(self): - return "colored_pole_finder_state" + def __repr__(self): + return f'ColoredPoleFinderState(color_low={self.color_low}, color_high={self.color_high})' def initialize(self, t, controls, sub_state, world_state, sensors): self.last_t = t @@ -66,8 +66,8 @@ def __init__(self, color_low, color_high): self.fx_pid.output_limits = (-0.5, 0.5) self.fx_pid.setpoint = 0 - def state_name(self): - return "colored_pole_approacher_state" + def __repr__(self): + return f'ColoredPoleApproacherState(color_low={self.color_low}, color_high={self.color_high})' def initialize(self, t, controls, sub_state, world_state, sensors): self.last_t = t @@ -110,7 +110,6 @@ def process(self, t, controls, sub_state, world_state, sensors): self.time_close = self.time_close + dt else: self.time_close = 0 - cv2.imshow('image', image) cv2.imshow('mask', mask) @@ -119,7 +118,7 @@ def process(self, t, controls, sub_state, world_state, sensors): def finalize(self, t, controls, sub_state, world_state, sensors): controls.planar_move_command(Fx=0) - def completed(self): + def has_completed(self): return self.has_lost_pole() or self.at_pole() def exit_code(self): diff --git a/path_planning/src/path_planning/states/relative_travel_state.py b/path_planning/src/path_planning/states/relative_travel_state.py index 8241498d..2f9d492c 100644 --- a/path_planning/src/path_planning/states/relative_travel_state.py +++ b/path_planning/src/path_planning/states/relative_travel_state.py @@ -24,7 +24,8 @@ def __init__(self, target='pole', x_offset=None, y_offset=None, z_offset=None, r self.absolute_target_yaw = math.degrees(math.atan2(-y_offset, -x_offset)) + relative_yaw def __repr__(self): - return "{}({})".format(self.state_name(), self.target) + return f'RelativeTravelState({self.target}, {self.x_offset}, {self.y_offset}, {self.z_offset}, ' \ + f'relative_yaw={self.relative_yaw})' def update_target(self, target): self.target = target @@ -44,9 +45,6 @@ def update_travel_state_helper(self, world_state): self.travel_state_helper.update_target(new_target_x, new_target_y, new_target_z, self.absolute_target_yaw) - def state_name(self): - return "relative_travel" - def initialize(self, t, controls, sub_state, world_state, sensors): self.update_travel_state_helper(world_state) self.travel_state_helper.initialize(t, controls, sub_state, world_state, sensors) diff --git a/path_planning/src/path_planning/states/stabilize_state.py b/path_planning/src/path_planning/states/stabilize_state.py index c30b4a0f..59e5dc96 100644 --- a/path_planning/src/path_planning/states/stabilize_state.py +++ b/path_planning/src/path_planning/states/stabilize_state.py @@ -10,32 +10,33 @@ class StabilizeState(BaseState): """ def __init__(self, roll=0, pitch=0, yaw=0, tolerance_degrees=5, velocity_tolerance_degrees=2): - self.r = roll - self.p = pitch - self.y = yaw + self.roll = roll + self.pitch = pitch + self.yaw = yaw self.tolerance = np.radians(tolerance_degrees) self.velocity_tolerance = np.radians(velocity_tolerance_degrees) self.completed = False def __repr__(self): - return self.state_name() + return f'StabilizeState(roll={self.roll}, pitch={self.pitch}, yaw={self.yaw}, ' \ + f'tolerance_degrees={np.degrees(self.tolerance)}, velocity_tolerance_degrees={self.velocity_tolerance})' - def state_name(self): - return "stabilize_state" + def __str__(self): + return f'StabilizeState(roll={self.roll}, pitch={self.pitch}, yaw={self.yaw})' def initialize(self, t, controls, sub_state, world_state, sensors): self.completed = False - controls.set_orientation_goal(roll=self.r, pitch=self.p, yaw=self.y) - print(self.state_name(), 'starting to stabilize to (r, p, y)=(', self.r, ',', self.p, ',', self.y, ')') + controls.set_orientation_goal(roll=self.roll, pitch=self.pitch, yaw=self.yaw) + print(self, 'starting to stabilize to (r, p, y)=(', self.roll, ',', self.pitch, ',', self.yaw, ')') def process(self, t, controls, sub_state, world_state, sensors): state = sub_state.get_submarine_state() - if abs_angle_difference(self.r, state.orientation_rpy.x) < self.tolerance and \ - abs_angle_difference(self.p, state.orientation_rpy.y) < self.tolerance and \ - abs_angle_difference(self.y, state.orientation_rpy.z) < self.tolerance and \ + if abs_angle_difference(self.roll, state.orientation_rpy.x) < self.tolerance and \ + abs_angle_difference(self.pitch, state.orientation_rpy.y) < self.tolerance and \ + abs_angle_difference(self.yaw, state.orientation_rpy.z) < self.tolerance and \ state.angular_velocity.magnitude() < self.velocity_tolerance: self.completed = True - print(self.state_name(), 'stabilized!') + print(self, 'stabilized!') def has_completed(self): return self.completed diff --git a/path_planning/src/path_planning/states/thruster_test_state.py b/path_planning/src/path_planning/states/thruster_test_state.py index de078095..75178bac 100644 --- a/path_planning/src/path_planning/states/thruster_test_state.py +++ b/path_planning/src/path_planning/states/thruster_test_state.py @@ -8,35 +8,33 @@ class ThrusterTestState(BaseState): This state directly sends commands to the /motor_command topic, bypassing the thrust_computer node (which must not be running for this to work). """ - def __init__(self, thruster_count=8, thrust_amplitude=3, thrust_period=5): + def __init__(self, thruster_count=8, amplitude=3, period=5): """ Tests each of the thrusters in sequence with a sinusoidal thrust output with the given amplitude and period. :param thruster_count: The number of thrusters to test. - :param thrust_amplitude: The amplitude of the thrust in newtons. - :param thrust_period: The amount of time that each thruster will be tested for. + :param amplitude: The amplitude of the thrust in newtons. + :param period: The amount of time that each thruster will be tested for. """ self.thruster_count = thruster_count - self.thrust_amplitude = thrust_amplitude - self.period = thrust_period - self.k = 2 * np.pi / thrust_period + self.thrust_amplitude = amplitude + self.period = period + self.k = 2 * np.pi / period self.start_time = 0 self.completed = False def __repr__(self): - return self.state_name() + str(self.period) - - def state_name(self): - return "thruster_test_state" + return f'ThrusterTestState(thruster_count={self.thruster_count}, amplitude={self.thrust_amplitude}, ' \ + f'period={self.period})' def initialize(self, t, controls, sub_state, world_state, sensors): self.start_time = t self.completed = False - print(self.state_name(), 'starting to test', self.thruster_count, 'thrusters') + print(self, 'starting to test', self.thruster_count, 'thrusters') def process(self, t, controls, sub_state, world_state, sensors): thruster_index = int((t - self.start_time) / self.period) # round down - if thruster_index == self.thruster_count: + if thruster_index >= self.thruster_count: self.completed = True return diff --git a/path_planning/src/path_planning/states/travel_state.py b/path_planning/src/path_planning/states/travel_state.py index 7623e4fb..c1614c41 100644 --- a/path_planning/src/path_planning/states/travel_state.py +++ b/path_planning/src/path_planning/states/travel_state.py @@ -22,7 +22,11 @@ def __init__(self, target_x=0, target_y=0, target_z=0, target_yaw=0, verbose=Tru self.completed = False def __repr__(self): - return "{}({}, {}, {})".format(self.state_name(), self.target_x, self.target_y, self.target_z) + return f'TravelState({self.target_x}, {self.target_y}, {self.target_z}, target_yaw={self.target_yaw}, ' \ + f'verbose={self.verbose})' + + def __str__(self): + return f'TravelState({self.target_x}, {self.target_y}, {self.target_z}, target_yaw={self.target_yaw})' def update_target(self, target_x=None, target_y=None, target_z=None, target_yaw=None): """ @@ -42,9 +46,6 @@ def update_target(self, target_x=None, target_y=None, target_z=None, target_yaw= self.target_yaw = np.radians(target_yaw) self.invalidated = True - def state_name(self): - return "travel_state" - def update_targets(self, controls): if self.invalidated: controls.set_movement_target(self.target_x, self.target_y) diff --git a/path_planning/src/path_planning/states/waiting_state.py b/path_planning/src/path_planning/states/waiting_state.py index 5214bc75..ef2490d3 100644 --- a/path_planning/src/path_planning/states/waiting_state.py +++ b/path_planning/src/path_planning/states/waiting_state.py @@ -12,21 +12,17 @@ def __init__(self, delay): self.completed = False def __repr__(self): - return "{}({})".format(self.state_name(), self.delay) - - @staticmethod - def state_name(): - return "waiting_state" + return f'WaitingState({self.delay})' def initialize(self, t, controls, sub_state, world_state, sensors): self.start_time = t self.completed = False - print(self.state_name(), 'starting to wait for', self.delay, 'seconds') + print(self, 'starting to wait for', self.delay, 'seconds') def process(self, t, controls, sub_state, world_state, sensors): if t - self.start_time > self.delay: self.completed = True - print(self.state_name(), 'completed waiting!') + print(self, 'completed waiting!') def has_completed(self): return self.completed