dynamic_obstacle_tracking
detectes and track dynamic obstacles in pointcloud
Public Member Functions | Protected Attributes | Private Member Functions | List of all members
ZR300 Class Reference
Inheritance diagram for ZR300:
datmo::cloud_segmentation

Public Member Functions

 ZR300 ()
 
 ~ZR300 ()
 
void init (ros::NodeHandle &nh, ros::NodeHandle &private_nh)
 
- Public Member Functions inherited from datmo::cloud_segmentation
 cloud_segmentation ()
 
 ~cloud_segmentation ()
 
void init (ros::NodeHandle &nh, ros::NodeHandle &private_nh)
 

Protected Attributes

dynamic_reconfigure::Server< dynamic_obstacle_tracking::zr300Config > server
 
dynamic_reconfigure::Server< dynamic_obstacle_tracking::zr300Config >::CallbackType cb_type
 
- Protected Attributes inherited from datmo::cloud_segmentation
ros::Publisher pub
 publish point cloud after transforming it to base_link on topic /transformed_points More...
 
ros::Publisher pub_2
 Publish pointcloud with dynamic obstacles on topic /dynamic_points. More...
 
ros::Publisher pub_3
 Publish pointcloud with dynamic obstacles on topic /dynamic_points. More...
 
ros::Publisher centroids_pub
 Publish geometry_msgs::PoseArray centroids of dynamic obstacles on topic /object_centroids. More...
 
ros::Subscriber sub
 subscribes sensor_msgs::PointCloud2 from topic /cloud More...
 
tf::TransformListener listener
 A TF listener. More...
 
tf::TransformBroadcaster br
 TF brodcaster to broadcast relative transfom between current pointcloud and prev PointCloud. More...
 
tf::StampedTransform current_cloud_transform
 Container to store transform of latest pointcloud wrt /odom. More...
 
tf::StampedTransform ref_cloud_transform
 Container to store transform of reference pointcloud wrt /odom. More...
 
tf::StampedTransform prev_cloud_transform
 Container to store transform of previous pointcloud wrt /odom. More...
 
pcl::PointCloud< pcl::PointXYZ >::Ptr cloud_transformed
 container to store current pointcloud after transforming it to /base_link frame from /sensor frame More...
 
pcl::PointCloud< pcl::PointXYZ >::Ptr obj_cloud
 container to store pointcloud having both static and dynamic objects More...
 
pcl::PointCloud< pcl::PointXYZ >::Ptr ref_obj_cloud
 container to store object cloud to be used as reference for comparing with object cloud at current time step for octree based spatial change detection More...
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr occuluded_cloud
 container to store the points at current timestep that are in the areas which were occuluded in reference object cloud. (Green in colour) More...
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr new_discovered_cloud
 Container to store points at current timestep that are in the areas which are newly discovered. (Blue in colour) More...
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr filtered_dynamic_cloud
 Container to store filtered dynamic cloud (Red in colour) = dynamic_cloud - occuluded_cloud - new_discovered_cloud. More...
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr classified_cloud
 Container to store final classified cloud = filtered_dynamic_cloud(Red) + occuluded_cloud(Green) + new_discovered_cloud(Blue) More...
 
vector< pcl::PointCloud< pcl::PointXYZ >::Ptr, Eigen::aligned_allocator< pcl::PointCloud< pcl::PointXYZ >::Ptr > > sourceClouds
 vector to store the "OCTREE_WINDOW" number of obj_cloud in the memory More...
 
vector< tf::StampedTransform > sourceTransforms
 Vector to store corresponding Transforms of each PointCloud in sourceClouds /odom to /base_link. More...
 
Eigen::Affine3d odom_transform_matrix
 Container to store relative transform between obj_cloud and ref_obj_cloud. More...
 
Eigen::Affine3f icp_transform_matrix
 
int counter
 
string frame_id
 
string base_frame_id
 
string sensor_frame_id
 
bool ENABLE_ICP
 Enable use of ICP to better match obj_cloud with ref_obj_cloud : Default it is disabled bcoz of bad results. More...
 
bool ENABLE_GROUND_REMOVAL
 Enable use of ransac plane fitting to remove ground points : Default it is disabled for ZR300 and enabled for Velodyne. More...
 
bool ENABLE_VOXELISE
 Enable voxel filter: Default it is enable for ZR300 and disabled for Velodyne. More...
 
bool ENABLE_OCCLUSION_DETECTION
 Enable Occlusion detection so as to prevent false dynamic obstacles detection due to shadow : Default it is enabled for ZR300 and enabled for Velodyne. More...
 
float VOXEL_LEAF_SIZE
 
bool ENABLE_SOR
 Enable Statistical Outlier removal filter: Default it is enable for ZR300 and disabled for Velodyne. More...
 
float SOR_MEAN_K
 number of neighbors to analyze for each point More...
 
float SOR_STD_DEV_MUL_THRESH
 distance in multiples of std dev after which point is considered an outlier More...
 
float PASS_X_MIN
 minimum value in x direction More...
 
float PASS_X_MAX
 maximum value in x direction More...
 
float PASS_Y_MIN
 minimum value in y direction More...
 
float PASS_Y_MAX
 maximum value in y direction More...
 
float PASS_Z_MIN
 minimum value in z direction More...
 
float PASS_Z_MAX
 maximum value in z direction More...
 
int OCTREE_WINDOW
 This parameter defines that current pointcloud will be compared with "OCTREE_WINDOW" times previous pointcloud for spatial change detection. More...
 
float OCTREE_RESOLUTION
 smallest dimension of octree leaf node More...
 
float SEG_CLUSTER_TOLERANCE
 Maximum distance between two points to be included in same cluster. More...
 
int SEG_MIN_CLUSTER_SIZE
 Minimum number of points that should be present within a cluster. More...
 
int SEG_MAX_CLUSTER_SIZE
 Maximum number points to be included in same cluster. More...
 

Private Member Functions

void dynamic_reconfigure_cb (dynamic_obstacle_tracking::zr300Config &config, uint32_t level)
 

Constructor & Destructor Documentation

◆ ZR300()

ZR300::ZR300 ( )

◆ ~ZR300()

ZR300::~ZR300 ( )

Member Function Documentation

◆ dynamic_reconfigure_cb()

void ZR300::dynamic_reconfigure_cb ( dynamic_obstacle_tracking::zr300Config &  config,
uint32_t  level 
)
private

◆ init()

void ZR300::init ( ros::NodeHandle &  nh,
ros::NodeHandle &  private_nh 
)

Member Data Documentation

◆ cb_type

dynamic_reconfigure::Server<dynamic_obstacle_tracking::zr300Config>::CallbackType ZR300::cb_type
protected

◆ server

dynamic_reconfigure::Server<dynamic_obstacle_tracking::zr300Config> ZR300::server
protected

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