mil_missions_core
- Base mission classes¶
Core library for creating missions to use with a mission server. The primary class
to be used with a mission server is BaseMission
, which can be inherited
from to create robot-specific mission tasks. These mission classes can be imported
by the mission runner and then run.
BaseMission¶
- class mil_missions_core.BaseMission(parent=None)[source]¶
The base for all missions used in mil_missions. Lots of this class is just documentation for the various functions that real missions can overload. Individual ROS robotics platforms should extend this base class to provide interfaces to the particular systems on the robot.
- str(x)
Prints the name of the mission.
- classmethod decode_parameters(parameters: str) dict | str [source]¶
Process parameters string from new mission goal or submission. Should return the processes parameters which will be passed to the run function. By default returns the json decoded object in the string or, if this fails, just the original string.
If this function throws an exception (such as a ParametersException), the mission will be aborted.
- classmethod has_mission(name: str)[source]¶
Returns true if the mission runner has a mission with specified name.
- classmethod name() str [source]¶
Override for real missions to return a string for how the mission with be referenced in the GUI/CLI. For example, a mission implemented in class
MyCoolMission
might implement.class MyCoolMission: @classmethod def name(cls): return 'My cool mission'
- Returns
The name of the mission. By default, simply returns the class’
__name__
method.- Return type
- run(parameters)[source]¶
The actual body of the mission. Should attempt to execute whatever is expected of the mission, using the interfaces set up in
setup()
orsetup_base()
to command actuator movements, read perception output, etc. Should usesend_feedback()
to update clients about what the mission is doing at the moment.If something goes wrong, raise an exception describing what went wrong and the mission will be aborted.
If it executes successfully, return with a string to send a final result to the connected clients. Missions can also spawn other missions in the run function using
run_submission()
.- Parameters
parameters – Arguments to modify the behavior of the mission. By default will be a json decoded object from the string passed in the goal, but can be changed by overriding decode_parameters.
- async run_submission(name: str, parameters: str = '') None [source]¶
Runs another mission available to the mission server, returning the string result of the missions execution.
- Parameters
name (str) – The name of the submission to spawn as a string. If this mission is unknown, raise an exception.
parameters (str) – Parameters to pass to the run function of the submission. Note, this function does not call decode_parameters, so parent missions need to do this or otherwise ensure the parameters are in the format expected by the child. Defaults to an empty string.
- Raises
Exception – The submission name is unrecognized - therefore, no submission can be run.
- Returns
The result of the mission with the given name.
- Return type
Optional[str]
- send_feedback(message: str) None [source]¶
Send a string as feedback to any clients monitoring this mission. If the mission is a child mission, it will call the send_feedback_child of its parent, allowing missions to choose how to use the feedback from its children.
- send_feedback_child(message: str, child: BaseMission)[source]¶
Called by child missions when sending feedback. By default sends this feedback prefixed with the name of the child mission.
- async classmethod setup() None [source]¶
Used to setup individual child missions. This is called after the base mission is setup using
setup_base()
.This method should be overridden for all child missions who wish to have a resource ready for when the mission begins.
Any resource setup in this method should be shutdown using the
shutdown()
method.class MovementMission(MyFancyRobotMission): @classmethod async def setup(cls): self.my_sub = await self.nh.subscribe("/my_topic", MyMessage) @classmethod async def shutdown(cls): await self.my_sub.shutdown()
- async classmethod setup_base(mission_runner) None [source]¶
Sets up a base mission, used to generate individual child missions that perform individual actions. This method should set up resources needed by all child missions, so that they will be available when the child mission begins.
This method should only be used for base missions, and there should be just one base mission per individual robotic system.
class MyFancyRobotMission: @classmethod async def setup_base(cls, mission_runner): await super(cls).setup_base(mission_runner)
- Parameters
mission_runner (
MissionRunner
) – The mission runner that will run the missions. Used to allow the individual missions to send feedback to the mission runner.
- async classmethod shutdown() None [source]¶
Shuts down a child mission. This is called when the mission server is shutting down all individual child missions.
Any resources that were setup using
setup()
should be considered for shutdown using this method.
- async classmethod shutdown_base() None [source]¶
Shuts down a base mission. This is called when the mission server is shutting down, and can be used to ensure that resources are properly closed. This is called before each individual child mission is shutdown using
shutdown()
.Any resources that were setup using
setup_base()
should be considered for shutdown using this method.
ChainWithTimeout¶
- mil_missions_core.MakeChainWithTimeout(base: Type)[source]¶
Generate a
ChainWithTimeout
mission with the BaseMission specified. Used by individual robotics platforms to reuse this example mission.For documentation on the
ChainWithTimeout
class, you will need to view the source code.- Parameters
base (Type) – A base class to use when constructing the
ChainWithTimeout
class.- Returns
The constructed class.
- Return type
ChainWithTimeout
Exceptions¶
- class mil_missions_core.MissionException(message, parameters=None)[source]¶
An exception representing a general error which occurred during the execution of a mission.
- parameters¶
???
- Type
Dict[Any, Any]
- class mil_missions_core.TimeoutException(timeout: Union[float, int])[source]¶
Represents an exception from a mission or submission not finishing within the requested time.
Inherits from
Exception
.- str(x)
Prints an explanatory error message using the provided timeout.
- class mil_missions_core.ParametersException(msg: str)[source]¶
Represents an exception from a mission or submission where the mission’s parameters had an error or inconsistency.
Inherits from
Exception
.- str(x)
Prints an explanatory error message using the provided message explaining what error occurred.
- class mil_missions_core.SubmissionException(mission: BaseMission, exception: Exception)[source]¶
Represents an exception encountered while running a submission.
Keeps the name of the submission which failed, so the user knowns where the failure occurred.
Inherits from
Exception
.- str(x)
Prints an explanatory error message using the provided mission name and exception that occurred.
MissionClient¶
- class mil_missions_core.MissionClient[source]¶
Extends SimpleActionClient to do bootstrap of making a mission client for you.
- classmethod available_missions() Any | None [source]¶
Returns a list of available missions or None if parameter is not set.
- Returns
The list of available missions. This is typed as Any currently because it is not yet known what type is returned by the parameter request.
- Return type
Optional[Any]
- run_mission(mission: str, parameters: str = '', done_cb: Callable[[int, Any], None] | None = None, active_cb: Callable[[], None] | None = None, feedback_cb: Callable[[Feedback], None] | None = None) None [source]¶
Send a goal to start a new mission with the specified parameters.
- Parameters
mission (str) – The name of the mission to start.
parameters (str) – The parameters to send to the mission. Defaults to an empty string.
done_cb (Optional[Callable[[int, Any], None]]) – The callback function to send to the action client to execute when the goal is done. The callable should take two parameters: an integer (specifically, an enumerated integer value from
actionlib_msgs.msg._GoalStatus.GoalStatus
) and the result.active_cb (Optional[Callable[[], None]]) – The callback function that gets called on transitions to an active state.
feedback_cb (Optional[Callable[[Any], None]]) – Callback that is executed when feedback for the goal is received. The callback should take one parameter: the feedback received.
MakeWait¶
- mil_missions_core.MakeWait(base: Type)[source]¶
Create a Wait mission with the specified base mission. Used by robotics platforms to reuse this mission with a different base mission.
- Parameters
base (Type) – The base class to construct the Wait mission from.
- Returns
The constructed waiting mission.
- Return type
Wait