as2_python_api.mission_interpreter.mission_interpreter module

Mission Interpreter and Executer.

class as2_python_api.mission_interpreter.mission_interpreter.MissionInterpreter(use_sim_time: bool = False, verbose: bool = False, executor: rclpy.executors.Executor = rclpy.executors.SingleThreadedExecutor)

Bases: object

Mission Interpreter and Executer.

append_mission(mid: int, mission: Mission) None

Insert mission at the end of the stack.

property drone: DroneInterfaceBase

Build a DroneInterface based on the mission requirements.

property feedback

Get current behavior feedback.

property feedback_dict

Get current behavior feedback dictionary.

insert_mission(mid: int, mission: Mission) None

Insert mission in front of the stack.

load_mission(mid: int, mission: Mission) None

Reset Mission Interpreter with other mission.

load_modules(mission: Mission)
property mission: Mission

Mission.

property mission_stack: MissionStack

Mission stack.

modify(idx: int, mid: int, item: MissionItem) bool

Modify mission item at index with another MissionItem.

Parameters:
  • idx (int) – index of the item to modify

  • mid (int) – mission ID

  • item (MissionItem) – MissionItem to modify from

Returns:

True if modified, False otherwise

Return type:

bool

next_item(mid: int) bool

Advance to next item in mission.

pause_mission(mid: int) bool

Pause mission.

reset(mid: int, mission: Mission) None

Reset Mission Interpreter with other mission.

resume_mission(mid: int) bool

Resume mission.

shutdown() None

Shutdown properly.

start_mission(mid: int) bool

Start mission in different thread.

property status: InterpreterStatus

Mission status.

stop_mission(mid: int) bool

Stop mission.

as2_python_api.mission_interpreter.mission_interpreter.test()

A doctest in a docstring.

>>> test()
test called with height=1.0, speed=2.0 and wait=True
test called with height=98.0, speed=99.0 and wait=True