#include <sensor_map.hpp>
Definition at line 103 of file sensor_map.hpp.
mitre_fast_layered_map::SensorMap::SensorMap |
( |
| ) |
|
Constructor to initialize mapping.
- Parameters
-
nh | Node handle to use for this map instance |
config | Map configuraton variables |
Definition at line 35 of file sensor_map.cpp.
mitre_fast_layered_map::Map(&nh, config);
Definition at line 23 of file sensor_map.cpp.
mitre_fast_layered_map::SensorMap::~SensorMap |
( |
| ) |
|
int mitre_fast_layered_map::SensorMap::getOccupancyGrid |
( |
nav_msgs::OccupancyGrid & |
_mapOut | ) |
|
Compiles the ground and nonground layers to create an occupancy grid.
- Parameters
-
_mapOut | [out] The occupancy grid to return |
- Returns
- 0
Definition at line 643 of file sensor_map.cpp.
void mitre_fast_layered_map::SensorMap::groundPointCb |
( |
const sensor_msgs::PointCloud2 & |
_cloud | ) |
|
Callback function for ground points.
- Parameters
-
_cloud | A point cloud of ONLY points labelled as part of the ground plane |
Definition at line 276 of file sensor_map.cpp.
int mitre_fast_layered_map::SensorMap::init |
( |
| ) |
|
int mitre_fast_layered_map::SensorMap::integrateStaticMap |
( |
| ) |
|
void mitre_fast_layered_map::SensorMap::markerCb |
( |
const visualization_msgs::Marker & |
marker | ) |
|
int mitre_fast_layered_map::SensorMap::moveMap |
( |
double |
_posX, |
|
|
double |
_posY |
|
) |
| |
Move the center of the map to follow ego.
- Parameters
-
_posX | [in] Position x in map frame to move to |
_posY | [in] Position y in map frame to move to |
- Returns
- 0 on successful move, -1 on failure, 1 if map move caused jump out of mapped area
Definition at line 195 of file sensor_map.cpp.
void mitre_fast_layered_map::SensorMap::nonGroundPointCb |
( |
const sensor_msgs::PointCloud2 & |
_cloud | ) |
|
Callback function for nonground points.
- Parameters
-
_cloud | Point Cloud holding ONLY points that registered as nonground (i.e. obstacles or ledges) |
Definition at line 344 of file sensor_map.cpp.
void mitre_fast_layered_map::SensorMap::odomCb |
( |
const nav_msgs::Odometry::ConstPtr |
odom | ) |
|
Odometry callback function to update map position.
- Parameters
-
odom | Odometry message used to move map |
Definition at line 166 of file sensor_map.cpp.
int mitre_fast_layered_map::SensorMap::once |
( |
| ) |
|
bool mitre_fast_layered_map::SensorMap::pointBoundingBoxFilter |
( |
const pcl::PointXYZ |
point | ) |
|
bool mitre_fast_layered_map::SensorMap::pointHeightFilter |
( |
const pcl::PointXYZ |
_point, |
|
|
double |
_vehicleHeight = 0 |
|
) |
| |
int mitre_fast_layered_map::SensorMap::publishMap |
( |
| ) |
|
int mitre_fast_layered_map::SensorMap::runFilter |
( |
| ) |
|
|
private |
Run the grid map through the filter chain.
- Returns
- 0 on success, -1 if failure within filter chain
Definition at line 480 of file sensor_map.cpp.
void mitre_fast_layered_map::SensorMap::staticMapCb |
( |
const nav_msgs::OccupancyGrid & |
_map | ) |
|
int mitre_fast_layered_map::SensorMap::tfTransformCloud |
( |
const sensor_msgs::PointCloud2 & |
_inCloud, |
|
|
sensor_msgs::PointCloud2 & |
_outCloud, |
|
|
std::string |
_outFrame |
|
) |
| |
int mitre_fast_layered_map::SensorMap::updateGroundPts |
( |
const PointCloud & |
_pointCloud | ) |
|
Records cells in the gridmap where the ground points landed.
- Parameters
-
_pointCloud | [in] Point cloud of points on the ground plane |
- Returns
- 0 on success, 1 if problem with filters
Definition at line 311 of file sensor_map.cpp.
int mitre_fast_layered_map::SensorMap::updateNongroundPts |
( |
const PointCloud & |
_pointCloud | ) |
|
Updates cells in the map that may have nonground (obstacle) points.
- Parameters
-
_pointCloud | [in] The point cloud consisting of only nonground points |
- Returns
- 0 on success, 1 if filter failure
Definition at line 371 of file sensor_map.cpp.
Holds corner of vehicle which will create polygon bounding box.
Definition at line 171 of file sensor_map.hpp.
bool mitre_fast_layered_map::SensorMap::cornersCalculated_ {false} |
|
private |
Record if we have received an odom update.
Definition at line 170 of file sensor_map.hpp.
Publisher for the whole grid map using grid map msgs.
Definition at line 162 of file sensor_map.hpp.
ros::Time mitre_fast_layered_map::SensorMap::groundLastUpdate_ |
|
private |
Keeps track of the last time we updated ground points.
Definition at line 174 of file sensor_map.hpp.
Receives point cloud of ground points.
Definition at line 159 of file sensor_map.hpp.
bool mitre_fast_layered_map::SensorMap::initialized_ {false} |
|
private |
after updating points
Filters to modify map after filters in place
Definition at line 167 of file sensor_map.hpp.
Subscriber for marker topic to add points to map.
Definition at line 156 of file sensor_map.hpp.
ros::Time mitre_fast_layered_map::SensorMap::nongroundLastUpdate_ |
|
private |
Keeps track of the last time we updated non ground points.
Definition at line 175 of file sensor_map.hpp.
Receives point cloud of nonground points.
Definition at line 158 of file sensor_map.hpp.
Filters to modify obstacle state of map.
Definition at line 166 of file sensor_map.hpp.
ros::Time mitre_fast_layered_map::SensorMap::odomLastUpdate_ |
|
private |
Keeps track of last time we updated position of map.
Definition at line 173 of file sensor_map.hpp.
Subscribes to odom topic to position map within frame.
Definition at line 157 of file sensor_map.hpp.
uint64_t mitre_fast_layered_map::SensorMap::readingsReceived_ {0} |
|
private |
Records how many readings we have received.
Definition at line 169 of file sensor_map.hpp.
bool mitre_fast_layered_map::SensorMap::recStaticMap_ {false} |
|
private |
Stateful variable for receiving static map.
Definition at line 172 of file sensor_map.hpp.
Storage for static map. For optimization we only want to receive it once.
Definition at line 165 of file sensor_map.hpp.
Will subscripe to the static map topic. ASSUMPTION: Only one static map.
Definition at line 160 of file sensor_map.hpp.
The documentation for this class was generated from the following files: