init_vars.cpp
Go to the documentation of this file.
1 #include "init_vars.hpp"
2 
4 {
5  defaultConfig_.obstacleFilterNs = "mitre_fast_layered_map_obstacle_filters";
6  defaultConfig_.mapOperationsFilterNs = "mitre_fast_layered_map_map_operations";
7  defaultConfig_.mapFrameId = "odom";
8  defaultConfig_.vehicleFrameId = "base_link";
13  defaultConfig_.markerSubTopic = "marker";
15  defaultConfig_.staticMapSubTopic = "staticmap";
27 
28  smallMap_.obstacleFilterNs = "none";
30  smallMap_.mapFrameId = "odom";
31  smallMap_.vehicleFrameId = "base_link";
32  smallMap_.gridmapOutputTopic = "gridmap";
33  smallMap_.occupancyOutputTopic = "costmap";
34  smallMap_.groundPointSubTopic = "ground";
36  smallMap_.markerSubTopic = "marker";
37  smallMap_.odomSubTopic = "odom";
38  smallMap_.staticMapSubTopic = "staticmap";
41  smallMap_.historyLayerPrefix = "history_";
50 
51 }
std::string obstacleFilterNs
Filter chain for filtering sensor data into obstacles.
Definition: sensor_map.hpp:65
std::string staticMapSubTopic
Sub topic for static maps that should be integrated with our dynamic map.
Definition: sensor_map.hpp:44
double permanentFilterProb
Probability required to declare a cell as a permanent obstacle.
Definition: sensor_map.hpp:73
std::string nonGroundPointSubTopic
Ros topic with nonground (obstacle) points.
Definition: sensor_map.hpp:40
bool enablePermanentObstacles
Whether to try and save permanent obstacles.
Definition: sensor_map.hpp:72
std::string mapFrameId
TF frame that the map should use.
Definition: sensor_map.hpp:50
std::string gridmapOutputTopic
Topic to output the full grid map on.
Definition: sensor_map.hpp:46
grid_map::Length len
Size of the map, assumed to be square.
Definition: sensor_map.hpp:51
bool enablePointHeightFilter
Whether to filter points by height.
Definition: sensor_map.hpp:67
std::string odomSubTopic
Ros topic holding odometry information.
Definition: sensor_map.hpp:42
double footPrintLen
Length of robot.
Definition: sensor_map.hpp:61
double resolution
Cell size of map.
Definition: sensor_map.hpp:52
std::string occupancyOutputTopic
Topic the occupancy map should be output on.
Definition: sensor_map.hpp:45
bool enableBoundingBoxFilter
Whether to filter lidar points if they are inside the hitbox of the vehicle.
Definition: sensor_map.hpp:68
std::string historyLayerPrefix
Prefix to use for history layers.
Definition: sensor_map.hpp:53
double footPrintWidth
Width of robot.
Definition: sensor_map.hpp:62
int numHistoryLayers
Number of layers to hold for history.
Definition: sensor_map.hpp:54
double maxPointHeight
If height filter is enabled, filter points more than this height above vehicle.
Definition: sensor_map.hpp:69
mitre_fast_layered_map::MapConfiguration defaultConfig_
Definition: init_vars.hpp:15
std::string vehicleFrameId
Frame id of the robot.
Definition: sensor_map.hpp:60
std::string groundPointSubTopic
Ros topic with ground points.
Definition: sensor_map.hpp:41
std::string mapOperationsFilterNs
Filter chain for map operations after obstacles have been determined.
Definition: sensor_map.hpp:66
std::string markerSubTopic
Ros topic to recieve obstacles from other sources.
Definition: sensor_map.hpp:43
Eigen::Array2d Length
mitre_fast_layered_map::MapConfiguration smallMap_
Definition: init_vars.hpp:16


mitre_fast_layered_map
Author(s):
autogenerated on Thu Mar 11 2021 03:06:49