#include <octomap_filter_raycast.h>
Public Member Functions | |
COcFilterRaycast (const std::string &octree_frame_id, ERunMode mode=FILTER_ALLWAYS) | |
Constructor. | |
virtual void | init (ros::NodeHandle &node_handle) |
Initialize. Must be called before first filtering. | |
void | setCloud (tPointCloudConstPtr cloud) |
Configure filter before each frame. Set input cloud. | |
virtual void | writeLastRunInfo () |
Write some info about last filter run. | |
Protected Member Functions | |
void | cameraInfoCB (const sensor_msgs::CameraInfo::ConstPtr &cam_info) |
Camera info callback. | |
void | computeBBX (const std_msgs::Header &sensor_header, octomap::point3d &bbx_min, octomap::point3d &bbx_max) |
Compute boundig box. | |
virtual void | filterInternal (tButServerOcTree &tree) |
Filtering function implementation. | |
octomap::point3d | getSensorOrigin (const std_msgs::Header &sensor_header) |
Compute sensor origin from the header info. | |
bool | inSensorCone (const cv::Point2d &uv) const |
Is point in sensor cone? | |
bool | isOccludedMap (const octomap::point3d &sensor_origin, const octomap::point3d &p, double resolution, tButServerOcTree &tree) const |
Return true, if occupied cell is between origin and p. | |
Protected Attributes | |
ros::Publisher | grid_pub_ |
Grid points publisher. | |
bool | m_bCamModelInitialized |
Is camera model initialized? | |
bool | m_bFilterInitialized |
Initialized. | |
std::string | m_camera_info_topic |
Camera info topic name. | |
image_geometry::PinholeCameraModel | m_camera_model |
Camera model. | |
cv::Size | m_camera_size |
Camera size. | |
int | m_camera_stereo_offset_left |
Camera offsets. | |
int | m_camera_stereo_offset_right |
ros::Subscriber | m_ciSubscriber |
Camera info subscriber. | |
tPointCloudConstPtr | m_cloudPtr |
Point cloud. | |
tPointCloud::Ptr | m_filtered_cloud |
Output filtered cloud. | |
boost::mutex | m_lockCamera |
Camera info locking. | |
boost::mutex | m_lockData |
Input cloud lock. | |
float | m_miss_speedup |
Speedup of integrate miss no time function. | |
long | m_numLeafsOutOfCone |
Number of leafs out of sensor cone. | |
long | m_numLeafsRemoved |
Number of removed leafs. | |
std_msgs::Header | m_sensor_header |
Sensor frame id. | |
octomap::point3d | m_sensor_origin |
tf::TransformListener | m_tfListener |
Transform listener. | |
pcl::VoxelGrid< tPclPoint > | m_vgfilter |
Use voxel filter to downsample pointcloud. | |
ros::Publisher | marker_pub_ |
Visualizations marker publisher. |
Definition at line 41 of file octomap_filter_raycast.h.
srs_env_model::COcFilterRaycast::COcFilterRaycast | ( | const std::string & | octree_frame_id, |
ERunMode | mode = FILTER_ALLWAYS |
||
) |
void srs_env_model::COcFilterRaycast::cameraInfoCB | ( | const sensor_msgs::CameraInfo::ConstPtr & | cam_info | ) | [protected] |
Camera info callback.
Camera ifo callback - initialize camera model
Definition at line 113 of file octomap_filter_raycast.cpp.
void srs_env_model::COcFilterRaycast::computeBBX | ( | const std_msgs::Header & | sensor_header, |
octomap::point3d & | bbx_min, | ||
octomap::point3d & | bbx_max | ||
) | [protected] |
void srs_env_model::COcFilterRaycast::filterInternal | ( | tButServerOcTree & | tree | ) | [protected, virtual] |
Filtering function implementation.
Filtering function implementation
Reimplemented from srs_env_model::COcTreeFilterBase.
Definition at line 133 of file octomap_filter_raycast.cpp.
octomap::point3d srs_env_model::COcFilterRaycast::getSensorOrigin | ( | const std_msgs::Header & | sensor_header | ) | [protected] |
Compute sensor origin from the header info.
Compute sensor origin from the header
Definition at line 347 of file octomap_filter_raycast.cpp.
void srs_env_model::COcFilterRaycast::init | ( | ros::NodeHandle & | node_handle | ) | [virtual] |
Initialize. Must be called before first filtering.
Initialize. Must be called before first filtering
Definition at line 64 of file octomap_filter_raycast.cpp.
bool srs_env_model::COcFilterRaycast::inSensorCone | ( | const cv::Point2d & | uv | ) | const [protected] |
Is point in sensor cone?
Definition at line 392 of file octomap_filter_raycast.cpp.
bool srs_env_model::COcFilterRaycast::isOccludedMap | ( | const octomap::point3d & | sensor_origin, |
const octomap::point3d & | p, | ||
double | resolution, | ||
tButServerOcTree & | tree | ||
) | const [protected] |
Return true, if occupied cell is between origin and p.
Return true, if occupied cell is between origin and p
Definition at line 406 of file octomap_filter_raycast.cpp.
void srs_env_model::COcFilterRaycast::setCloud | ( | tPointCloudConstPtr | cloud | ) |
Configure filter before each frame. Set input cloud.
Set input cloud. Must be called before filter call
Definition at line 94 of file octomap_filter_raycast.cpp.
void srs_env_model::COcFilterRaycast::writeLastRunInfo | ( | ) | [virtual] |
Write some info about last filter run.
Reimplemented from srs_env_model::COcTreeFilterBase.
Definition at line 103 of file octomap_filter_raycast.cpp.
Grid points publisher.
Definition at line 124 of file octomap_filter_raycast.h.
Is camera model initialized?
Definition at line 95 of file octomap_filter_raycast.h.
Initialized.
Definition at line 80 of file octomap_filter_raycast.h.
std::string srs_env_model::COcFilterRaycast::m_camera_info_topic [protected] |
Camera info topic name.
Definition at line 104 of file octomap_filter_raycast.h.
Camera model.
Definition at line 92 of file octomap_filter_raycast.h.
cv::Size srs_env_model::COcFilterRaycast::m_camera_size [protected] |
Camera size.
Definition at line 89 of file octomap_filter_raycast.h.
int srs_env_model::COcFilterRaycast::m_camera_stereo_offset_left [protected] |
Camera offsets.
Definition at line 86 of file octomap_filter_raycast.h.
int srs_env_model::COcFilterRaycast::m_camera_stereo_offset_right [protected] |
Definition at line 86 of file octomap_filter_raycast.h.
Camera info subscriber.
Definition at line 107 of file octomap_filter_raycast.h.
tPointCloudConstPtr srs_env_model::COcFilterRaycast::m_cloudPtr [protected] |
Point cloud.
Definition at line 110 of file octomap_filter_raycast.h.
tPointCloud::Ptr srs_env_model::COcFilterRaycast::m_filtered_cloud [protected] |
Output filtered cloud.
Definition at line 130 of file octomap_filter_raycast.h.
boost::mutex srs_env_model::COcFilterRaycast::m_lockCamera [protected] |
Camera info locking.
Definition at line 98 of file octomap_filter_raycast.h.
boost::mutex srs_env_model::COcFilterRaycast::m_lockData [protected] |
Input cloud lock.
Definition at line 101 of file octomap_filter_raycast.h.
float srs_env_model::COcFilterRaycast::m_miss_speedup [protected] |
Speedup of integrate miss no time function.
Definition at line 133 of file octomap_filter_raycast.h.
long srs_env_model::COcFilterRaycast::m_numLeafsOutOfCone [protected] |
Number of leafs out of sensor cone.
Definition at line 116 of file octomap_filter_raycast.h.
long srs_env_model::COcFilterRaycast::m_numLeafsRemoved [protected] |
Number of removed leafs.
Definition at line 113 of file octomap_filter_raycast.h.
Sensor frame id.
Definition at line 77 of file octomap_filter_raycast.h.
octomap::point3d srs_env_model::COcFilterRaycast::m_sensor_origin [protected] |
Definition at line 118 of file octomap_filter_raycast.h.
Transform listener.
Definition at line 83 of file octomap_filter_raycast.h.
pcl::VoxelGrid<tPclPoint> srs_env_model::COcFilterRaycast::m_vgfilter [protected] |
Use voxel filter to downsample pointcloud.
Definition at line 127 of file octomap_filter_raycast.h.
Visualizations marker publisher.
Definition at line 121 of file octomap_filter_raycast.h.