This toolbox contains datatypes, classes and tasks, which are necessary to access a task based navigation system.
INavigation Interface
The INavigation interface should be implemented by any task based navigation system. It provides a clean API for setting a navigation task and exports its methods as a service for RPC.
The navigation system that implements INavigation should call MIRA_REFLECT_BASE(r, INavigation) in its reflect method.
Tasks
Task based navigation systems are marked by their object oriented approach. They are modular and can be extended by adding new types of tasks that derive from a task base class.
In our approach of a task based navigation system the overall task consists of one or multiple subtasks. Each subtask is handled by a different sub module of the navigation system. The overall task is reached when all of its subtasks are completed.
The class Task class acts as such a container for subtasks. It allows adding of new subtasks as well as retrieving a subtask of a certain type.
The class SubTask is the base class for all kinds of sub goals that can be added to the overall task. Subtasks must be registered at the class factory and need to be serializable since they can be passed as items of a task via RPC to the navigation system.
There exist already some predefined subtasks for our navigation system that can be combined to form complex tasks.
E.g. the complex task for driving exclusively FORWARD to position x=10, y=0 (tolerance 10cm) facing an orientation of 90° (tolerance 15°) at the target position can be achieved with the following code:
class MyUnit : public MicroUnit {
...
void setTask()
{
std::string navService = waitForServiceInterface("INavigation");
callService<void>(navService, "setTask", task);
}
};
SubTasks
The following subtasks are supported by the navigation toolbox. The JSON syntax for each subtask is given to facilitate their use through the JSON RPC interface (e.g. with RPC console, mirainspect etc.).
PositionTask
The PositionTask is designed for driving to a given position providing two limits for a hysteresis that can be applied when checking for goal reached. The minimum tolerance is the distance where the path planner stops driving nearer to the given position. The maximum tolerance is the maximum allowed distance to the given position. When this distance is exceeded the path planner starts again driving nearer to the position until the minimum distance is reached again....
Parameters:
- Position (mira::Point2f)
The request position.
- MinTolerance (float)
The minimum tolerance/lower limit for path planner hysteresis.
- MaxTolerance (float)
The maximum tolerance/upper limit for path planner hysteresis.
- FrameID (std::string)
The frame the position is related to. Default = "/GlobalFrame".
JSON representation:
{
"@class" : "mira::navigation::PositionTask",
"FrameID" : "/maps/MapFrame",
"MaxTolerance" : 0.3,
"MinTolerance" : 0.2,
"Position" : {"X" : 0.0, "Y" : 5.0}
}
OrientationTask
The OrientationTask has the purpose to reach a given orientation with no more deviation than the given tolerance.
Parameters:
- Orientation (mira::Anglef)
- The requested orientation.
- Tolerance (mira::Anglef)
- FrameID (std::string)
The frame the angle is related to. Default = "/GlobalFrame".
JSON representation:
{
"@class" : "mira::navigation::OrientationTask",
"FrameID" : "/maps/MapFrame",
"Orientation" : 180,
"Tolerance" : 15.0
}
PreferredDirectionTask
The PreferredDirectionTask has the purpose of limiting the direction the robot drives.
Parameters:
- Direction (mira::navigation::PreferredDirectionTask::Direction)
The preferred direction (0 = both, 1 = forward, -1 = backward).
- WrongDirectionCost (float)
Costs for driving into not-preferred direction. Setting this >= 1.0 makes the non-"preferred" direction forbidden! Default = 1.0.
JSON representation:
{
"@class" : "mira::navigation::PreferredDirectionTask",
"Direction" : 1,
"WrongDirectionCost" : 0.5
}
DockingTask
The DockingTask is designed for docking to a given position with a given orientation.
Parameters:
- Pose (mira::Pose2)
Position and orientation of the desired docking position.
- Tolearance (mira::Pose2)
The tolerance for docking.
- GoalFrame (std::string)
The frame of the goal.
JSON representation:
{
"@class" : "mira::navigation::DockingTask",
"GoalFrame" : "/GlobalFrame",
"Pose" : {"X" : 0.0, "Y" : 5.0, "Phi" : 5},
"Tolerance" : {"X" : 0.04, "Y" : 0.02, "Phi" : 1}
}
KeepDistanceTask
The KeepDistanceTask is designed to keep a specified distance to obstacles. Obstacles are not "just" avoided but the robot tries to stay away from them in the specified distance.
Parameters:
- MinDistance (float)
The minium distance to keep from obstacles. Default = 0.0.
- DesiredDistance (float)
The desired distance to keep from obstacles. Default = 0.0.
- CriticalDistance (float)
The critical distance that triggers a recovery behaviour. Default = 0.0. The critical distance should be lower than minimum distance. That way, the robot can not reach a critical distance by itself, but an object can come closer than critical distance if it is moving towards the robot.
JSON representation:
{
"@class" : "mira::navigation::KeepDistanceTask",
"DesiredDistance" : 0.5,
"MinDistance" : 0.2,
"CriticalDistance" : 0.1
}
MileageTask
The MileageTask has the purpose to drive at least a given mileage before the task is done. The mileage is given as an absolute value.
Parameters:
- Mileage (float)
The requested mileage in [m].
JSON representation:
{
"@class" : "mira::navigation::MileageTask",
"Mileage" : 5.0
}
VelocityTask
The VelocityTask has the purpose to limit the speed of the robot during navigation.
Parameters:
JSON representation:
{
"@class" : "mira::navigation::VelocityTask",
"Velocity" : {"X" : 0.6, "Y" : 0.0, "Phi" : 30}
}
PersonApproachTask
The PersonApproachTask is designed for approaching a person in a certain distance.
Parameters:
- MinDistance (float)
The minimum distance to the person in [m].
- MaxDistance (float)
The maximum distance to the person in [m].
- OrientationTolerance (float)
The allowed tolerance for orientation in [rad].
JSON representation:
{
"@class" : "mira::navigation::PersonApproachTask",
"MaxDistance" : 1.0,
"MinDistance" : 0.6,
"OrientationTolerance" : 20
}
PersonFollowTask
The PersonFollowTask is designed for driving to a certain distance to a person (person following).
Parameters:
- MinDistance (float)
The minimum distance to the person in [m].
- MaxDistance (float)
The maximum distance to the person in [m].
- OrientationToPerson (float)
The desired orientation of the followed person relative to the robot frame in [rad].
- OrientationTolerance (float)
The allowed tolerance for orientation in [rad].
JSON representation:
{
"@class" : "mira::navigation::PersonFollowTask",
"MaxDistance" : 1.0,
"MinDistance" : 0.6,
"OrientationToPerson" : 45,
"OrientationTolerance" : 20
}
RemoteControlTask
The RemoteControlTask enables remote controlling of a robot via the navigation system. Therefore the requested driving commands of the user should be followed as close as possible while using obstacle avoidance features. Can be combined with the IgnoreObstaclesTask to disable obstacle avoidance.
This subtask has no parameters.
JSON representation:
{
"@class" : "mira::navigation::RemoteControlTask"
}
IgnoreObstaclesTask
The IgnoreObstaclesTask has the purpose to DISABLE the local obstacle avoidance. This subtask should be set only if there is no risk for any collision, or where the collision check must be disabled in order to approach obstacles very closely, e.g. when docking on.
This subtask has no parameters.
JSON representation:
{
"@class" : "mira::navigation::IgnoreObstaclesTask"
}
RotateTask
The RotateTask commands a rotation in place. In contrast to the OrientationTask it defines the amount of rotation, not the target orientation.
A positive angle means positive = counter-clockwise rotation.
Parameters:
- Angle (float)
- How much (and which direction) shall the robot rotate [deg]. Default=180.0;
- Speed (float)
- How fast shall the robot rotate [positive deg/s]. Default=30.0;
JSON representation:
{
"@class" : "mira::navigation::RotateTask",
"Angle" : 180.0,
"Speed" : 30.0
}
PathFollowTask
The PathFollowTask is used to command following a path defined by waypoints. It consists some general control parameters and a list of waypoints.
Parameters:
- Precision (float)
- The precision for following the path (max. distance from path) [m]. Default=0.25;
- GoalTranslationTolerance (float)
- The position tolerance for reaching the goal point [m]. Default=0.1;
- GoalOrientationTolerance (mira::Anglef)
- The orientation tolerance for reaching the goal point [deg]. Default=10.0;
- FrameID (std::string)
- The coordinate frame of the points. Default='/GlobalFrame';
- Points (std::vector<Pose2>)
- Waypoints (control points of the spline));
JSON representation:
{
"@class" : "mira::navigation::PathFollowTask",
"Precision" : 0.25,
"GoalTranslationTolerance" : 0.1,
"GoalOrientationTolerance" : 10.0,
"FrameID" : "/maps/MapFrame",
"Points" : [ { "X" : 0.1, "Y" : 0.3, "Phi" : 10 },
{ "X" : 0.3, "Y" : 0.4, "Phi" : 20 } ]
}
VelocityWaypointTask
The VelocityWaypointTask is very similar to the PathFollowTask, except that its waypoints describe a position and individual translation velocity.
Parameters:
- Precision (float)
- The precision for following the path (max. distance from path) [m]. Default=0.25;
- GoalTranslationTolerance (float)
- The position tolerance for reaching the goal point [m]. Default=0.1;
- GoalOrientationTolerance (mira::Anglef)
- The orientation tolerance for reaching the goal point [deg]. Default=10.0;
- FrameID (std::string)
- The coordinate frame of the points. Default='/GlobalFrame';
- Points (std::vector<VelocityWaypoint>)
- Waypoints, including velocity [m/s]);
JSON representation:
{
"@class" : "mira::navigation::VelocityWaypointTask",
"Precision" : 0.25,
"GoalTranslationTolerance" : 0.1,
"GoalOrientationTolerance" : 10.0,
"FrameID" : "/maps/MapFrame",
"Points" : [ { "Pos": { "X" : 0.1, "Y" : 0.3 }, "vT" : 0.1 },
{ "Pos": { "X" : 0.3, "Y" : 0.3 }, "vT" : 0.2 } ]
}
RestrictAreaTask
The RestrictAreaTask is used to restrict movement to an area.
Parameters:
- RestrictingAreas (std::vector<Polygon2f>)
- Container for restricting areas. Movement is restricted to the union over that container;
- FrameID (std::string)
- The coordinate frame of the areas. Default='/GlobalFrame';
JSON representation:
{
"@class" : "mira::navigation::RestrictAreaTask",
"FrameID" : "/maps/MapFrame",
"RestrictingAreas" : [[{"X":-1,"Y":-1},{"X":1,"Y":-1},{"X":1,"Y":6},{"X":-1,"Y":6}]]
}