Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
range_sensor_layer::RangeSensorLayer Class Reference

#include <range_sensor_layer.h>

Inheritance diagram for range_sensor_layer::RangeSensorLayer:
Inheritance graph
[legend]

Public Types

enum  InputSensorType { VARIABLE, FIXED, ALL }
 
- Public Types inherited from costmap_2d::Costmap2D
typedef boost::recursive_mutex mutex_t
 

Public Member Functions

virtual void activate ()
 
virtual void deactivate ()
 
virtual void onInitialize ()
 
 RangeSensorLayer ()
 
virtual void reset ()
 
virtual void updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
 
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
- Public Member Functions inherited from costmap_2d::CostmapLayer
void addExtraBounds (double mx0, double my0, double mx1, double my1)
 
 CostmapLayer ()
 
bool isDiscretized ()
 
virtual void matchSize ()
 
- Public Member Functions inherited from costmap_2d::Layer
const std::vector< geometry_msgs::Point > & getFootprint () const
 
std::string getName () const
 
void initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *tf)
 
bool isCurrent () const
 
 Layer ()
 
virtual void onFootprintChanged ()
 
virtual ~Layer ()
 
- Public Member Functions inherited from costmap_2d::Costmap2D
unsigned int cellDistance (double world_dist)
 
void convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 
bool copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y)
 
 Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
 
 Costmap2D (const Costmap2D &map)
 
 Costmap2D ()
 
unsigned char * getCharMap () const
 
unsigned char getCost (unsigned int mx, unsigned int my) const
 
unsigned char getDefaultValue ()
 
unsigned int getIndex (unsigned int mx, unsigned int my) const
 
mutex_tgetMutex ()
 
double getOriginX () const
 
double getOriginY () const
 
double getResolution () const
 
unsigned int getSizeInCellsX () const
 
unsigned int getSizeInCellsY () const
 
double getSizeInMetersX () const
 
double getSizeInMetersY () const
 
void indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const
 
void mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const
 
Costmap2Doperator= (const Costmap2D &map)
 
void polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 
void resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
 
void resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
 
bool saveMap (std::string file_name)
 
bool setConvexPolygonCost (const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
 
void setCost (unsigned int mx, unsigned int my, unsigned char cost)
 
void setDefaultValue (unsigned char c)
 
virtual void updateOrigin (double new_origin_x, double new_origin_y)
 
bool worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const
 
void worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const
 
void worldToMapNoBounds (double wx, double wy, int &mx, int &my) const
 
virtual ~Costmap2D ()
 

Private Member Functions

float area (int x1, int y1, int x2, int y2, int x3, int y3)
 
void bufferIncomingRangeMsg (const sensor_msgs::RangeConstPtr &range_message, const std::string &topic)
 
double delta (double phi)
 
double gamma (double theta)
 
void get_deltas (double angle, double *dx, double *dy)
 
int orient2d (int Ax, int Ay, int Bx, int By, int Cx, int Cy)
 
void processFixedRangeMsg (sensor_msgs::Range &range_message)
 
void processRangeMsg (sensor_msgs::Range &range_message)
 
void processVariableRangeMsg (sensor_msgs::Range &range_message)
 
void reconfigureCB (range_sensor_layer::RangeSensorLayerConfig &config, uint32_t level)
 
void resetRange ()
 
double sensor_model (double r, double phi, double theta)
 
unsigned char to_cost (double p)
 
double to_prob (unsigned char c)
 
void update_cell (double ox, double oy, double ot, double r, double nx, double ny, bool clear)
 
void updateCostmap ()
 
void updateCostmap (sensor_msgs::Range &range_message, bool clear_sensor_cone)
 

Private Attributes

unsigned int buffered_readings_
 
bool clear_on_max_reading_
 
double clear_threshold_
 
dynamic_reconfigure::Server< range_sensor_layer::RangeSensorLayerConfig > * dsrv_
 
std::string global_frame_
 
double inflate_cone_
 
ros::Time last_reading_time_
 
double mark_threshold_
 
double max_angle_
 
double max_x_
 
double max_y_
 
double min_x_
 
double min_y_
 
double no_readings_timeout_
 
double phi_v_
 
boost::function< void(sensor_msgs::Range &range_message)> processRangeMessageFunc_
 
boost::mutex range_message_mutex_
 
std::unordered_map< std::string, std::list< sensor_msgs::Range > > range_msgs_buffers_
 
std::vector< ros::Subscriberrange_subs_
 
size_t ranges_buffer_size_ { 0 }
 

Additional Inherited Members

- Protected Member Functions inherited from costmap_2d::CostmapLayer
void touch (double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
 
void updateWithAddition (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithMax (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithTrueOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void useExtraBounds (double *min_x, double *min_y, double *max_x, double *max_y)
 
- Protected Member Functions inherited from costmap_2d::Costmap2D
void copyMapRegion (data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y)
 
virtual void deleteMaps ()
 
virtual void initMaps (unsigned int size_x, unsigned int size_y)
 
void raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX)
 
virtual void resetMaps ()
 
- Protected Attributes inherited from costmap_2d::CostmapLayer
bool has_extra_bounds_
 
- Protected Attributes inherited from costmap_2d::Layer
bool current_
 
bool enabled_
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
tf::TransformListenertf_
 
- Protected Attributes inherited from costmap_2d::Costmap2D
unsigned char * costmap_
 
unsigned char default_value_
 
double origin_x_
 
double origin_y_
 
double resolution_
 
unsigned int size_x_
 
unsigned int size_y_
 

Detailed Description

Definition at line 18 of file range_sensor_layer.h.

Member Enumeration Documentation

Enumerator
VARIABLE 
FIXED 
ALL 

Definition at line 21 of file range_sensor_layer.h.

Constructor & Destructor Documentation

range_sensor_layer::RangeSensorLayer::RangeSensorLayer ( )

Definition at line 19 of file range_sensor_layer.cpp.

Member Function Documentation

void range_sensor_layer::RangeSensorLayer::activate ( )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 501 of file range_sensor_layer.cpp.

float range_sensor_layer::RangeSensorLayer::area ( int  x1,
int  y1,
int  x2,
int  y2,
int  x3,
int  y3 
)
inlineprivate

Definition at line 87 of file range_sensor_layer.h.

void range_sensor_layer::RangeSensorLayer::bufferIncomingRangeMsg ( const sensor_msgs::RangeConstPtr &  range_message,
const std::string &  topic 
)
private

Definition at line 191 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::deactivate ( )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 496 of file range_sensor_layer.cpp.

double range_sensor_layer::RangeSensorLayer::delta ( double  phi)
private

Definition at line 124 of file range_sensor_layer.cpp.

double range_sensor_layer::RangeSensorLayer::gamma ( double  theta)
private

Definition at line 116 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::get_deltas ( double  angle,
double *  dx,
double *  dy 
)
private

Definition at line 129 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::onInitialize ( )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 21 of file range_sensor_layer.cpp.

int range_sensor_layer::RangeSensorLayer::orient2d ( int  Ax,
int  Ay,
int  Bx,
int  By,
int  Cx,
int  Cy 
)
inlineprivate

Definition at line 92 of file range_sensor_layer.h.

void range_sensor_layer::RangeSensorLayer::processFixedRangeMsg ( sensor_msgs::Range &  range_message)
private

Definition at line 227 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::processRangeMsg ( sensor_msgs::Range &  range_message)
private

Definition at line 219 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::processVariableRangeMsg ( sensor_msgs::Range &  range_message)
private

Definition at line 253 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::reconfigureCB ( range_sensor_layer::RangeSensorLayerConfig &  config,
uint32_t  level 
)
private

Definition at line 161 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::reset ( )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 487 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::resetRange ( )
private

Definition at line 404 of file range_sensor_layer.cpp.

double range_sensor_layer::RangeSensorLayer::sensor_model ( double  r,
double  phi,
double  theta 
)
private

Definition at line 141 of file range_sensor_layer.cpp.

unsigned char range_sensor_layer::RangeSensorLayer::to_cost ( double  p)
inlineprivate

Definition at line 61 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::to_prob ( unsigned char  c)
inlineprivate

Definition at line 57 of file range_sensor_layer.h.

void range_sensor_layer::RangeSensorLayer::update_cell ( double  ox,
double  oy,
double  ot,
double  r,
double  nx,
double  ny,
bool  clear 
)
private

Definition at line 380 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::updateBounds ( double  robot_x,
double  robot_y,
double  robot_yaw,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 410 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::updateCostmap ( )
private

Definition at line 201 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::updateCostmap ( sensor_msgs::Range &  range_message,
bool  clear_sensor_cone 
)
private

Definition at line 266 of file range_sensor_layer.cpp.

void range_sensor_layer::RangeSensorLayer::updateCosts ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 444 of file range_sensor_layer.cpp.

Member Data Documentation

unsigned int range_sensor_layer::RangeSensorLayer::buffered_readings_
private

Definition at line 80 of file range_sensor_layer.h.

bool range_sensor_layer::RangeSensorLayer::clear_on_max_reading_
private

Definition at line 76 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::clear_threshold_
private

Definition at line 75 of file range_sensor_layer.h.

dynamic_reconfigure::Server<range_sensor_layer::RangeSensorLayerConfig>* range_sensor_layer::RangeSensorLayer::dsrv_
private

Definition at line 84 of file range_sensor_layer.h.

std::string range_sensor_layer::RangeSensorLayer::global_frame_
private

Definition at line 73 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::inflate_cone_
private

Definition at line 72 of file range_sensor_layer.h.

ros::Time range_sensor_layer::RangeSensorLayer::last_reading_time_
private

Definition at line 79 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::mark_threshold_
private

Definition at line 75 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::max_angle_
private

Definition at line 71 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::max_x_
private

Definition at line 82 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::max_y_
private

Definition at line 82 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::min_x_
private

Definition at line 82 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::min_y_
private

Definition at line 82 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::no_readings_timeout_
private

Definition at line 78 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::phi_v_
private

Definition at line 71 of file range_sensor_layer.h.

boost::function<void(sensor_msgs::Range& range_message)> range_sensor_layer::RangeSensorLayer::processRangeMessageFunc_
private

Definition at line 66 of file range_sensor_layer.h.

boost::mutex range_sensor_layer::RangeSensorLayer::range_message_mutex_
private

Definition at line 67 of file range_sensor_layer.h.

std::unordered_map<std::string, std::list<sensor_msgs::Range> > range_sensor_layer::RangeSensorLayer::range_msgs_buffers_
private

Definition at line 69 of file range_sensor_layer.h.

std::vector<ros::Subscriber> range_sensor_layer::RangeSensorLayer::range_subs_
private

Definition at line 81 of file range_sensor_layer.h.

size_t range_sensor_layer::RangeSensorLayer::ranges_buffer_size_ { 0 }
private

Definition at line 68 of file range_sensor_layer.h.


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


range_sensor_layer
Author(s): David!!
autogenerated on Thu Mar 4 2021 04:02:55