Classes | Public Types | Public Member Functions | Private Attributes | List of all members
ObstaclePoints Class Reference

#include <obstacle_points.h>

Classes

class  PolarLine
 

Public Types

typedef std::pair< tf2::Vector3, tf2::Vector3Line
 

Public Member Functions

void add_test_point (tf2::Vector3 p)
 
void clear_test_points ()
 
std::vector< Lineget_lines (ros::Duration max_age)
 
std::vector< tf2::Vector3get_points (ros::Duration max_age)
 
 ObstaclePoints (ros::NodeHandle &nh, tf2_ros::Buffer &tf_buffer)
 
void range_callback (const sensor_msgs::Range::ConstPtr &msg)
 
void scan_callback (const sensor_msgs::LaserScan::ConstPtr &msg)
 

Private Attributes

std::string baseFrame
 
std::vector< float > cosLUT
 
bool have_lidar
 
LidarSensor lidar
 
tf2::Vector3 lidar_normal
 
tf2::Vector3 lidar_origin
 
std::vector< PolarLinelidar_points
 
ros::Time lidar_stamp
 
std::mutex points_mutex
 
ros::Subscriber scan_sub
 
std::map< std::string, RangeSensorsensors
 
std::vector< float > sinLUT
 
ros::Subscriber sonar_sub
 
std::vector< tf2::Vector3test_points
 
tf2_ros::Buffertf_buffer
 

Detailed Description

Definition at line 89 of file obstacle_points.h.

Member Typedef Documentation

Definition at line 144 of file obstacle_points.h.

Constructor & Destructor Documentation

ObstaclePoints::ObstaclePoints ( ros::NodeHandle nh,
tf2_ros::Buffer tf_buffer 
)

Definition at line 35 of file obstacle_points.cpp.

Member Function Documentation

void ObstaclePoints::add_test_point ( tf2::Vector3  p)

Definition at line 230 of file obstacle_points.cpp.

void ObstaclePoints::clear_test_points ( )

Definition at line 235 of file obstacle_points.cpp.

std::vector< ObstaclePoints::Line > ObstaclePoints::get_lines ( ros::Duration  max_age)

Definition at line 216 of file obstacle_points.cpp.

std::vector< tf2::Vector3 > ObstaclePoints::get_points ( ros::Duration  max_age)

Definition at line 176 of file obstacle_points.cpp.

void ObstaclePoints::range_callback ( const sensor_msgs::Range::ConstPtr &  msg)

Definition at line 44 of file obstacle_points.cpp.

void ObstaclePoints::scan_callback ( const sensor_msgs::LaserScan::ConstPtr &  msg)

Definition at line 107 of file obstacle_points.cpp.

Member Data Documentation

std::string ObstaclePoints::baseFrame
private

Definition at line 104 of file obstacle_points.h.

std::vector<float> ObstaclePoints::cosLUT
private

Definition at line 119 of file obstacle_points.h.

bool ObstaclePoints::have_lidar
private

Definition at line 112 of file obstacle_points.h.

LidarSensor ObstaclePoints::lidar
private

Definition at line 106 of file obstacle_points.h.

tf2::Vector3 ObstaclePoints::lidar_normal
private

Definition at line 114 of file obstacle_points.h.

tf2::Vector3 ObstaclePoints::lidar_origin
private

Definition at line 113 of file obstacle_points.h.

std::vector<PolarLine> ObstaclePoints::lidar_points
private

Definition at line 115 of file obstacle_points.h.

ros::Time ObstaclePoints::lidar_stamp
private

Definition at line 116 of file obstacle_points.h.

std::mutex ObstaclePoints::points_mutex
private

Definition at line 102 of file obstacle_points.h.

ros::Subscriber ObstaclePoints::scan_sub
private

Definition at line 109 of file obstacle_points.h.

std::map<std::string, RangeSensor> ObstaclePoints::sensors
private

Definition at line 107 of file obstacle_points.h.

std::vector<float> ObstaclePoints::sinLUT
private

Definition at line 119 of file obstacle_points.h.

ros::Subscriber ObstaclePoints::sonar_sub
private

Definition at line 108 of file obstacle_points.h.

std::vector<tf2::Vector3> ObstaclePoints::test_points
private

Definition at line 123 of file obstacle_points.h.

tf2_ros::Buffer& ObstaclePoints::tf_buffer
private

Definition at line 110 of file obstacle_points.h.


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


move_basic
Author(s): Jim Vaughan
autogenerated on Fri Mar 26 2021 02:46:58