Neobotix Stations:
Charging Station (V2):
Load Handle Docking Station:
Picture comming soon
Contents
Download
Requirements
- Laserscanner
- Move_Base
- Odometry
Usage
1. C++ implementation
Create a service client and call the service.
ros::NodeHandle n; ros::ServiceClient client = n.serviceClient<std_srvs::Empty>("locate_station"); std_srvs::Empty empty; if(client.call(empty)) { ROS_INFO("arraived at the station."); } else { ROS_ERROR("Failed to find the station!"); }
2. Configuration
2.1. Parameter
Number: |
Name |
Description |
Default |
1: |
version |
Type of station to look for. |
2 |
2: |
x_threshold |
max. distance between two points in x to be part of the same object |
0.035 [m] |
3: |
y_threshold |
max. distance between two points in y to be part of the same object |
0.035 [m] |
4: |
nr_of_tries |
max. number of tries to find the station |
5 |
5: |
min_points |
min. number of points a object muss contain to be valid |
5 |
6: |
dist_pre_goal |
distance from station to first goal |
0.75 [m] |
7: |
dist_goal |
distance from station to second goal |
0.48 [m] |
8: |
approach_velocity |
velocity to move from first goal to second goal |
0.05 [m/s] |
9: |
dist_points_min |
min. length of the station |
0.38 [m] |
10: |
dist_points_max |
max. length of the station |
0.41 [m] |
11: |
average_calculation_number |
number of laserscans to calculate coordinates as exactly as possible |
40 |
12: |
min_nr_found |
min. number of successfully calculated coordinates |
12 |
13: |
visualize |
True: Publish Points and Polygons. False: Do not publish any Points or Polygons. |
false |
14: |
high_min |
only necessary for charging station V2, should be left at default |
0.06 |
15: |
high_max |
only necessary for charging station V2, should be left at default |
0.09 |
3. Additional notes
3.1. Tolerances
This package uses Move_Base to move to the first goal. Make sure your navigation plugin tolerances are configured as low as possible! We recommend: xy_goal_tolerance < 6cm and yaw_goal_tolerance < 0.04 rad
3.2. Tested Plugin
For our tests we use the eband_local_planner which can be found here
4. Warnings
As mentioned above your xy_goal_tolerance and yaw_goal_tolerance are very important. The robot can crash into the station if it is not configured exactly!!!