-
Notifications
You must be signed in to change notification settings - Fork 1
/
local_mapper.orogen
98 lines (75 loc) · 3.73 KB
/
local_mapper.orogen
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
name "local_mapper"
using_library 'velodyne_lidar'
using_library 'envire'
import_types_from "base"
import_types_from "envire"
import_types_from "velodyne_lidar/MultilevelLaserScan.h"
import_types_from "envire/maps/MLSConfiguration.hpp"
task_context "Task" do
needs_configuration
input_port("pointcloud_samples", "base/samples/Pointcloud").
needs_reliable_connection.
doc "Arbitrary 3d points in respect to the laser frame"
input_port("scan_samples", "base/samples/LaserScan").
needs_reliable_connection.
doc "LaserScann of front Scanner"
input_port("scan_samples_back", "base/samples/LaserScan").
needs_reliable_connection.
doc "Optional LaserScann of rear scanner"
input_port("velodyne_scans", "velodyne_lidar::MultilevelLaserScan").
needs_reliable_connection.
doc 'Optional velodyne scans'
output_port('map', ro_ptr('std/vector</envire/BinaryEvent>')).
doc('Mls map of the environment').
keep_last_written_value(false)
operation('markRectInMap').
argument('width', 'double', 'width of the rectangle').
argument('height', 'double', 'height of the rectangle').
argument('pose', 'base::samples::RigidBodyState', 'Pose of the rectangle center').
argument('offset', 'double', 'offset in height between the pose and the rectange height').
returns('bool')
operation('dropMap').
returns('bool')
operation('setNewMap').
argument('map', "/RTT/extras/ReadOnlyPointer</std/vector</envire/BinaryEvent>>", 'new map').
argument('newMap2Odometry', 'base/samples/RigidBodyState', 'Transformation of the new map to the odometry coordinate frame').
returns('bool')
transformer do
transformation("body_center", "odometry")
transformation("laser", "body_center")
transformation("laser_back", "body_center")
transformation("velodyne", "body_center")
align_port('scan_samples', 0.025)
align_port('scan_samples_back', 0.025)
align_port('velodyne_scans', 0.08)
align_port('pointcloud_samples', 0.2)
max_latency(0.1)
end
property('map_size', 'double', 3.0).
doc 'The size of the local map'
property('boundary_size', 'double', 1.0).
doc 'The size of the boundary of the map. If the Robot enters the boundary the map will be moved'
property('map_resolution', 'double', 0.1).
doc 'The size of each grid cell'
property('map_update_model', 'envire::MLSConfiguration::update_model', :SLOPE).
doc 'The update model of mls map: KALMAN, SUM, SLOPE'
property('history_scale_factor', 'double', 1.0).
doc 'Scale factor between 1.0 and 0.0 of how much old values are valued.'
property('scan_angle_change_trigger', 'double', 0.3).
doc 'If the angle from any Scanner to the robot center changes more that this value a new map will be written to the output port'
property('robot_angle_change_trigger', 'double', 0.3).
doc 'If the angle of the robot center changes more that this value a new map will be written to the output port'
property('robot_translation_trigger', 'double', 0.05).
doc 'If the robot moves more that this value a new map will be written to the output port'
property('height_to_ground', 'double', 0).
doc 'the distance between the body_center frame and the ground'
## velodyne filter parameter
property('velodyne_maximum_angle_to_neighbor', 'double', 2.53).
doc('valid neigbors have an angle not greater than this value.').
doc('the angle is always defined from the origin to the more distant point.')
property('velodyne_minimum_valid_neighbors', 'int', 2).
doc('minimum amount of valid neigbors')
needs_configuration
port_driven
worstcase_processing_time 2.0
end