Skip to content

alex-lotz/TestRepo

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

20 Commits
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

SmartCdlServer Component

SmartCdlServer-ComponentImage

Component Short Description: The SmartCdlServer is based on the Curvature Distance Lookup (CDL) algorithm for fast local obstacle avoidance.

Component Documentation

The SmartCdlServer is based on the Curvature Distance Lookup (CDL) algorithm for fast local obstacle avoidance.

The CDL algorithm is an improvement of the dynamic window approach. It considers the dynamics and kinematics of the robot, as well as its polygonal shape. It consumes raw laser scans or other sensor perceptions transformed into occupancy grids. The basic idea is that a robot moves along different curvatures (v, w combinations) which represent trajectories built up by circular arcs. The huge number of possible v, w combinations is reduced based on the observation that only a few curvatures are safely selectable given the current state and kinematics of the robot. Curvatures leading to a collision are discarded. High performance advantages are achieved by precalculating lookup tables. The final selection along the remaining admissible v, w combinations is done by an objective function, which trades off speed, goal-directedness and remaining distance until collision.

This objective function together with its weighting factors build different strategies, such as reactive driving, joystick navigation, rotating or approaching goals. The strategies are used for the selection of the best-fitting curvature with respect to the purpose of the strategy. Example strategies are passing over intermediate waypoints, approaching a goal given by a path-planner or following a person.

The SmartCdlServer will read files which contain precalculated lookup tables generated by smartCdlCalculate utility (see SmartSoft UtilityRepository). They contain the kinematics of the robot.

SmartCdlServer supports differential drive, synchro drive and omnidrive if neglecting lateral velocity.

Note: This component is used in Tutorials (e.g. Lesson 1).

See also: Christian Schlegel. Fast local obstacle avoidance under kinematic and dynamic constraints for a mobile robot. In Proc. Int. Conf. on Intelligent Robots and Systems (IROS), p. 594-599, Victoria, Canada, 1998.

Component-Datasheet Properties

Table: Component-Datasheet Properties
Property Name Property Value Property Description
SpdxLicense LGPL-2.0-or-later https://spdx.org/licenses/LGPL-2.0-or-later.html
TechnologyReadinessLevel TRL5
Homepage http://servicerobotik-ulm.de/components
Supplier Servicerobotics Ulm
Purpose Navigation
Memory 20000 KB
Capability CollisionAvoidance

Component Ports

LaserClient

Documentation: Incoming laser scans that the CDL algorithm uses for obstacle avoidance, e.g. from SmartLaserLMS200Server

Table: Datasheet Properties of Component-Port LaserClient
Property Name Property Value Property Description
CoordnateDimensions 2D

LaserClient2

Documentation: Second (optional) laser client allows using two laser-scanners concurrently

PlannerClient

Documentation: Goals from planner (e.g. smartPlannerBreathFirstSearch) can be sent to this port

NavVelSendServer

Documentation:

Navigation commands v and w sent via this port will be considered when chosing a trajectory.

This port can be used to ensure collision free navigation while following incoming navigation commands from e.g. a joystick (e.g. SmartExampleJoystickNavigationClient) as close as possible. This port accepts inputs only if strategy JOYSTICK is set.

See strategy JOYSTICK.

Table: Datasheet Properties of Component-Port NavVelSendServer
Property Name Property Value Property Description
CoordnateDimensions 2D

TrackingClient

Documentation: Goals from tracking can be sent to this port. (e.g. smartLaserPersonTracker)

IRClient

Documentation:

PathNavigationGoalClient

Documentation:

BaseStateClient

Documentation:

Table: Datasheet Properties of Component-Port BaseStateClient
Property Name Property Value Property Description
CoordnateDimensions 2D

NavVelSendClient

Documentation: Typically connected to the robot base (e.g. SmartPioneerBaseServer). This port sends navigation commands v, w.

Table: Datasheet Properties of Component-Port NavVelSendClient
Property Name Property Value Property Description
MotionPrimitive DifferentialDrive
CoordnateDimensions 2D

GoalEventServer

Documentation:

Register with event state CDL_GOAL_NOT_REACHED to be notified when the stateful event switches to event state CDL_GOAL_REACHED.

The CDL_GOAL_REACHED will be sent only once per activation. CDL_GOAL_REACHED event is sent when a goal was reached (i.e. the robot is within goal distance or angle error).

ComponentMode Neutral : Port is neutral, does not consume new input while in this state. ComponentMode MoveRobot : Will send goal reached events.

RobotBlockedEventServer

Documentation:

Component Parameters: SmartCdlServerParams

Internal Parameter: PathNav

Documentation:

Table: Internal Parameter PathNav
Attribute Name Attribute Type Attribute Value Attribute Description
pathNavPredictedGoalPose_controll1_dist Double 200.0
pathNavPredictedGoalPose_controll1_speed Double 100.0
pathNavPredictedGoalPose_controll2_dist Double 300.0
pathNavPredictedGoalPose_controll2_speed Double 250.0
pathNavPredictedGoalPose_controll3_dist Double 600.0
pathNavPredictedGoalPose_controll3_speed Double 600.0
pathNavPredictedGoalPose_minDist Double 200
pathNavRecover_max_dist Double 2000
robotBlocked_event_timeout UInt16 15

timout for robot beeing block in secons

Internal Parameter: Cdl

Documentation:

Table: Internal Parameter Cdl
Attribute Name Attribute Type Attribute Value Attribute Description
dataDir String "data/lookup-files/"
curvature_default_file String "CDLindex_P3DX.dat"

File with the curvature indices as produced by cdlCalculate. Relative to current dir or absolute. See also parameter LOOKUPTABLE().

lookup_default_file String "CDLdist_P3DX.dat"

File with the distance values as produced by cdlCalculate. Relative to current dir or absolute. See also parameter LOOKUPTABLE().

lookup_default_file_compressed Boolean false
accel_default_file String "CDLacc_P3DX.dat"

File with the allowed accelerations as produced by cdlCalculate. Relative to current dir or absolute. See also parameter LOOKUPTABLE().

curvature_second_file String "CDLindex_P3DX.dat"

File with the curvature indices as produced by cdlCalculate. Relative to current dir or absolute. See also parameter LOOKUPTABLE().

lookup_second_file String "CDLdist_P3DX.dat"

File with the distance values as produced by cdlCalculate. Relative to current dir or absolute. See also parameter LOOKUPTABLE().

lookup_second_file_compressed Boolean false
accel_second_file String "CDLacc_P3DX.dat"

File with the allowed accelerations as produced by cdlCalculate. Relative to current dir or absolute. See also parameter LOOKUPTABLE().

translation_acc Double 400.0

Translational acceleration. [mm/s^2]

rotation_acc Double 100.0

Rotational acceleration. [deg/s^2]

delta_t_calc Double 0.35

CDL predicts the robot motion deltacalc timesteps into the future. (10Hz was 0.7 now with 20Hz 0.35 Matthias)

delta_t_trigger Double 0.1

The time steps for the CDL execution cycle. Defines the rate in which the CDL task is executed.

followHysteresis Boolean false

In following mode: if true, the robot will only follow the person if the person moved a considerably distance.

contour_default_file String "CDLcontour_P3DX.dat"
contour_second_file String "CDLcontour_P3DX.dat"
use_obstacle_history Boolean false
freeBehaviorDist Double 350.0
freeBehaviorDist_second Double 350.0

Internal Parameter: CdlRotate

Documentation:

Table: Internal Parameter CdlRotate
Attribute Name Attribute Type Attribute Value Attribute Description
error Double 5.0

Define allowed error for in place rotation [deg]. Similar to goalregion for rotation.

rotDev1 Double 1.0
rotDev2 Double 1.0
rotDev3 Double 15.0
rotDev4 Double 45.0
rotSpeed1 Double 0.0
rotSpeed2 Double 2.0
rotSpeed3 Double 10.0
rotSpeed4 Double 70.0

Internal Parameter: Server

Documentation:

Table: Internal Parameter Server
Attribute Name Attribute Type Attribute Value Attribute Description
plannerInit Boolean true
trackerInit Boolean false
laserClient2Init Boolean false
irClientInit Boolean false
pathNavInit Boolean false
baseClientInit Boolean false

ParameterSetInstance: CdlParameter

Trigger Instance: SETSTRATEGY

Property: active = false

Documentation:

Set the CDL strategy.

Available strategies:

  • REACTIVE: Reactive driving. The robot tries to maximize its speed by avoiding any obstacles. It will drive into the direction which allows the highest translational velocity and provides the largest remaining travel distance. This is the default value.
  • JOYSTICK: The robot can be controlled with a joystick. The CDL takes input from the port navigationVelocitySendServer and choses a trajectory closest to the v, w commands given by the joystick. See also server port navigationVelocitySendServer.
  • APPROACH_HALT: Approach a goal and halt when reached. Will send a CDL_GOAL_REACHED event via the cdlGoalEventServer when the goal is reached. Possible goal modes: ABSOLUTE, PLANNER.
  • APPROACH: Approach a target but switch to REACTIVE when the goal is reached rather than stopping as in strategy APPROACH_HALT. Will send a CDL_GOAL_REACHED event via the cdlGoalEventServer when the goal is reached. Can be used to achieve smooth movement when using intermediate goal points. Goal modes: ABSOLUTE, PLANNER.
  • ROTATE: Rotate into the given direction and report this by the CDL_GOAL_REACHED event. The heading can be given by absolute position, absolute angle or relative angle. Goal modes: ABSOLUTE, ANGLEABSOLUTE, ANGLERELATIVE.
  • FOLLOW: Drive into the given direction with the given translational velocity. Takes goals from the trackingClient port. Used e.g. by the smartLaserPersonTracker. Goal modes: PERSON.
  • BACKWARD: Move blindly backwards and stop as soon as the given distance has been covered. The distance is calculated to a previously saved position (parameter SAVECURPOS()). Note that this is blind driving. This strategy can be used if a mobile platform has no laser scanner mounted that points backwards. Fires CDL_GOAL_REACHED when distance has been covered.
  • PATH_NAV: TODO

Parameter Instance: FREEBEHAVIOR

Documentation:

Activate or deactivate the free behavior in stalled situations. If activated, the robot will turn in a free direction in stalled situations. Values: ACTIVATE, DEACTIVATE

Table: Parameter-Instance FREEBEHAVIOR
Attribute Name Attribute Type Attribute Value Attribute Description
free InlineEnumeration DEACTIVATE

Parameter Instance: PATHNAVFREEBEHAVIOR

Documentation:

Table: Parameter-Instance PATHNAVFREEBEHAVIOR
Attribute Name Attribute Type Attribute Value Attribute Description
free InlineEnumeration DEACTIVATE

Parameter Instance: LOOKUPTABLE

Documentation:

Changes the lookup table. Lookup tables are precalculated in files and contain the kinematics and shape of the robot. Two lookup files can be specified in the ini configuration. This parameter allows to switch between these lookup tables at runtime. Note that you can use this parameter only in state neutral. Values: DEFAULT, SECOND. See Ini-Configuration.

Table: Parameter-Instance LOOKUPTABLE
Attribute Name Attribute Type Attribute Value Attribute Description
lt InlineEnumeration DEFAULT

Parameter Instance: TRANSVEL

Documentation:

Set translation velocity ?vmin, ?vmax in [mm/s]. The values are thresholded by the robot's vmin and vmax inputs to calculate the lookup tables in cdlCalculate (CDL_V_TRA_).

Table: Parameter-Instance TRANSVEL
Attribute Name Attribute Type Attribute Value Attribute Description
vmin Double 0.0
vmax Double 400.0

Parameter Instance: ROTVEL

Documentation:

Set rotation velocity minimum/maximum values ?wmin, ?wmax in [deg/s]. The values are thresholded by the robot's wmin and wmax inputs to calculate the lookup tables in cdlCalculate (CDL_V_ROT_).

Table: Parameter-Instance ROTVEL
Attribute Name Attribute Type Attribute Value Attribute Description
wmin Double -40.0
wmax Double 40.0

Parameter Instance: GOALMODE

Documentation:

Set goal type and goal source. Available modes:

  • ABSOLUTE: Use absolute goal position. Can only be used for goals that do not require path planning, as the CDL cannot handle local minimas. See strategies. Goal can be set with parameter GOALREGION(?x)(?y)(?a)(?id), while ?a is ignored. Used to approach a goal exactly.
  • PLANNER: Goal specification from planner, port plannerClient. Typically used with path planners (e.g. smartPlannerBreathFirstSearch).
  • PERSON: Optimized parameters for person approaching, port trackingClient (e.g. smartLaserPersonTracker).
  • SAVED: Used for backward driving (strategy BACKWARD) as a point of reference to calculate the driven distance. The reference point must be saved with SAVECURPOS() first.
  • ANGLEABSOLUTE: Heading is given by an absolute angle [deg]. Used with strategy ROTATE as a reference. Goal direction first must be set with parameter GOALREGION(?x)(?y)(?a)(?id) while ?x and ?y are ignored.
  • ANGLERELATIVE: Heading is given by an angle [deg] relative to robot. Used with strategy ROTATE as a reference. Goal direction must be set with parameter GOALREGION(?x)(?y)(?a)(?id) while ?x and ?y are ignored. Rotates then relative to this saved position.
  • PATH_NAV: TODO

Table: Parameter-Instance GOALMODE
Attribute Name Attribute Type Attribute Value Attribute Description
gm InlineEnumeration NEUTRAL

Parameter Instance: GOALREGION

Documentation:

Set goal: ?x, ?y, angle ?a, id ?id. Sends an event CDL_GOAL_NOT_REACHED once a new goal is set. CDL_GOAL_REACHED is sent as soon as the goal is reached. All values must be set while ?x/?y or ?a may be ignored depending on the strategy and goalmode.

Table: Parameter-Instance GOALREGION
Attribute Name Attribute Type Attribute Value Attribute Description
goalX Double 0.0
goalY Double 0.0
goalA Double 0.0

Trigger Instance: SETGOALREGION

Property: active = false

Documentation:

Parameter Instance: APPROACHDIST

Documentation:

Set goal approach distance [mm]. The robot will approach until goal is within this distance.

Table: Parameter-Instance APPROACHDIST
Attribute Name Attribute Type Attribute Value Attribute Description
approachDistance Double 100.0

Parameter Instance: ID

Documentation:

Set CDL_ID. Used to synchronize components, for example with smartMapperGridMap and smartPlannerBreathFirstSearch.

Table: Parameter-Instance ID
Attribute Name Attribute Type Attribute Value Attribute Description
id Int32 0

Trigger Instance: SAVECURPOS

Property: active = false

Documentation:

Save the current robot pose as ?id (for relative movements).

Parameter Instance: SAFETYCL

Documentation:

Set global CDL safety clearance distance [mm]. Robot will keep this distance from obstacles when approaching.

Table: Parameter-Instance SAFETYCL
Attribute Name Attribute Type Attribute Value Attribute Description
safetyClearance Int32 200