#include <obstacle_points.h>
Classes | |
| class | PolarLine |
Public Types | |
| typedef std::pair< tf2::Vector3, tf2::Vector3 > | Line |
Public Member Functions | |
| void | add_test_point (tf2::Vector3 p) |
| void | clear_test_points () |
| std::vector< Line > | get_lines (ros::Duration max_age) |
| std::vector< tf2::Vector3 > | get_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< PolarLine > | lidar_points |
| ros::Time | lidar_stamp |
| std::mutex | points_mutex |
| ros::Subscriber | scan_sub |
| std::map< std::string, RangeSensor > | sensors |
| std::vector< float > | sinLUT |
| ros::Subscriber | sonar_sub |
| std::vector< tf2::Vector3 > | test_points |
| tf2_ros::Buffer & | tf_buffer |
Definition at line 89 of file obstacle_points.h.
| typedef std::pair<tf2::Vector3, tf2::Vector3> ObstaclePoints::Line |
Definition at line 144 of file obstacle_points.h.
| ObstaclePoints::ObstaclePoints | ( | ros::NodeHandle & | nh, |
| tf2_ros::Buffer & | tf_buffer | ||
| ) |
Definition at line 35 of file obstacle_points.cpp.
| 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.
|
private |
Definition at line 104 of file obstacle_points.h.
|
private |
Definition at line 119 of file obstacle_points.h.
|
private |
Definition at line 112 of file obstacle_points.h.
|
private |
Definition at line 106 of file obstacle_points.h.
|
private |
Definition at line 114 of file obstacle_points.h.
|
private |
Definition at line 113 of file obstacle_points.h.
|
private |
Definition at line 115 of file obstacle_points.h.
|
private |
Definition at line 116 of file obstacle_points.h.
|
private |
Definition at line 102 of file obstacle_points.h.
|
private |
Definition at line 109 of file obstacle_points.h.
|
private |
Definition at line 107 of file obstacle_points.h.
|
private |
Definition at line 119 of file obstacle_points.h.
|
private |
Definition at line 108 of file obstacle_points.h.
|
private |
Definition at line 123 of file obstacle_points.h.
|
private |
Definition at line 110 of file obstacle_points.h.