Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
mitre_fast_layered_map::SensorMap Class Reference

#include <sensor_map.hpp>

Public Member Functions

int getOccupancyGrid (nav_msgs::OccupancyGrid &)
 Compiles the ground and nonground layers to create an occupancy grid. More...
 
void groundPointCb (const sensor_msgs::PointCloud2 &)
 Callback function for ground points. More...
 
int init ()
 
int integrateStaticMap ()
 
void markerCb (const visualization_msgs::Marker &)
 
int moveMap (double, double)
 Move the center of the map to follow ego. More...
 
void nonGroundPointCb (const sensor_msgs::PointCloud2 &)
 Callback function for nonground points. More...
 
void odomCb (const nav_msgs::Odometry::ConstPtr)
 Odometry callback function to update map position. More...
 
int once ()
 
bool pointBoundingBoxFilter (const pcl::PointXYZ)
 
bool pointHeightFilter (const pcl::PointXYZ, double _vehicleHeight=0)
 
int publishMap ()
 
 SensorMap ()
 Constructor to initialize mapping. More...
 
 SensorMap (ros::NodeHandle *, MapConfiguration)
 
void staticMapCb (const nav_msgs::OccupancyGrid &)
 
int tfTransformCloud (const sensor_msgs::PointCloud2 &, sensor_msgs::PointCloud2 &, std::string)
 
int updateGroundPts (const PointCloud &)
 Records cells in the gridmap where the ground points landed. More...
 
int updateNongroundPts (const PointCloud &)
 Updates cells in the map that may have nonground (obstacle) points. More...
 
 ~SensorMap ()
 

Private Member Functions

int runFilter ()
 Run the grid map through the filter chain. More...
 

Private Attributes

MapConfiguration config_
 
std::vector< geometry_msgs::Posecorners_
 Holds corner of vehicle which will create polygon bounding box. More...
 
bool cornersCalculated_ {false}
 Record if we have received an odom update. More...
 
grid_map::GridMap gridMap_
 Mapping data storage container. More...
 
ros::Publisher gridMapPub_
 Publisher for the whole grid map using grid map msgs. More...
 
ros::Time groundLastUpdate_
 Keeps track of the last time we updated ground points. More...
 
ros::Subscriber groundPointsSub_
 Receives point cloud of ground points. More...
 
bool initialized_ {false}
 
filters::FilterChain< grid_map::GridMapmapOperationsFilterChain_
 after updating points More...
 
ros::Subscriber markerSub_
 Subscriber for marker topic to add points to map. More...
 
ros::NodeHandle nh_
 Passed in node handle for namespace. More...
 
ros::Time nongroundLastUpdate_
 Keeps track of the last time we updated non ground points. More...
 
ros::Subscriber nonGroundPointsSub_
 Receives point cloud of nonground points. More...
 
filters::FilterChain< grid_map::GridMapobstacleFilterChain_
 Filters to modify obstacle state of map. More...
 
ros::Publisher occPub_
 Publisher of occupancy grid. More...
 
ros::Time odomLastUpdate_
 Keeps track of last time we updated position of map. More...
 
ros::Subscriber odomSub_
 Subscribes to odom topic to position map within frame. More...
 
uint64_t readingsReceived_ {0}
 Records how many readings we have received. More...
 
bool recStaticMap_ {false}
 Stateful variable for receiving static map. More...
 
grid_map::GridMap staticMap_
 Storage for static map. For optimization we only want to receive it once. More...
 
ros::Subscriber staticMapSub_
 Will subscripe to the static map topic. ASSUMPTION: Only one static map. More...
 
tf2_ros::Buffer tfBuffer_
 Holds transformations from tf tree. More...
 
tf2_ros::TransformListener tfListener_
 Used in tfBuffer_. More...
 

Friends

class TestMap
 

Detailed Description

Definition at line 103 of file sensor_map.hpp.

Constructor & Destructor Documentation

mitre_fast_layered_map::SensorMap::SensorMap ( )

Constructor to initialize mapping.

Parameters
nhNode handle to use for this map instance
configMap configuraton variables

Definition at line 35 of file sensor_map.cpp.

mitre_fast_layered_map::SensorMap::SensorMap ( ros::NodeHandle nh,
MapConfiguration  config 
)
MapConfiguraton config;
// Set config
mitre_fast_layered_map::Map(&nh, config);

Definition at line 23 of file sensor_map.cpp.

mitre_fast_layered_map::SensorMap::~SensorMap ( )

Definition at line 42 of file sensor_map.cpp.

Member Function Documentation

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
_cloudA 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 ( )

Definition at line 51 of file sensor_map.cpp.

int mitre_fast_layered_map::SensorMap::integrateStaticMap ( )

Definition at line 519 of file sensor_map.cpp.

void mitre_fast_layered_map::SensorMap::markerCb ( const visualization_msgs::Marker &  marker)

Definition at line 583 of file sensor_map.cpp.

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
_cloudPoint 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
odomOdometry message used to move map

Definition at line 166 of file sensor_map.cpp.

int mitre_fast_layered_map::SensorMap::once ( )

Definition at line 147 of file sensor_map.cpp.

bool mitre_fast_layered_map::SensorMap::pointBoundingBoxFilter ( const pcl::PointXYZ  point)

Definition at line 463 of file sensor_map.cpp.

bool mitre_fast_layered_map::SensorMap::pointHeightFilter ( const pcl::PointXYZ  _point,
double  _vehicleHeight = 0 
)

Definition at line 448 of file sensor_map.cpp.

int mitre_fast_layered_map::SensorMap::publishMap ( )

Definition at line 657 of file sensor_map.cpp.

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)

Definition at line 611 of file sensor_map.cpp.

int mitre_fast_layered_map::SensorMap::tfTransformCloud ( const sensor_msgs::PointCloud2 &  _inCloud,
sensor_msgs::PointCloud2 &  _outCloud,
std::string  _outFrame 
)

Definition at line 690 of file sensor_map.cpp.

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.

Friends And Related Function Documentation

friend class TestMap
friend

Definition at line 144 of file sensor_map.hpp.

Member Data Documentation

MapConfiguration mitre_fast_layered_map::SensorMap::config_
private

Definition at line 153 of file sensor_map.hpp.

std::vector<geometry_msgs::Pose> mitre_fast_layered_map::SensorMap::corners_
private

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.

grid_map::GridMap mitre_fast_layered_map::SensorMap::gridMap_
private

Mapping data storage container.

Definition at line 164 of file sensor_map.hpp.

ros::Publisher mitre_fast_layered_map::SensorMap::gridMapPub_
private

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.

ros::Subscriber mitre_fast_layered_map::SensorMap::groundPointsSub_
private

Receives point cloud of ground points.

Definition at line 159 of file sensor_map.hpp.

bool mitre_fast_layered_map::SensorMap::initialized_ {false}
private

Definition at line 151 of file sensor_map.hpp.

filters::FilterChain<grid_map::GridMap> mitre_fast_layered_map::SensorMap::mapOperationsFilterChain_
private

after updating points

Filters to modify map after filters in place

Definition at line 167 of file sensor_map.hpp.

ros::Subscriber mitre_fast_layered_map::SensorMap::markerSub_
private

Subscriber for marker topic to add points to map.

Definition at line 156 of file sensor_map.hpp.

ros::NodeHandle mitre_fast_layered_map::SensorMap::nh_
private

Passed in node handle for namespace.

Definition at line 155 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.

ros::Subscriber mitre_fast_layered_map::SensorMap::nonGroundPointsSub_
private

Receives point cloud of nonground points.

Definition at line 158 of file sensor_map.hpp.

filters::FilterChain<grid_map::GridMap> mitre_fast_layered_map::SensorMap::obstacleFilterChain_
private

Filters to modify obstacle state of map.

Definition at line 166 of file sensor_map.hpp.

ros::Publisher mitre_fast_layered_map::SensorMap::occPub_
private

Publisher of occupancy grid.

Definition at line 161 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.

ros::Subscriber mitre_fast_layered_map::SensorMap::odomSub_
private

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.

grid_map::GridMap mitre_fast_layered_map::SensorMap::staticMap_
private

Storage for static map. For optimization we only want to receive it once.

Definition at line 165 of file sensor_map.hpp.

ros::Subscriber mitre_fast_layered_map::SensorMap::staticMapSub_
private

Will subscripe to the static map topic. ASSUMPTION: Only one static map.

Definition at line 160 of file sensor_map.hpp.

tf2_ros::Buffer mitre_fast_layered_map::SensorMap::tfBuffer_
private

Holds transformations from tf tree.

Definition at line 149 of file sensor_map.hpp.

tf2_ros::TransformListener mitre_fast_layered_map::SensorMap::tfListener_
private

Used in tfBuffer_.

Definition at line 150 of file sensor_map.hpp.


The documentation for this class was generated from the following files:


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