Public Types | Public Member Functions | Private Member Functions | Private Attributes
range_sensor_layer::RangeSensorLayer Class Reference

#include <range_sensor_layer.h>

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

List of all members.

Public Types

enum  InputSensorType { VARIABLE, FIXED, ALL }

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)

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)
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)
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::list< sensor_msgs::Range > range_msgs_buffer_
std::vector< ros::Subscriberrange_subs_

Detailed Description

Definition at line 13 of file range_sensor_layer.h.


Member Enumeration Documentation

Enumerator:
VARIABLE 
FIXED 
ALL 

Definition at line 16 of file range_sensor_layer.h.


Constructor & Destructor Documentation

Definition at line 13 of file range_sensor_layer.cpp.


Member Function Documentation

Reimplemented from costmap_2d::Layer.

Definition at line 460 of file range_sensor_layer.cpp.

float range_sensor_layer::RangeSensorLayer::area ( int  x1,
int  y1,
int  x2,
int  y2,
int  x3,
int  y3 
) [inline, private]

Definition at line 74 of file range_sensor_layer.h.

void range_sensor_layer::RangeSensorLayer::bufferIncomingRangeMsg ( const sensor_msgs::RangeConstPtr &  range_message) [private]

Definition at line 169 of file range_sensor_layer.cpp.

Reimplemented from costmap_2d::Layer.

Definition at line 455 of file range_sensor_layer.cpp.

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

Definition at line 117 of file range_sensor_layer.cpp.

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

Definition at line 109 of file range_sensor_layer.cpp.

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

Definition at line 122 of file range_sensor_layer.cpp.

Reimplemented from costmap_2d::Layer.

Definition at line 15 of file range_sensor_layer.cpp.

int range_sensor_layer::RangeSensorLayer::orient2d ( int  Ax,
int  Ay,
int  Bx,
int  By,
int  Cx,
int  Cy 
) [inline, private]

Definition at line 79 of file range_sensor_layer.h.

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

Definition at line 199 of file range_sensor_layer.cpp.

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

Definition at line 191 of file range_sensor_layer.cpp.

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

Definition at line 224 of file range_sensor_layer.cpp.

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

Definition at line 153 of file range_sensor_layer.cpp.

Reimplemented from costmap_2d::Layer.

Definition at line 446 of file range_sensor_layer.cpp.

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

Definition at line 134 of file range_sensor_layer.cpp.

unsigned char range_sensor_layer::RangeSensorLayer::to_cost ( double  p) [inline, private]

Definition at line 52 of file range_sensor_layer.h.

double range_sensor_layer::RangeSensorLayer::to_prob ( unsigned char  c) [inline, private]

Definition at line 51 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 346 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 369 of file range_sensor_layer.cpp.

Definition at line 175 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 237 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 405 of file range_sensor_layer.cpp.


Member Data Documentation

Definition at line 67 of file range_sensor_layer.h.

Definition at line 63 of file range_sensor_layer.h.

Definition at line 62 of file range_sensor_layer.h.

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

Definition at line 71 of file range_sensor_layer.h.

Definition at line 60 of file range_sensor_layer.h.

Definition at line 59 of file range_sensor_layer.h.

Definition at line 66 of file range_sensor_layer.h.

Definition at line 62 of file range_sensor_layer.h.

Definition at line 58 of file range_sensor_layer.h.

Definition at line 69 of file range_sensor_layer.h.

Definition at line 69 of file range_sensor_layer.h.

Definition at line 69 of file range_sensor_layer.h.

Definition at line 69 of file range_sensor_layer.h.

Definition at line 65 of file range_sensor_layer.h.

Definition at line 58 of file range_sensor_layer.h.

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

Definition at line 54 of file range_sensor_layer.h.

Definition at line 55 of file range_sensor_layer.h.

std::list<sensor_msgs::Range> range_sensor_layer::RangeSensorLayer::range_msgs_buffer_ [private]

Definition at line 56 of file range_sensor_layer.h.

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 Sat Jun 8 2019 19:17:45