ed_sensor_integration
Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
LaserUpdater Class Reference

#include <updater.h>

Public Member Functions

void configure (tue::Configuration &config)
 Configure updater. More...
 
void configureLaserModel (uint num_beams, double angle_min, double angle_max, double range_min, double range_max)
 configure the LRF model based on a laserscan message More...
 
unsigned int getNumBeams ()
 get the number of beams of the model More...
 
void renderWorld (const geo::Pose3D &sensor_pose, const ed::WorldModel &world, std::vector< double > &model_ranges)
 render the worldmodel as would be seen by the lrf. More...
 
void setLaserFrame (const std::string &frame_id)
 set the frame of the laser model More...
 
void update (const ed::WorldModel &world, std::vector< double > &sensor_ranges, const geo::Pose3D &sensor_pose, const double timestamp, ed::UpdateRequest &req)
 update update the worldmodel based on a novel laserscan message. More...
 

Public Attributes

bool fit_entities_
 
double max_cluster_size_
 
uint max_gap_size_
 
double min_cluster_size_
 
uint min_segment_size_pixels_
 
double segment_depth_threshold_
 
double world_association_distance_
 

Private Member Functions

void associate (std::vector< double > &sensor_ranges, const std::vector< double > &model_ranges)
 associate: filter sensor information and remove ranges that can be associated with the worldmodel. Leaving only novel data. More...
 
std::vector< ScanSegmentsegment (const std::vector< double > &sensor_ranges)
 divide the sensor ranges into segments More...
 
EntityUpdate segmentToConvexHull (const ScanSegment &segment, const geo::Pose3D &sensor_pose, const std::vector< double > &sensor_ranges)
 convert a segment of ranges to a convex hull More...
 

Private Attributes

std::string lrf_frame_
 
geo::LaserRangeFinder lrf_model_
 
std::map< ed::UUID, geo::Pose3Dpose_cache
 

Detailed Description

Definition at line 17 of file laser/updater.h.

Member Function Documentation

◆ associate()

void LaserUpdater::associate ( std::vector< double > &  sensor_ranges,
const std::vector< double > &  model_ranges 
)
private

associate: filter sensor information and remove ranges that can be associated with the worldmodel. Leaving only novel data.

Parameters
[in]sensor_rangesdistances measured by the lrf
[in,out]model_rangesdistances as predicted by the worldmodel. Will be filtered. (associated ranges have value 0.0)

Definition at line 471 of file laser/updater.cpp.

◆ configure()

void LaserUpdater::configure ( tue::Configuration config)

Configure updater.

Parameters
[in]configConfiguration which may contain the following fields: world_association_distance min_segment_size_pixels segment_depth_threshold min_cluster_size max_cluster_size max_gap_size fit_entities Whether or not to fit an entity (0 or 1)

Definition at line 258 of file laser/updater.cpp.

◆ configureLaserModel()

void LaserUpdater::configureLaserModel ( uint  num_beams,
double  angle_min,
double  angle_max,
double  range_min,
double  range_max 
)
inline

configure the LRF model based on a laserscan message

Parameters
num_beamsnumber of beams in the lrf model
angle_minangle corresponding to the first beam in radians
angle_maxangle corresponding to the final beam in radians
range_minminimum distance that can be detected with the lrf in meters
range_maxmaximum distance that can be detected with the lrf in meters

Definition at line 56 of file laser/updater.h.

◆ getNumBeams()

unsigned int LaserUpdater::getNumBeams ( )
inline

get the number of beams of the model

Definition at line 73 of file laser/updater.h.

◆ renderWorld()

void LaserUpdater::renderWorld ( const geo::Pose3D sensor_pose,
const ed::WorldModel world,
std::vector< double > &  model_ranges 
)

render the worldmodel as would be seen by the lrf.

Parameters
[in]sensor_posepose of the lrf to be modeled in the world frame.
[in]worldworldmodel
[out]model_rangesranges of distances as would be seen by an lrf

Definition at line 451 of file laser/updater.cpp.

◆ segment()

std::vector< ScanSegment > LaserUpdater::segment ( const std::vector< double > &  sensor_ranges)
private

divide the sensor ranges into segments

Definition at line 484 of file laser/updater.cpp.

◆ segmentToConvexHull()

EntityUpdate LaserUpdater::segmentToConvexHull ( const ScanSegment segment,
const geo::Pose3D sensor_pose,
const std::vector< double > &  sensor_ranges 
)
private

convert a segment of ranges to a convex hull

Definition at line 565 of file laser/updater.cpp.

◆ setLaserFrame()

void LaserUpdater::setLaserFrame ( const std::string frame_id)
inline

set the frame of the laser model

Parameters
frame_idframe id of the laser

Definition at line 68 of file laser/updater.h.

◆ update()

void LaserUpdater::update ( const ed::WorldModel world,
std::vector< double > &  sensor_ranges,
const geo::Pose3D sensor_pose,
const double  timestamp,
ed::UpdateRequest req 
)

update update the worldmodel based on a novel laserscan message.

Parameters
[in]worldworldmodel to be updated
[in]sensor_rangesdistances measured by the lrf
[in]sensor_posepose of the lrf sensor at the time of the measurement
[in]timestamptimestamp of the lrf measurment
[out]requpdate request

Definition at line 278 of file laser/updater.cpp.

Member Data Documentation

◆ fit_entities_

bool LaserUpdater::fit_entities_

Definition at line 90 of file laser/updater.h.

◆ lrf_frame_

std::string LaserUpdater::lrf_frame_
private

Definition at line 114 of file laser/updater.h.

◆ lrf_model_

geo::LaserRangeFinder LaserUpdater::lrf_model_
private

Definition at line 113 of file laser/updater.h.

◆ max_cluster_size_

double LaserUpdater::max_cluster_size_

Definition at line 89 of file laser/updater.h.

◆ max_gap_size_

uint LaserUpdater::max_gap_size_

Definition at line 91 of file laser/updater.h.

◆ min_cluster_size_

double LaserUpdater::min_cluster_size_

Definition at line 88 of file laser/updater.h.

◆ min_segment_size_pixels_

uint LaserUpdater::min_segment_size_pixels_

Definition at line 85 of file laser/updater.h.

◆ pose_cache

std::map<ed::UUID, geo::Pose3D> LaserUpdater::pose_cache
private

Definition at line 116 of file laser/updater.h.

◆ segment_depth_threshold_

double LaserUpdater::segment_depth_threshold_

Definition at line 87 of file laser/updater.h.

◆ world_association_distance_

double LaserUpdater::world_association_distance_

Definition at line 86 of file laser/updater.h.


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