|
rapid
A ROS robotics library.
|
Namespaces | |
| pr2 | |
Classes | |
| class | Box3DRoiServer |
| class | HSurface |
| class | ImageRecognizer |
| class | Object |
| class | PoseEstimator |
| class | PoseEstimationHeatMapper |
| class | PoseEstimationInterface |
| class | PoseEstimationMatch |
| class | RandomHeatMapper |
| class | Scene |
| struct | SceneParseParams |
| struct | HSurfaceParams |
| struct | ObjectParams |
| struct | ParseParams |
| class | ObjectViz |
| class | HSurfaceViz |
| class | SceneViz |
Functions | |
| void | CloudToImage (const sensor_msgs::CameraInfo &camera_info, const pcl::PointCloud< pcl::PointXYZRGB > &cloud, cv::Mat *image) |
| void | CloudToImage (const sensor_msgs::CameraInfo &camera_info, const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const pcl::PointIndices::Ptr &indices, cv::Mat *image) |
| sensor_msgs::CameraInfo | HeadMountKinectCameraInfo () |
| PointCloud< PointXYZRGB >::Ptr | PclFromRos (const PointCloud2 &msg) |
| PointCloud2::Ptr | RosFromPcl (PointCloud< PointXYZRGB >::Ptr cloud) |
| double | ComputeIcpFitness (pcl::PointCloud< pcl::PointXYZRGB >::Ptr &scene, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &object, const rapid_msgs::Roi3D &roi) |
| cv::Mat | ReadMeanFile (const std::string &mean_file, const cv::Size &input_geometry, int num_channels, std::string *error=NULL) |
| static bool | PairCompare (const std::pair< float, int > &lhs, const std::pair< float, int > &rhs) |
| static std::vector< int > | Argmax (const std::vector< float > &v, int N) |
| bool | ComparePoseEstimationMatch (const PoseEstimationMatch &a, const PoseEstimationMatch &b) |
| void | VisualizeMatches (ros::Publisher &pub, ros::Publisher &marker_pub, const std::vector< PoseEstimationMatch > &matches) |
| void | ClosestAxis (const Eigen::Matrix3d &mat, const Eigen::Vector3d &vec, int *index, double *cosine_sim) |
| bool | FindHorizontalPlane (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, double distance_threshold, double eps_angle, pcl::PointIndices::Ptr inliers) |
| bool | FindHorizontalPlane (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices, double distance_threshold, double eps_angle, pcl::PointIndices::Ptr inliers) |
| void | GetBoundingBox (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices, geometry_msgs::PoseStamped *midpoint, geometry_msgs::Vector3 *dimensions) |
| void | GetPlanarBoundingBox (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices, geometry_msgs::Pose *midpoint, geometry_msgs::Vector3 *dimensions) |
| void | GetPlanarBoundingBox (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, geometry_msgs::Pose *midpoint, geometry_msgs::Vector3 *dimensions) |
| pcl::PointCloud < pcl::PointXYZRGB >::Ptr | IndicesToCloud (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices) |
| double | ComputeResolution (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud) |
| double | ComputeResolution (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::search::Search< pcl::PointXYZRGB > &tree) |
| pcl::PointCloud < pcl::PointXYZRGB >::Ptr | Average (const std::vector< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > &clouds) |
| pcl::PointCloud < pcl::PointXYZRGB >::Ptr | GetSmoothedKinectCloud (const std::string &topic, int num_clouds=5) |
| ParseParams | Pr2Params () |
| bool | ParseScene (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const ParseParams ¶ms, Scene *scene) |
| bool | ParseHSurface (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices, const ParseParams ¶ms, HSurface *surface) |
| bool | ParseObjects (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud, const pcl::PointIndices::ConstPtr &indices, const ParseParams ¶ms, std::vector< Object > *objects) |
|
static |
| pcl::PointCloud<pcl::PointXYZRGB>::Ptr rapid::perception::Average | ( | const std::vector< pcl::PointCloud< pcl::PointXYZRGB >::Ptr > & | clouds | ) |
| void rapid::perception::ClosestAxis | ( | const Eigen::Matrix3d & | mat, |
| const Eigen::Vector3d & | vec, | ||
| int * | index, | ||
| double * | cosine_sim | ||
| ) |
| void rapid::perception::CloudToImage | ( | const sensor_msgs::CameraInfo & | camera_info, |
| const pcl::PointCloud< pcl::PointXYZRGB > & | cloud, | ||
| cv::Mat * | image | ||
| ) |
| void rapid::perception::CloudToImage | ( | const sensor_msgs::CameraInfo & | camera_info, |
| const pcl::PointCloud< pcl::PointXYZRGB > & | cloud, | ||
| const pcl::PointIndices::Ptr & | indices, | ||
| cv::Mat * | image | ||
| ) |
| bool rapid::perception::ComparePoseEstimationMatch | ( | const PoseEstimationMatch & | a, |
| const PoseEstimationMatch & | b | ||
| ) |
| double rapid::perception::ComputeIcpFitness | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | scene, |
| pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | object, | ||
| const rapid_msgs::Roi3D & | roi | ||
| ) |
| double rapid::perception::ComputeResolution | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud | ) |
| double rapid::perception::ComputeResolution | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| const pcl::search::Search< pcl::PointXYZRGB > & | tree | ||
| ) |
| bool rapid::perception::FindHorizontalPlane | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| double | distance_threshold, | ||
| double | eps_angle, | ||
| pcl::PointIndices::Ptr | inliers | ||
| ) |
| bool rapid::perception::FindHorizontalPlane | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| const pcl::PointIndices::ConstPtr & | indices, | ||
| double | distance_threshold, | ||
| double | eps_angle, | ||
| pcl::PointIndices::Ptr | inliers | ||
| ) |
| void rapid::perception::GetBoundingBox | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| const pcl::PointIndices::ConstPtr & | indices, | ||
| geometry_msgs::PoseStamped * | midpoint, | ||
| geometry_msgs::Vector3 * | dimensions | ||
| ) |
| void rapid::perception::GetPlanarBoundingBox | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| const pcl::PointIndices::ConstPtr & | indices, | ||
| geometry_msgs::Pose * | midpoint, | ||
| geometry_msgs::Vector3 * | dimensions | ||
| ) |
| void rapid::perception::GetPlanarBoundingBox | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| geometry_msgs::Pose * | midpoint, | ||
| geometry_msgs::Vector3 * | dimensions | ||
| ) |
| pcl::PointCloud<pcl::PointXYZRGB>::Ptr rapid::perception::GetSmoothedKinectCloud | ( | const std::string & | topic, |
| int | num_clouds = 5 |
||
| ) |
| sensor_msgs::CameraInfo rapid::perception::HeadMountKinectCameraInfo | ( | ) |
| pcl::PointCloud<pcl::PointXYZRGB>::Ptr rapid::perception::IndicesToCloud | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| const pcl::PointIndices::ConstPtr & | indices | ||
| ) |
|
static |
| bool rapid::perception::ParseHSurface | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| const pcl::PointIndices::ConstPtr & | indices, | ||
| const ParseParams & | params, | ||
| HSurface * | surface | ||
| ) |
| bool rapid::perception::ParseObjects | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| const pcl::PointIndices::ConstPtr & | indices, | ||
| const ParseParams & | params, | ||
| std::vector< Object > * | objects | ||
| ) |
| bool rapid::perception::ParseScene | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud, |
| const ParseParams & | params, | ||
| Scene * | scene | ||
| ) |
| PointCloud<PointXYZRGB>::Ptr rapid::perception::PclFromRos | ( | const PointCloud2 & | msg | ) |
Definition at line 15 of file conversions.h.
| ParseParams rapid::perception::Pr2Params | ( | ) |
| cv::Mat rapid::perception::ReadMeanFile | ( | const std::string & | mean_file, |
| const cv::Size & | input_geometry, | ||
| int | num_channels, | ||
| std::string * | error = NULL |
||
| ) |
| PointCloud2::Ptr rapid::perception::RosFromPcl | ( | PointCloud< PointXYZRGB >::Ptr | cloud | ) |
Definition at line 21 of file conversions.h.
| void rapid::perception::VisualizeMatches | ( | ros::Publisher & | pub, |
| ros::Publisher & | marker_pub, | ||
| const std::vector< PoseEstimationMatch > & | matches | ||
| ) |