diff --git a/config/mower_config.schema.json b/config/mower_config.schema.json index 46995b71..bb23ca70 100644 --- a/config/mower_config.schema.json +++ b/config/mower_config.schema.json @@ -274,6 +274,13 @@ "description": "Distance in [m] to drive forward after docking.", "x-environment-variable": "OM_DOCKING_DISTANCE" }, + "OM_DOCKING_APPROACH_DISTANCE": { + "type": "number", + "default": 1.5, + "title": "Docking Approach Distance", + "description": "Distance in [m] from the docking point to start docking.", + "x-environment-variable": "OM_DOCKING_APPROACH_DISTANCE" + }, "OM_DOCKING_EXTRA_TIME": { "type": "number", "default": 0.0, @@ -301,6 +308,34 @@ "description": "Distance in [m] to drive for undocking.", "x-environment-variable": "OM_UNDOCK_DISTANCE" }, + "OM_UNDOCK_ANGLED_DISTANCE": { + "type": "number", + "title": "Undock Angled Distance", + "default": 0.0, + "description": "Distance in [m] to continue driving at an angle for undocking.", + "x-environment-variable": "OM_UNDOCK_ANGLED_DISTANCE" + }, + "OM_UNDOCK_ANGLE": { + "type": "number", + "title": "Undock Angle", + "default": 0.0, + "description": "Angle in degrees for second stage undocking.", + "x-environment-variable": "OM_UNDOCK_ANGLE" + }, + "OM_UNDOCK_FIXED_ANGLE": { + "type": "boolean", + "title": "Undock Fixed Angle", + "default": true, + "description": "True to fix the undock angle, false to vary it.", + "x-environment-variable": "OM_UNDOCK_FIXED_ANGLE" + }, + "OM_UNDOCK_USE_CURVE": { + "type": "boolean", + "title": "Undock Use Curve", + "default": true, + "description": "True to use a curved second stage, false for a straight second stage.", + "x-environment-variable": "OM_UNDOCK_USE_CURVE" + }, "OM_OUTLINE_COUNT": { "type": "number", "default": 4, diff --git a/config/mower_config.sh.example b/config/mower_config.sh.example index 7b085c8b..1e4b7146 100644 --- a/config/mower_config.sh.example +++ b/config/mower_config.sh.example @@ -118,6 +118,9 @@ export OM_USE_F9R_SENSOR_FUSION=False ################################ ## Mower Logic Settings ## ################################ +# Docking starts at this distance from the dock point +export OM_DOCKING_APPROACH_DISTANCE=1.5 + # The distance to drive forward AFTER reaching the second docking point export OM_DOCKING_DISTANCE=1.0 @@ -130,9 +133,24 @@ export OM_DOCKING_RETRY_COUNT=4 # Whether to attempt redocking if the voltage is no longer detected after docking. export OM_DOCKING_REDOCK=False -# The distance to drive for undocking. This needs to be large enough for the robot to have GPS reception +# The first stage distance to drive for undocking. As a minimum it needs to clear the dock. +# If the additional angled move isn't used then this needs to be large enough for the robot to have GPS reception. export OM_UNDOCK_DISTANCE=2.0 +# The additional second stage distance to drive at an angle for undocking. This needs to be large enough for the robot to have GPS reception. +# Note - this section may still be driven without gps so don't expect high positional accuracy. +export OM_UNDOCK_ANGLED_DISTANCE=0.0 + +# The angle at which to drive for the additional distance (neg values are to the left of the dock, pos to the right). +export OM_UNDOCK_ANGLE=0.0 + +# If true will allways use the angle specified. +# If false will vary the undocking angle between +abs(OM_UNDOCK_ANGLE) to -abs(OM_UNDOCK_ANGLE) on subsequent undocks to reduce grass wear. +export OM_UNDOCK_FIXED_ANGLE=True + +# If true will use a curved second stage undock move, if false will use a straight undock move. +export OM_UNDOCK_USE_CURVE=True + # Uncomment, if you want to use the perimeter sensor of your Mowgli-type mower # for docking. Set it to 1 or 2 dependig on the signal selected on the docking # station (S1 or S2). diff --git a/src/open_mower/launch/open_mower.launch b/src/open_mower/launch/open_mower.launch index afc5e4d0..d7f71b17 100644 --- a/src/open_mower/launch/open_mower.launch +++ b/src/open_mower/launch/open_mower.launch @@ -15,7 +15,7 @@ - +