Pilot
The Pilot domain provides main components of a modular navigator for mobile robots. The Pilot consists of a core library that contains all main classes and interfaces that are used by the separate modules.
The actual functionality of the navigator is located in different plugins. Each plugin is compiled into a separate library. The plugin concept allows to combine different algorithms to create a navigation solution that is customized for the specific application.
Most important plugins are Motion Planners, like the Dynamic Window Approach (DWA). Many motion planners that compute a cost function within the velocity space (e.g. DWA) can be modularized themselves. Those modules are called "objectives". The purpose of objectives is to evaluate motion trajectory candidates generated by the motion planner according to the current robot state. Each objective votes for a certain trajectory by computing a cost value. The cost values of all active objectives are accumulated and finally, the trajectory that yields the smallest summed cost is chosen to determine the next motion command.
In the following the channels and services are described that are required by the Pilot core unit. The used motion planner, path planner and each used objective may require additional channels and services. These are listed below.
Channels
Subscribed
Published
- PilotEvent (std::string)
The status of the navigation system. One of the following values:
- Indicating idle state:
- 'Idle': no task set, nothing to do
- Indicating routine operation:
- 'PlanAndDrive': moving according to the current task
- Indicating success:
- 'GoalReached': task has been reached
- Indicating special states or events, still trying to succeed:
- 'PathTemporarilyLost': path planner had a path to goal but does not have one currently (path got blocked)
- 'WaitForData': waiting for required (channel) data
- 'Recover': Pilot trying to recover to overcome dissatisfaction of objective(s)
- Indicating failure (task cancelled):
- 'NoPathPlannable': path planner did not have a path to goal for too long
- 'NoValidMotionCommand': local motion planner cannot find a valid command
- 'NoData': task failed because required (channel) data was missing
- 'TaskError': error setting task
- 'TaskFailed': task failed for other reason (usually not a goal task)
- 'RecoveryFailed': recovery failed
- 'UnknownError': task failed for unhandled error
- Task (boost::shared_ptr<mira::navigation::Task>)
The current navigation task
- debug/Acceleration (mira::Velocity2)
The requested acceleration for the next cycle
- debug/Velocity (mira::Velocity2)
The requested velocity for the next cycle
Services
Required
- IDrive
- void setVelocity(mira::Velocity2)
- IRobotModelProvider
- boost::shared_ptr<RobotModel> getRobotModel()
Published
- INavigation
- void setGoal(mira::Pose2, float, float)
- Set a goal position with translational(meter) and rotational(radian) tolerance
- void setTask(boost::shared_ptr<mira::navigation::Task>)
- Set a new task. NULL resets task and stops navigation
- void repeatTask()
- Repeat the last task (if any)
- void setMute(bool)
- Mutes/Unmutes the navigation system (mute = driving commands are computed but setVelocity is not called)
- void setDriveService(const std::string&, const mira::Duration&)
- Change the drive service to be used
- void setRecoverTask(boost::shared_ptr<mira::navigation::Task>)
- Go into recovery state and set a new task for recovery
Parameters
- ModelProvider (std::string)
The name of the service that provides a robot model (if empty, a suitable service is chosen automatically).
- DriveService (std::string)
The name of the service that is used for setting the velocity (if empty, a suitable service is chosen automatically).
- CPUUsage (float) [property]
The cpu usage in percent (default: 90%).
- Mute (bool) [property]
If enabled, then the robot does not send drive commands (default: false).
- UseRecovery (bool) [property]
Are recovery strategies enabled (default: false).
- Planner (mira::pilot::AbstractPlanner) [property]
The motion planner that is used by the navigator.
- RecoveryStrategies (std::map<int, mira::navigation::TaskPtr>) [property]
The recovery strategies used by the navigator.
The task based system
Based on the modular concept of objectives, the navigator offers a suitable interface that allows to specify complex tasks. In order to develop a highly generic navigator, we use a task based system which allows to define jobs consisting of several sub-tasks and their corresponding parameters. To meet the requirements of different applications, many sub-tasks are defined that can be combined to create complex tasks, the most important are:
- driving to a specified position using a path planner
- avoid collisions and keep distance to obstacles
- adjust the orientation at the goal point (e.g. to face a user)
- docking with a charging station
- follow a moving goal (e.g. tracked person)
- follow a specified path
- explore the environment autonomously while avoiding obstacles
- drive a maximum allowed distance
- maintain speed limits
Each sub-task can be parameterized by numerous task specific options, including:
- goal point to drive to,
- preferred driving direction of the robot (backward, forward or both)
- accuracy for reaching a goal point
- accuracy for the orientation angle at a goal point
- maximum allowed driving distance (e.g. during exploration) By specifying a combination of sub-tasks and their parameters the robot’s navigation behavior can be completely modified at runtime.
To fulfill the job, the navigator must complete each sub-task by following the specified rules and options. Moreover, the task based system allows for the addition of new sub-tasks in the future, when required, without changing the interface of existing tasks or interfering with existing applications. This is an important advantage of this task based design since it reduces the effort necessary for software maintenance.
An overview of basic task definitions can be found in the documentation of toolbox Navigation (SubTasks).
Objectives are automatically activated or deactivated upon a new task based on the contained subtasks they "understand" when using a planner derived from the AbstractObjectiveBasedPlanner.
mira::pilot::AbstractObjectiveBasedPlanner
This is the base class for all objective based planners. It provides an interface for managing objectives and defines some basic parameters. It automatically distributes a task to all active objectives, collects their votes and assigns planning times. It needs a robot model that is at least a subclass of mira::robot::UnicycleBasedRobotModel.
Services
Published
- void enableObjective(std::string, bool)
- Enables/Disables an objective
Parameters
- PlanningHorizon (mira::Duration) [property]
The planning horizon [ms]. It should be equal to or larger than the Pilots cycle time.
- MinLookAhead (mira::Duration) [property]
The minimum look ahead time.
- MaxLookAhead (mira::Duration) [property]
The maximum look ahead time. Based on the current translation speed of the robot a look ahead time is interpolated between the min and max look ahead times.
- TrajectorySamples (int) [property]
Number of samples along the predicted trajectory.
- MaxNoCommandTime (mira::Duration) [property]
How long is it allowed to have no valid velocity command.
- Objectives (std::list<mira::pilot::AbstractObjectiveBasedPlanner::ObjectiveInfo>) [property]
The list of used objectives.
mira::pilot::AbstractDynamicWindow
One of the most often used algorithms for anticipatory motion planning is the Dynamic Window Approach. This algorithm searches for the optimal motion command directly in the space of velocities. Therefore, the robot’s two dimensional velocity space is discretized into regular two dimensional cells where each cell represents a certain trajectory. Each cell is assigned a cost function. Finally, the velocities corresponding to the cell that yields the smallest costs are chosen as motion commands. In these computations the Dynamic Window Approach takes the robot’s dynamic into account by reducing the search space to those velocities which are reachable under the dynamic constraints such as limited speed and acceleration. Additionally, only velocities are considered that are safe and do not lead to collisions. As stated before, each cell covers a certain area of the velocity space and corresponds to a certain velocity command. For motion planning, a cost function is computed for each cell and therefore the velocity command that yields the smallest cost is chosen. For each cell of the adaptive dynamic window within the dynamic constraints of the robot, each objective is called to compute its cost value ci for that cell or to mark the associated action as “not admissible”. In the latter case the computation for the cell is aborted immediately to save computation time. The final overall cost of each cell is then computed by the weighted sum of the returned cost values ci of all objectives.
The base class of all dynamic window based algorithms (mira::pilot::AbstractDynamicWindow) implements a mira::pilot::AbstractObjectiveBasedPlanner and already provides most of the functionality and data structures needed for a dynamic window approach.
Channels
Published
- debug/DynamicWindow (mira::pilot::AbstractDynamicWindow::Config)
Contains the current state of the dynamic window including all reachable velocity cells with their costs and votes of each objective as well as the best action. Mostly used for debugging.
- debug/Trajectories (mira::pilot::TrajectoryFamily)
The current trajectories generated using trajectory rollout. For each trajectory it contains the trajectory (vector of poses) as well as the cost.
mira::pilot::DynamicWindow
This class implements a mira::pilot::AbstractDynamicWindow and builds up a cell structure that uses two different sizes and resolutions for rotational dimension (DWA y-Axis) and translational dimension (DWA x-Axis).
Parameters
- TransVelocityResolution (float)
Resolution of the cells in translational dimension [m/s^2]
- RotVelocityResolution (float)
Resolution of the cells in rotational dimension [deg/s^2]
- TransSize (int)
Number of cells in translational velocity dimension
- RotSize (int)
Number of cells in rotational velocity dimension
Distance objective
This objective is activated by default. It forbids trajectories that would lead to a collision of the robot with obstacles. It can be disabled by setting the subtask mira::navigation::IgnoreObstaclesTask. It optionally limits the robots translation to a given maximum safety speed when a safety zone is defined around the robot and a trajectory would lead to a collision of this zone with an obstacle.
The robot's rigid model is used to determine the footprint of the robot. This footprint will be checked against collisions in an occupancy grid map (typically a local map with high update rate, e.g. created from laser readings). Collision representations with name "SafetyZone" in the robot's rigid model are used to get the optional safety zone footprint of the robot.
<link name="RobotFrame">
<collision>
<include
file=
"MyRobots-footprint.xml" />
</collision>
<collision name="SafetyZone">
<geometry>
<cylinder length="0.001" radius="0.75" />
</geometry>
</collision>
</link>
In the above example the geometry defined in the file "MyRobots-footprint.xml" is used for normal collision detection whereas the cylinder defined in the collision representation with name "SafetyZone" will be used as a safety zone around the robot for limiting the robot's speed when an obstacle violates this zone.
In addition to just avoiding collisions, the Distance objective can be used to actually keep a defined minimum distance to obstacles, using a KeepDistanceTask. In contrast to collision avoidance, the distance is not calculated with respect to the exact robot shape, but assumes a circular shape (with a configurable radius, by default the robot's outer radius). The minDistance parameter from the KeepDistanceTask will be used to deny trajectories getting closer to obstacles than this limit, while undershooting the criticalDistance will be interpreted as another moving object actively approaching the robot and result in signalling dissatisfaction (Reason: Interference). In praxis, both thresholds are dynamically adapted continuously, regarding the obstacle distance at the current position and the obstacle distance at the (planned) target position (if in reach). This will account for measurement noise and allow reaching (and leaving) targets although they are closer to the next obstacle than the KeepDistanceTask would permit.
The desiredDistance parameter in KeepDistanceTask can be set to a value higher than minDistance to assign an additional cost if a trajectory's obstacle distance is between minDistance and desiredDistance. This needs good balancing with other costs e.g. from PathObjective though and is discouraged for all but the most experienced (or experimentally inclined) users.
Channels
Subscribed
- LocalMap (mira::maps::OccupancyGrid)
The local occupancy grid map that should be used for obstacle collision checks.
- Path (std::vector<mira::Point2f>)
The path planned by the path objective (see below).
Published
- debug/DistanceMap (mira::Img8U3)
The distance transformed collision map containing a trajectory of robot shapes (based on the trajectory chosen by the motion planner).
- debug/Shape (mira::Img<>)
The shape at the current position used for collision testing.
Parameters
- DistanceLimitForCosts (float) [property]
Max. distance in m that is used for the cost function. Distances > DistanceLimitForCosts are not taken into account.
- CollisionTest (mira::model::CollisionTest) [property]
Model for collision testing.
- RotationIgnoresCollision (bool) [property]
Ignore collision test of robot footprint to obstacle for purely rotational action. Collision test involves rotating a grid and is therefore prone to inaccuracies, sometimes denying rotation when obstacles are close but not actually colliding. This property provides a workaround for robots whose shape is invariant to rotation.
- MaxSafetyZoneTransVelocity (float) [property]
Maximum translation velocity if an obstacle violates robot's defines safety zone (if any).
- MaxMapAge (mira::Duration) [property]
Maximum age of collision test map.
- DbgUpdateInterval (mira::Duration) [property]
How often is the debug map updated.
- KeepDistanceRadius (float) [property]
Robot radius assumed when calculating obstacle distance for KeepDistanceTask (<0 -> use footprint's outer radius). Values smaller than the model's inner radius are invalid.
- PassiveThresholdMargin (float) [property]
Margin maintained between active and passive obstacle distance thresholds when they are reduced below values from KeepDistanceTask (due to goals being closer to obstacles).
- MaxObstacleBelowMinDistTime (mira::Duration) [property]
Maximum time spent closer than KeepDistanceTask::critialDistance to an obstacle before dissatisfaction.
- ActiveThreshold (float) [property]
Current obstacle distance threshold for active motion (read-only).
- PassiveThreshold (float) [property]
Current obstacle distance threshold for objects moving up to us (read-only).
Path objective
This objective is activated by the subtask mira::navigation::PositionTask. It plans a path on the global map and votes for following the path to the goal area.
Channels
Subscribed
- InitCostMap (mira::maps::GridMap<double>)
Final cost mapper stage's init map (see CostMapperMainPage). This is just used to trigger a full path planner update when one of the cost mappers' init maps changes.
- CurrentCostMap (mira::maps::GridMap<double>)
Cost mapper's final cost map (after updates by all cost mapper stages). "Dirty regions" are queried for this map from the cost mapper to update the path planner as needed.
- LocalMap (mira::maps::OccupancyGrid)
Optionally used to check if the planned path is free with a collision check.
Published
- Path (std::vector<mira::Point2f>)
The planned path
- debug/NavStatus (mira::maps::GridMap<uint8,3>)
The planning status of the planning map/navigation function (for debugging purposes).
- debug/NavStatusActual (mira::maps::GridMap<uint8,3>)
Same as NavStatus, but circumventing doublebuffering (if active), so this is always the actual data in the path planner.
- debug/NavFunctionNearGoal (mira::maps::GridMap<uint8,3>)
This shows a high resolution rendering of the navigation function in close proximity of the goal point, which can be used to achieve sub-cell resolution goal accuracy (if active).
Transforms
- Needs transform between odometry frame id and the frame id of the costmap.
Parameters
- CostMap (std::string)
The identifier for the used cost map in the cost mapper.
- UseRelativeCosts (bool) [property]
Compute costs using the navigation function relative to the current position instead of using the absolute values of the navigation function. This actually should be the better choice for a generic navigation framework, but unfortunately causes undesired effects in practice
- UseFilteredValue (bool) [property]
Is interpolation between the cell values in the planner map enabled. This is necessary to enable sub-cellsize goal accuracy.
- NoPlanCosts (float) [property]
Cost that is returned for an action leading into a yet unplanned region in the nav function. <=0 means strictly DENY.
- DissatisfactionTime (mira::Duration) [property]
Time until dissatisfaction is signalled if not moving.
- OscillationTimeout (mira::Duration) [property]
Time until dissatisfaction is signalled if not progressing forward.
- OscillationTranslationThreshold (float) [property]
Minimum translational progress required before OscillationTimeout to avoid dissatisfaction.
- ResetCostMapsOnNewTask (bool) [property]
Whether to reset cost maps when a new task is set (if true, calls initMaps() on cost mapper on setTask()).
- Planner (mira::navigation::EstarPlanner) [property]
The global path planner
- DbgUpdateInterval (mira::Duration) [property]
The update interval for debug info (NavStatus etc.)
- DbgCostsInGoalRegion (bool) [property]
Show nav function value in goal region (if false, goal region is marked flat green)
- CollisionTestEnabled (bool) [property]
Use collision test on LocalMap along planned path.
- CollisionTest (mira::model::CollisionTest) [property]
Model for collision testing.
- MaxPathBlockedTime (mira::Duration) [property]
Time to wait before replanning if a collision is detected on the path.
- PathCollisionLookAhead (float) [property]
Distance to llok for collisions along the path.
Heading objective
This objective is activated by the subtask mira::navigation::OrientationTask. It will rotate the robot to face into the given direction. When combined with the Path objective the robot will first drive to the given goal and then rotate to face the given direction.
The HeadingObjective provides two methods of recovery. The first one is RecoveryMode::SetDissatisfaction, which corresponds to the standard Pilot recovery mechanisms. The second one is RecoveryMode::TurnAway. In this mode the robot turns away from the goal orientation and tries to reach it from the other side.
Transforms
- Needs transform between odometry frame id and the frame id specified in the task.
Parameters
- RecoveryMode (mira::pilot::HeadingObjective::RecoveryMode) [property]
How to recover if not moving.
- DissatisfactionTime (mira::Duration) [property]
Time until recovery meassures are taken if not moving.
- RequireZeroRotVelocityAtGoal (bool) [property]
Additionally require the rotational velocity to be 0 at the goal.
Direction objective
This objective is activated by the mira::navigation::PreferredDirectionTask. It implements the preferred or prohibited driving directions of a robot.
Channels
Subscribed
- Path (std::vector<mira::Point2f>)
The currently planned path (optional).
Parameters
- DistanceFactor (float) [property]
Factor for weighting driving into the wrong direction.
- MinWrongDirectionCost (float) [property]
Minimum cost for driving into wrong direction.
- HeadingWeight (float) [property]
The additional cost that is caused by a wrong heading direction that does not point along the path to the goal, should be as small as possible.
- MaxWrongDistance (float) [property]
Maximum distance we are allowed to drive into non preferred direction in meter.
- AvoidTurnNearGoal (bool) [property]
Allow driving into wrong direction when already close to goal.
- MaxPathAge (mira::Duration) [property]
Maximum admissible age of the path.
Mileage objective
This objective is activated by the subtask mira::navigation::MileageTask. The task is reached if the robot has driven a given mileage since the task was activated. It can be used together with the Explore objective.
Channels
Subscribed
- Mileage (float)
The absolute driven distance of the robot in meter.
Explore objective
This objective is activated by the subtask mira::navigation::MileageTask. It tries to drive with a maximum given speed and can be used to explore an area. Can be used together with the Mileage objective to stop after a given distance.
Needs a differential robot model to work.
Parameters
- MaxExploreVelocity (float) [property]
Maximum velocity for exploring.
- MaxInplaceRotationalVelocity (float) [property]
Maximum rotation velocity for in-place rotation.
RemoteControl objective
Allows to set a velocity the robot should drive, while still e.g. performing obstacle avoidance.
Services
Published
- IDrive
- void setVelocity(mira::Velocity2)
Speed objective
The objective reads regional translation speed limits from a speed map and makes sure the robot observes them. If a VelocityTask is set, it also limits the velocities (translatio nand rotation) accordingly. Limits apply to the absolute values of the robot velocity.
Channels
Subscribed
- <ChannelName> (mira::maps::OccupancyGrid)
Map defining translation speed limits for each cell, as a fraction between LowerSpeed and UpperSpeed
- SpeedMapAbsolute (mira::maps::GridMap<float>)
Map defining translation speed limits for each cell, as absolute speed value
- SpeedLimit (mira::Velocity2)
Global speed limit (translation and rotation)
Parameters
- Map (std::string)
Speed map channel name.
- LowerSpeed (float) [property]
Translation speed limit corresponding to black value in map.
- UpperSpeed (float) [property]
Translation speed limit corresponding to white value in map.
Follow a predefined path
The purpose of the PathFollowObjective is to set an entire path in the task, which the robot will follow point by point.
Channels
Published
- FollowPath (std::vector<mira::Pose2>)
Path given in the task.
- Markers (mira::model::Marker)
Mark the current path point.
Parameters
- PathWeight (float) [property]
Weight factor for distance to path.
- GoalWeight (float) [property]
Weight factor for distance to goal.
- HeadingWeight (float) [property]
Weight factor for heading distance.
- LookAheadFactor (float) [property]
Multiplier for motion planner's standard lookahead time.
- HeadingSmoothAngle (float) [property]
Cutting a curve is allowed for path changes up to this angle.
- PathPointDensity (float) [property]
Desired point density, achieved by interpolation.
- EnableMarkers (bool) [property]
Whether to publish debug markers.
Set a task
The following examples assume, that the Pilot is located in the namespace /navigation.
Use MiraCenter
In miracenter you can open a 3d view, add visualizations of the used map, the RobotFrame or a visualization of the robot's rigid model and optionally some sensor data (e.g. laser). This will give you an idea of where the robot is localized in the map. Then select the GoalTool and click at a point in the map (note: the position must be reachable, free and not be located in a nogo area). The robot will start navigating to the selected position. You can change the GoalTool's preferences in the 3D view's property editor (Visualization Control), in General->Tools.
Use the C++ RPC interface
To set a task one needs to create a "task container" and add one or more subtasks (see The task based system). The required headers for the different tasks can be found in the toolbox Navigation, so you need to add MIRA_REQUIRE_PACKAGE(Navigation) to your package or CMake file and link against the lib Navigation.
In the following example we create a task that will send the robot to position x:0 and y:5 (with a tolerance of 0.3 - 0.2 meter) facing direction 180° (with a tolerance of 15°) when reaching this point. Additionally we only want to allow forward motion. The example code assumes that it is placed somewhere inside a Unit or MicroUnit class.
...
class MyUnit : public MicroUnit {
...
void setTask()
{
callService<void>("/navigation/Pilot", "setTask", task);
}
...
};
If the namespace of the Pilot service is unknown, the following code can be used to discover the INavigation interface:
void setTask()
{
...
auto providers = queryServicesForInterface("INavigation");
if(providers.empty())
return;
const std::string service = providers.front();
auto rpcFuture = authority->callService<void>(service, "setTask", task);
rpcFuture.get();
}
Use the RPC console
Within miracenter, the RPC console can be used to set a new task.
The simplest way to set a new goal is to use the setGoal method:
/navigation/Pilot.setGoal({ "X": 0.0, "Y": 5.0, "Phi": 180.0 }, 0.2, 0.3)
Furthermore, also the method setTask can be used:
/navigation/Pilot.setTask({
"SubTasks" : [
{
"@class" : "mira::navigation::PositionTask",
"MaxTolerance" : 0.2,
"MinTolerance" : 0.1,
"Position" : {
"X" : 2.0,
"Y" : 0.0
}
},
{
"@class" : "mira::navigation::OrientationTask",
"Orientation" : 180,
"Tolerance" : 15
},
{
"@class" : "mira::navigation::PreferredDirectionTask",
"Direction" : 1,
"WrongDirectionCost" : 0.5
}
]
})
(Please note: The example above must be put into one line in the RPC console!)
Use the JSON RPC interface
The JSON-RPC interface can be used via the WebServer (e.g. JavaScript) or via the RPCView or RPCConsole in miracenter. To set a task one needs to create a "task container" and add one or more subtasks (see The task based system). In the following example we create a task that will send the robot to position x:0 and y:5 (with a tolerance of 0.3 - 0.2 meter) facing direction 180° (with a tolerance of 15°) when reaching this point. Additionally we only want to allow forward motion.
method = "/navigation/Pilot.setTask";
param = {"SubTasks" : [
{
"@class" : "mira::navigation::PositionTask",
"MaxTolerance" : 0.3,
"MinTolerance" : 0.2,
"Position" : {"X" : 0.0,"Y" : 5.0}
},
{
"@class" : "mira::navigation::OrientationTask",
"Orientation" : 180,
"Tolerance" : 15.0
},
{
"@class" : "mira::navigation::PreferredDirectionTask",
"Direction" : 1,
"WrongDirectionCost" : 0.5
}
]};
callService(method, JSON.stringify(param));