pcodar
- Point Cloud Object Detection¶
The PCODAR system is responsible for coordinating LIDAR data into a database of usable objects associated with locations.
Type Aliases¶
-
using pcodar::Config = point_cloud_object_detection_and_recognition::PCODARConfig¶
Alias for the dynamic reconfigure object used for PCODAR configuration.
-
using pcodar::point_t = pcl::PointXYZ¶
Alias for type of pointcloud used internally.
-
using pcodar::point_cloud_ptr = point_cloud::Ptr¶
Pointer to PCODAR’s pointclouds.
-
using pcodar::point_cloud_const_ptr = point_cloud::ConstPtr¶
Constant pointer to PCODAR’s pointclouds.
-
using pcodar::cluster_t = pcl::PointIndices¶
Clusters used in object detection.
Classes¶
InputCloudFilter¶
- funcInputCloudFilter
- funcfilter
- funcset_bounds
- funcset_robot_footprint
- funcset_robot_pose
-
class InputCloudFilter¶
Filters a single incoming pointcloud after it has been transformed into global frame. Removes points outside of a specified “bounds” polygon and points inside a specified robot footprint polygon.
Public Functions
-
InputCloudFilter()¶
-
void filter(point_cloud_const_ptr in, point_cloud &pc)¶
Filters @in, storing resulting pointcloud into @pc.
-
void set_bounds(point_cloud_ptr bounds)¶
Sets the bounds with a pointcloud where each point is a verticie of the bounds polygon.
-
void set_robot_footprint(Eigen::Vector4f const &min, Eigen::Vector4f const &max)¶
Set the robot footprint with a pointcloud in the robot’s local frame where each point is a verticie of the footprint polygon
-
void set_robot_pose(Eigen::Affine3d const &transform)¶
Sets the transform from the global frame to the robot, should be called before @filter.
-
InputCloudFilter()¶
MarkerManager¶
- funcinitialize
- funcreset
- funcupdate_markers
-
class MarkerManager¶
Publishes interactive markers visualizing the objects in the database and allowing the user to modify classification in RVIZ.
Associator¶
- funcassociate
- funcupdate_config
-
class Associator¶
Associates recently identified objects with previous objects so they persist over time. This is accomplished by finding the nearest neighbor point, creating a new object if this is greater than a maximum distance.
Public Functions
-
void update_config(Config const &config)¶
Update the dynamic reconfigure parameters associated with this class.
-
void associate(ObjectMap &prev_objects, point_cloud const &pc, clusters_t clusters)¶
Associate old objects with newly identified clusters. @prev_objects is updated + appended in place for new associations
-
void update_config(Config const &config)¶
ObjectDetector¶
- funcget_clusters
- funcupdate_config
-
class ObjectDetector¶
Detects objects in a pointcloud by clustering points that are nearby.
Public Functions
-
clusters_t get_clusters(point_cloud_const_ptr pc)¶
Returns an array of clusters found in @pc.
-
clusters_t get_clusters(point_cloud_const_ptr pc)¶
Object¶
- funcObject
- funcas_msg
- funcget_center
- funcget_points
- funcget_points_ptr
- funcget_search_tree
- funcset_classification
- funcset_id
- funcupdate_points
-
class Object¶
Represents an object, a persistent clustered set of points that are nearby. Objects can have associated labels and other metadata.
Public Functions
-
Object(point_cloud_ptr const &pc, uint id, KdTreePtr const &search_tree)¶
Create an object from a pointcloud of points associated with.
-
void update_points(point_cloud_ptr const &pc, KdTreePtr const &search_tree)¶
Update the points associated with an object.
-
point_cloud const &get_points() const¶
-
point_cloud_ptr get_points_ptr() const¶
-
mil_msgs::PerceptionObject const &as_msg() const¶
-
void set_classification(std::string const &classification)¶
-
void set_id(uint id)¶
Friends
- friend class mil_gazebo::PCODARGazebo
-
Object(point_cloud_ptr const &pc, uint id, KdTreePtr const &search_tree)¶
ObjectMap¶
- funcDatabaseQuery
- funcObjectMap
- funcadd_object
- funcerase_object
- functo_msg
-
class ObjectMap¶
Contains a map of unique integer identifiers to objects (point clusters).
Public Functions
-
ObjectMap()¶
-
mil_msgs::PerceptionObjectArray to_msg()¶
Creates a ROS message of the objects to publish / use for markers.
-
bool DatabaseQuery(mil_msgs::ObjectDBQuery::Request &req, mil_msgs::ObjectDBQuery::Response &res)¶
Processes a database query service request.
-
uint add_object(point_cloud_ptr const &pc, KdTreePtr const &search_tree)¶
Add a new object by its pointcloud, given it a new unique id.
Public Members
-
std::unordered_map<uint, Object> objects_¶
Internal map of id’s to objects TODO: make private and provide function interfaces
-
std::vector<uint> just_removed_¶
Recently removed objects, for marker manager.
-
size_t highest_id_¶
The id that will be assigned to the next new object, starting at 0.
-
ObjectMap()¶
OgridManager¶
- funcOgridManager
- funcdraw_boundary
- funcinitialize
- funcset_bounds
- funcupdate_config
- funcupdate_ogrid
-
class OgridManager¶
NodeBase¶
- funcNodeBase
- funcUpdateObjects
- funcinitialize
-
class NodeBase¶
Base class for a class implementing the object detection needed for the PCODAR node. This can be fulfilled by processesing LIDAR pointclouds (like in @pcodarNode) or using simulated ground truth (like in pcodar_gazebo).
Subclassed by pcodar::Node
Node¶
- func()
- funcNode
- funcvelodyne_cb
PersistentCloudFilter¶
- funcPersistentCloudFilter
- funcfilter
- funcupdate_config
-
class PersistentCloudFilter¶
PointCloudCircularBuffer¶
- funcPointCloudCircularBuffer
- funcadd_point_cloud
- funcclear
- funcget_point_cloud
- funcupdate_config
-
class PointCloudCircularBuffer¶
Buffer of n most recently added pointclouds, used to assemble a persistent pointcloud of pointclouds accumulated over time.
Public Functions
-
PointCloudCircularBuffer()¶
-
point_cloud_ptr get_point_cloud()¶
Get accumulated pointcloud from buffered pointclouds, or nullptr if N pointclouds have not yet been added.
-
void add_point_cloud(const point_cloud_ptr &pc)¶
Add a pointcloud to the back of the buffer, deleting the oldest if it is full.
-
void update_config(Config const &config)¶
Update the number of pointclouds from the dynamic reconfigure object.
-
void clear()¶
Clear buffer.
-
PointCloudCircularBuffer()¶