Namespaces | |
| namespace | srv |
Classes | |
| struct | AddManualKeyframe |
| struct | AddManualKeyframeRequest_ |
| struct | AddManualKeyframeResponse_ |
| class | FeatureDetector |
| Base class for sparse feature extractors. More... | |
| class | FeatureHistory |
| Auxiliary class for the frame-to-frame ICP class. More... | |
| class | FeatureViewer |
| Application to test and visualize the different type of feature detectors. More... | |
| struct | GenerateGraph |
| struct | GenerateGraphRequest_ |
| struct | GenerateGraphResponse_ |
| class | GftDetector |
| GoodFeaturesToTrack detector. More... | |
| class | KeyframeAssociation |
| Class representing an association between two keyframes, used for graph-based pose alignement. More... | |
| class | KeyframeGraphDetector |
| Detects graph correspondences based on visual feature matching between keyframes. More... | |
| class | KeyframeGraphSolver |
| Base class for graph-based global alignment classes. More... | |
| class | KeyframeGraphSolverG2O |
| Graph-based global alignement using g2o (generalized graph optimizaiton) More... | |
| class | KeyframeMapper |
| Builds a 3D map from a series of RGBD keyframes. More... | |
| struct | Load |
| struct | LoadRequest_ |
| struct | LoadResponse_ |
| class | MotionEstimation |
| Base class for visual odometry motion estimation methods. More... | |
| class | MotionEstimationICP |
| Frame-to-frame ICP motion estimation. More... | |
| class | MotionEstimationICPProbModel |
| Motion estimation based on aligning sparse features against a persistent, dynamic model. More... | |
| class | OrbDetector |
| ORB detector. More... | |
| struct | PublishKeyframe |
| struct | PublishKeyframeRequest_ |
| struct | PublishKeyframeResponse_ |
| struct | PublishKeyframes |
| struct | PublishKeyframesRequest_ |
| struct | PublishKeyframesResponse_ |
| class | RGBDFrame |
| Auxiliarry class that holds together rgb and depth images. More... | |
| class | RGBDImageProc |
| Processes the raw output of OpenNI sensors to create a stream of RGB-D images. More... | |
| class | RGBDImageProcNodelet |
| Nodelet driver for the RGBDImageProc class. More... | |
| class | RGBDKeyframe |
| Extension of an RGBDFrame, which has a pose, and a 3D point cloud. More... | |
| struct | Save |
| struct | SaveRequest_ |
| struct | SaveResponse_ |
| struct | SolveGraph |
| struct | SolveGraphRequest_ |
| struct | SolveGraphResponse_ |
| class | StarDetector |
| STAR detector. More... | |
| class | SurfDetector |
| SURF detector. More... | |
| class | VisualOdometry |
| Subscribes to incoming RGBD images and outputs the position of the moving (base) frame wrt some fixed frame. More... | |
Typedefs | |
| typedef ::ccny_rgbd::AddManualKeyframeRequest_ < std::allocator< void > > | AddManualKeyframeRequest |
| typedef boost::shared_ptr < ::ccny_rgbd::AddManualKeyframeRequest const > | AddManualKeyframeRequestConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::AddManualKeyframeRequest > | AddManualKeyframeRequestPtr |
| typedef ::ccny_rgbd::AddManualKeyframeResponse_ < std::allocator< void > > | AddManualKeyframeResponse |
| typedef boost::shared_ptr < ::ccny_rgbd::AddManualKeyframeResponse const > | AddManualKeyframeResponseConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::AddManualKeyframeResponse > | AddManualKeyframeResponsePtr |
| typedef std::vector< bool > | BoolVector |
| typedef sensor_msgs::CameraInfo | CameraInfoMsg |
| typedef message_filters::Subscriber < CameraInfoMsg > | CameraInfoSubFilter |
| typedef dynamic_reconfigure::Server < FeatureDetectorConfig > | FeatureDetectorConfigServer |
| typedef boost::shared_ptr < FeatureDetector > | FeatureDetectorPtr |
| typedef std::vector< float > | FloatVector |
| typedef ::ccny_rgbd::GenerateGraphRequest_ < std::allocator< void > > | GenerateGraphRequest |
| typedef boost::shared_ptr < ::ccny_rgbd::GenerateGraphRequest const > | GenerateGraphRequestConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::GenerateGraphRequest > | GenerateGraphRequestPtr |
| typedef ::ccny_rgbd::GenerateGraphResponse_ < std::allocator< void > > | GenerateGraphResponse |
| typedef boost::shared_ptr < ::ccny_rgbd::GenerateGraphResponse const > | GenerateGraphResponseConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::GenerateGraphResponse > | GenerateGraphResponsePtr |
| typedef dynamic_reconfigure::Server < GftDetectorConfig > | GftDetectorConfigServer |
| typedef boost::shared_ptr < GftDetectorConfigServer > | GftDetectorConfigServerPtr |
| typedef boost::shared_ptr < GftDetector > | GftDetectorPtr |
| typedef sensor_msgs::Image | ImageMsg |
| typedef image_transport::Publisher | ImagePublisher |
| typedef image_transport::SubscriberFilter | ImageSubFilter |
| typedef image_transport::ImageTransport | ImageTransport |
| typedef std::vector< int > | IntVector |
| typedef pcl::KdTreeFLANN < PointFeature > | KdTree |
| typedef Eigen::aligned_allocator < RGBDKeyframe > | KeyframeAllocator |
| typedef Eigen::aligned_allocator < KeyframeAssociation > | KeyframeAssociationAllocator |
| typedef std::vector < KeyframeAssociation, KeyframeAssociationAllocator > | KeyframeAssociationVector |
| typedef std::vector < RGBDKeyframe, KeyframeAllocator > | KeyframeVector |
| typedef std::vector< cv::KeyPoint > | KeypointVector |
| typedef ::ccny_rgbd::LoadRequest_ < std::allocator< void > > | LoadRequest |
| typedef boost::shared_ptr < ::ccny_rgbd::LoadRequest const > | LoadRequestConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::LoadRequest > | LoadRequestPtr |
| typedef ::ccny_rgbd::LoadResponse_ < std::allocator< void > > | LoadResponse |
| typedef boost::shared_ptr < ::ccny_rgbd::LoadResponse const > | LoadResponseConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::LoadResponse > | LoadResponsePtr |
| typedef Eigen::Matrix3f | Matrix3f |
| typedef std::vector < Eigen::Matrix3f > | Matrix3fVector |
| typedef nav_msgs::Odometry | OdomMsg |
| typedef dynamic_reconfigure::Server < OrbDetectorConfig > | OrbDetectorConfigServer |
| typedef boost::shared_ptr < OrbDetectorConfigServer > | OrbDetectorConfigServerPtr |
| typedef boost::shared_ptr < OrbDetector > | OrbDetectorPtr |
| typedef nav_msgs::Path | PathMsg |
| typedef image_geometry::PinholeCameraModel | PinholeCameraModel |
| typedef std::vector< cv::Point2f > | Point2fVector |
| typedef std::vector< cv::Point3f > | Point3fVector |
| typedef pcl::PointCloud < PointFeature > | PointCloudFeature |
| typedef pcl::PointCloud< PointT > | PointCloudT |
| typedef pcl::PointXYZ | PointFeature |
| typedef pcl::PointXYZRGB | PointT |
| typedef ::ccny_rgbd::PublishKeyframeRequest_ < std::allocator< void > > | PublishKeyframeRequest |
| typedef boost::shared_ptr < ::ccny_rgbd::PublishKeyframeRequest const > | PublishKeyframeRequestConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::PublishKeyframeRequest > | PublishKeyframeRequestPtr |
| typedef ::ccny_rgbd::PublishKeyframeResponse_ < std::allocator< void > > | PublishKeyframeResponse |
| typedef boost::shared_ptr < ::ccny_rgbd::PublishKeyframeResponse const > | PublishKeyframeResponseConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::PublishKeyframeResponse > | PublishKeyframeResponsePtr |
| typedef ::ccny_rgbd::PublishKeyframesRequest_ < std::allocator< void > > | PublishKeyframesRequest |
| typedef boost::shared_ptr < ::ccny_rgbd::PublishKeyframesRequest const > | PublishKeyframesRequestConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::PublishKeyframesRequest > | PublishKeyframesRequestPtr |
| typedef ::ccny_rgbd::PublishKeyframesResponse_ < std::allocator< void > > | PublishKeyframesResponse |
| typedef boost::shared_ptr < ::ccny_rgbd::PublishKeyframesResponse const > | PublishKeyframesResponseConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::PublishKeyframesResponse > | PublishKeyframesResponsePtr |
| typedef message_filters::Synchronizer < RGBDSyncPolicy3 > | RGBDSynchronizer3 |
| typedef message_filters::Synchronizer < RGBDSyncPolicy4 > | RGBDSynchronizer4 |
| typedef message_filters::sync_policies::ApproximateTime < ImageMsg, ImageMsg, CameraInfoMsg > | RGBDSyncPolicy3 |
| typedef message_filters::sync_policies::ApproximateTime < ImageMsg, ImageMsg, CameraInfoMsg, CameraInfoMsg > | RGBDSyncPolicy4 |
| typedef ::ccny_rgbd::SaveRequest_ < std::allocator< void > > | SaveRequest |
| typedef boost::shared_ptr < ::ccny_rgbd::SaveRequest const > | SaveRequestConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::SaveRequest > | SaveRequestPtr |
| typedef ::ccny_rgbd::SaveResponse_ < std::allocator< void > > | SaveResponse |
| typedef boost::shared_ptr < ::ccny_rgbd::SaveResponse const > | SaveResponseConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::SaveResponse > | SaveResponsePtr |
| typedef ::ccny_rgbd::SolveGraphRequest_ < std::allocator< void > > | SolveGraphRequest |
| typedef boost::shared_ptr < ::ccny_rgbd::SolveGraphRequest const > | SolveGraphRequestConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::SolveGraphRequest > | SolveGraphRequestPtr |
| typedef ::ccny_rgbd::SolveGraphResponse_ < std::allocator< void > > | SolveGraphResponse |
| typedef boost::shared_ptr < ::ccny_rgbd::SolveGraphResponse const > | SolveGraphResponseConstPtr |
| typedef boost::shared_ptr < ::ccny_rgbd::SolveGraphResponse > | SolveGraphResponsePtr |
| typedef dynamic_reconfigure::Server < StarDetectorConfig > | StarDetectorConfigServer |
| typedef boost::shared_ptr < StarDetectorConfigServer > | StarDetectorConfigServerPtr |
| typedef boost::shared_ptr < StarDetector > | StarDetectorPtr |
| typedef dynamic_reconfigure::Server < SurfDetectorConfig > | SurfDetectorConfigServer |
| typedef boost::shared_ptr < SurfDetectorConfigServer > | SurfDetectorConfigServerPtr |
| typedef boost::shared_ptr < SurfDetector > | SurfDetectorPtr |
| typedef pcl::registration::TransformationEstimationSVD < PointFeature, PointFeature > | TransformationEstimationSVD |
| typedef Eigen::Vector3f | Vector3f |
| typedef std::vector < Eigen::Vector3f > | Vector3fVector |
Enumerations | |
| enum | DepthFitMode { DEPTH_FIT_LINEAR, DEPTH_FIT_LINEAR_ZERO, DEPTH_FIT_QUADRATIC, DEPTH_FIT_QUADRATIC_ZERO } |
| Polynomial fit modes for depth unwarping. More... | |
Functions | |
| void | buildPointCloud (const cv::Mat &depth_img_rect, const cv::Mat &intr_rect_ir, PointCloudT &cloud) |
| Constructs a point cloud, a depth image and instrinsic matrix. | |
| void | buildPointCloud (const cv::Mat &depth_img_rect_reg, const cv::Mat &rgb_img_rect, const cv::Mat &intr_rect_rgb, PointCloudT &cloud) |
| Constructs a point cloud with color. | |
| void | buildRegisteredDepthImage (const cv::Mat &intr_rect_ir, const cv::Mat &intr_rect_rgb, const cv::Mat &ir2rgb, const cv::Mat &depth_img_rect, cv::Mat &depth_img_rect_reg) |
| reprojects a depth image to another depth image, registered in the rgb camera's frame. | |
| void | convertCameraInfoToMats (const CameraInfoMsg::ConstPtr camera_info_msg, cv::Mat &intr, cv::Mat &dist) |
| Create OpenCV matrices from a CameraInfoMsg. | |
| void | convertMatToCameraInfo (const cv::Mat &intr, CameraInfoMsg &camera_info_msg) |
| Create CameraInfoMsg from OpenCV matrices (assumes no distortion) | |
| void | depthImageFloatTo16bit (const cv::Mat &depth_image_in, cv::Mat &depth_image_out) |
| converts a 32FC1 depth image (in meters) to a 16UC1 depth image (in mm). | |
| Eigen::Matrix4f | eigenFromTf (const tf::Transform &tf) |
| Converts an tf::Transform transform to an Eigen transform. | |
| double | getMsDuration (const ros::WallTime &start) |
| Returns the duration, in ms, from a given time. | |
| void | getTfDifference (const tf::Transform &motion, double &dist, double &angle) |
| Given a transform, calculates the linear and angular distance between it and identity. | |
| void | getTfDifference (const tf::Transform &a, const tf::Transform b, double &dist, double &angle) |
| Given two transformss, calculates the linear and angular distance between them, or the linear and angular components of a.inv() * b. | |
| bool | loadKeyframes (KeyframeVector &keyframes, const std::string &path) |
| Loads a vector of RGBD keyframes to disk. | |
| void | openCVRtToTf (const cv::Mat &R, const cv::Mat &t, tf::Transform &transform) |
| Creates a tf transform from a 3x3 OpenCV rotation matrix and a 3x1 OpenCV translation vector. | |
| PLUGINLIB_DECLARE_CLASS (ccny_rgbd, RGBDImageProcNodelet, RGBDImageProcNodelet, nodelet::Nodelet) | |
| void | pointCloudFromMeans (const Vector3fVector &means, PointCloudFeature &cloud) |
| Creates a pcl point cloud form a vector of eigen matrix means. | |
| void | removeInvalidDistributions (const Vector3fVector &means, const Matrix3fVector &covariances, const BoolVector &valid, Vector3fVector &means_f, Matrix3fVector &covariances_f) |
| Filters out a vector of means and a vector of covariances given a mask of valid entries. | |
| void | removeInvalidMeans (const Vector3fVector &means, const BoolVector &valid, Vector3fVector &means_f) |
| Filters out a vector of means given a mask of valid entries. | |
| bool | saveKeyframes (const KeyframeVector &keyframes, const std::string &path) |
| Saves a vector of RGBD keyframes to disk. | |
| tf::Transform | tfFromEigen (Eigen::Matrix4f trans) |
| Converts an Eigen transform to a tf::Transform. | |
| bool | tfGreaterThan (const tf::Transform &a, double dist, double angle) |
| Given a transfom (possibly computed as a difference between two transforms) checks if either its angular or linar component exceeds a threshold. | |
| void | tfToEigenRt (const tf::Transform &tf, Matrix3f &R, Vector3f &t) |
| Decomposes a tf into an Eigen 3x3 rotation matrix and Eigen 3x1 rotation vector. | |
| void | tfToOpenCVRt (const tf::Transform &transform, cv::Mat &R, cv::Mat &t) |
| Decomposes a tf::Transform into a 3x3 OpenCV rotation matrix and a 3x1 OpenCV translation vector. | |
| void | tfToXYZRPY (const tf::Transform &t, double &x, double &y, double &z, double &roll, double &pitch, double &yaw) |
| Decomposes a tf::Transform into x, y, z, roll, pitch, yaw. | |
| void | transformDistributions (Vector3fVector &means, Matrix3fVector &covariances, const tf::Transform &transform) |
| Transforms a vector of means and covariances. | |
| void | transformMeans (Vector3fVector &means, const tf::Transform &transform) |
| Transforms a vector of means. | |
| void | unwarpDepthImage (cv::Mat &depth_img_in, const cv::Mat &coeff0, const cv::Mat &coeff1, const cv::Mat &coeff2, int fit_mode=DEPTH_FIT_QUADRATIC) |
| Given a depth image, uwarps it according to a polynomial model. | |
| typedef ::ccny_rgbd::AddManualKeyframeRequest_<std::allocator<void> > ccny_rgbd::AddManualKeyframeRequest |
Definition at line 41 of file AddManualKeyframe.h.
| typedef boost::shared_ptr< ::ccny_rgbd::AddManualKeyframeRequest const> ccny_rgbd::AddManualKeyframeRequestConstPtr |
Definition at line 44 of file AddManualKeyframe.h.
| typedef boost::shared_ptr< ::ccny_rgbd::AddManualKeyframeRequest> ccny_rgbd::AddManualKeyframeRequestPtr |
Definition at line 43 of file AddManualKeyframe.h.
| typedef ::ccny_rgbd::AddManualKeyframeResponse_<std::allocator<void> > ccny_rgbd::AddManualKeyframeResponse |
Definition at line 64 of file AddManualKeyframe.h.
| typedef boost::shared_ptr< ::ccny_rgbd::AddManualKeyframeResponse const> ccny_rgbd::AddManualKeyframeResponseConstPtr |
Definition at line 67 of file AddManualKeyframe.h.
| typedef boost::shared_ptr< ::ccny_rgbd::AddManualKeyframeResponse> ccny_rgbd::AddManualKeyframeResponsePtr |
Definition at line 66 of file AddManualKeyframe.h.
| typedef std::vector<bool> ccny_rgbd::BoolVector |
| typedef sensor_msgs::CameraInfo ccny_rgbd::CameraInfoMsg |
| typedef dynamic_reconfigure::Server<FeatureDetectorConfig> ccny_rgbd::FeatureDetectorConfigServer |
| typedef boost::shared_ptr<FeatureDetector> ccny_rgbd::FeatureDetectorPtr |
Definition at line 119 of file feature_detector.h.
| typedef std::vector<float> ccny_rgbd::FloatVector |
| typedef ::ccny_rgbd::GenerateGraphRequest_<std::allocator<void> > ccny_rgbd::GenerateGraphRequest |
Definition at line 41 of file GenerateGraph.h.
| typedef boost::shared_ptr< ::ccny_rgbd::GenerateGraphRequest const> ccny_rgbd::GenerateGraphRequestConstPtr |
Definition at line 44 of file GenerateGraph.h.
| typedef boost::shared_ptr< ::ccny_rgbd::GenerateGraphRequest> ccny_rgbd::GenerateGraphRequestPtr |
Definition at line 43 of file GenerateGraph.h.
| typedef ::ccny_rgbd::GenerateGraphResponse_<std::allocator<void> > ccny_rgbd::GenerateGraphResponse |
Definition at line 64 of file GenerateGraph.h.
| typedef boost::shared_ptr< ::ccny_rgbd::GenerateGraphResponse const> ccny_rgbd::GenerateGraphResponseConstPtr |
Definition at line 67 of file GenerateGraph.h.
| typedef boost::shared_ptr< ::ccny_rgbd::GenerateGraphResponse> ccny_rgbd::GenerateGraphResponsePtr |
Definition at line 66 of file GenerateGraph.h.
| typedef dynamic_reconfigure::Server<GftDetectorConfig> ccny_rgbd::GftDetectorConfigServer |
| typedef boost::shared_ptr<GftDetectorConfigServer> ccny_rgbd::GftDetectorConfigServerPtr |
| typedef boost::shared_ptr<GftDetector> ccny_rgbd::GftDetectorPtr |
Definition at line 74 of file gft_detector.h.
| typedef sensor_msgs::Image ccny_rgbd::ImageMsg |
| typedef std::vector<int> ccny_rgbd::IntVector |
| typedef Eigen::aligned_allocator<RGBDKeyframe> ccny_rgbd::KeyframeAllocator |
Definition at line 100 of file rgbd_keyframe.h.
| typedef Eigen::aligned_allocator<KeyframeAssociation> ccny_rgbd::KeyframeAssociationAllocator |
Definition at line 70 of file keyframe_association.h.
| typedef std::vector<KeyframeAssociation, KeyframeAssociationAllocator> ccny_rgbd::KeyframeAssociationVector |
Definition at line 71 of file keyframe_association.h.
| typedef std::vector<RGBDKeyframe, KeyframeAllocator> ccny_rgbd::KeyframeVector |
Definition at line 101 of file rgbd_keyframe.h.
| typedef std::vector<cv::KeyPoint> ccny_rgbd::KeypointVector |
| typedef ::ccny_rgbd::LoadRequest_<std::allocator<void> > ccny_rgbd::LoadRequest |
| typedef boost::shared_ptr< ::ccny_rgbd::LoadRequest const> ccny_rgbd::LoadRequestConstPtr |
| typedef boost::shared_ptr< ::ccny_rgbd::LoadRequest> ccny_rgbd::LoadRequestPtr |
| typedef ::ccny_rgbd::LoadResponse_<std::allocator<void> > ccny_rgbd::LoadResponse |
| typedef boost::shared_ptr< ::ccny_rgbd::LoadResponse const> ccny_rgbd::LoadResponseConstPtr |
| typedef boost::shared_ptr< ::ccny_rgbd::LoadResponse> ccny_rgbd::LoadResponsePtr |
| typedef Eigen::Matrix3f ccny_rgbd::Matrix3f |
| typedef std::vector<Eigen::Matrix3f> ccny_rgbd::Matrix3fVector |
| typedef nav_msgs::Odometry ccny_rgbd::OdomMsg |
| typedef dynamic_reconfigure::Server<OrbDetectorConfig> ccny_rgbd::OrbDetectorConfigServer |
| typedef boost::shared_ptr<OrbDetectorConfigServer> ccny_rgbd::OrbDetectorConfigServerPtr |
| typedef boost::shared_ptr<OrbDetector> ccny_rgbd::OrbDetectorPtr |
Definition at line 72 of file orb_detector.h.
| typedef nav_msgs::Path ccny_rgbd::PathMsg |
| typedef std::vector<cv::Point2f> ccny_rgbd::Point2fVector |
| typedef std::vector<cv::Point3f> ccny_rgbd::Point3fVector |
| typedef pcl::PointCloud<PointT> ccny_rgbd::PointCloudT |
| typedef pcl::PointXYZ ccny_rgbd::PointFeature |
| typedef pcl::PointXYZRGB ccny_rgbd::PointT |
| typedef ::ccny_rgbd::PublishKeyframeRequest_<std::allocator<void> > ccny_rgbd::PublishKeyframeRequest |
Definition at line 46 of file PublishKeyframe.h.
| typedef boost::shared_ptr< ::ccny_rgbd::PublishKeyframeRequest const> ccny_rgbd::PublishKeyframeRequestConstPtr |
Definition at line 49 of file PublishKeyframe.h.
| typedef boost::shared_ptr< ::ccny_rgbd::PublishKeyframeRequest> ccny_rgbd::PublishKeyframeRequestPtr |
Definition at line 48 of file PublishKeyframe.h.
| typedef ::ccny_rgbd::PublishKeyframeResponse_<std::allocator<void> > ccny_rgbd::PublishKeyframeResponse |
Definition at line 69 of file PublishKeyframe.h.
| typedef boost::shared_ptr< ::ccny_rgbd::PublishKeyframeResponse const> ccny_rgbd::PublishKeyframeResponseConstPtr |
Definition at line 72 of file PublishKeyframe.h.
| typedef boost::shared_ptr< ::ccny_rgbd::PublishKeyframeResponse> ccny_rgbd::PublishKeyframeResponsePtr |
Definition at line 71 of file PublishKeyframe.h.
| typedef ::ccny_rgbd::PublishKeyframesRequest_<std::allocator<void> > ccny_rgbd::PublishKeyframesRequest |
Definition at line 46 of file PublishKeyframes.h.
| typedef boost::shared_ptr< ::ccny_rgbd::PublishKeyframesRequest const> ccny_rgbd::PublishKeyframesRequestConstPtr |
Definition at line 49 of file PublishKeyframes.h.
| typedef boost::shared_ptr< ::ccny_rgbd::PublishKeyframesRequest> ccny_rgbd::PublishKeyframesRequestPtr |
Definition at line 48 of file PublishKeyframes.h.
| typedef ::ccny_rgbd::PublishKeyframesResponse_<std::allocator<void> > ccny_rgbd::PublishKeyframesResponse |
Definition at line 69 of file PublishKeyframes.h.
| typedef boost::shared_ptr< ::ccny_rgbd::PublishKeyframesResponse const> ccny_rgbd::PublishKeyframesResponseConstPtr |
Definition at line 72 of file PublishKeyframes.h.
| typedef boost::shared_ptr< ::ccny_rgbd::PublishKeyframesResponse> ccny_rgbd::PublishKeyframesResponsePtr |
Definition at line 71 of file PublishKeyframes.h.
| typedef ::ccny_rgbd::SaveRequest_<std::allocator<void> > ccny_rgbd::SaveRequest |
| typedef boost::shared_ptr< ::ccny_rgbd::SaveRequest const> ccny_rgbd::SaveRequestConstPtr |
| typedef boost::shared_ptr< ::ccny_rgbd::SaveRequest> ccny_rgbd::SaveRequestPtr |
| typedef ::ccny_rgbd::SaveResponse_<std::allocator<void> > ccny_rgbd::SaveResponse |
| typedef boost::shared_ptr< ::ccny_rgbd::SaveResponse const> ccny_rgbd::SaveResponseConstPtr |
| typedef boost::shared_ptr< ::ccny_rgbd::SaveResponse> ccny_rgbd::SaveResponsePtr |
| typedef ::ccny_rgbd::SolveGraphRequest_<std::allocator<void> > ccny_rgbd::SolveGraphRequest |
Definition at line 41 of file SolveGraph.h.
| typedef boost::shared_ptr< ::ccny_rgbd::SolveGraphRequest const> ccny_rgbd::SolveGraphRequestConstPtr |
Definition at line 44 of file SolveGraph.h.
| typedef boost::shared_ptr< ::ccny_rgbd::SolveGraphRequest> ccny_rgbd::SolveGraphRequestPtr |
Definition at line 43 of file SolveGraph.h.
| typedef ::ccny_rgbd::SolveGraphResponse_<std::allocator<void> > ccny_rgbd::SolveGraphResponse |
Definition at line 64 of file SolveGraph.h.
| typedef boost::shared_ptr< ::ccny_rgbd::SolveGraphResponse const> ccny_rgbd::SolveGraphResponseConstPtr |
Definition at line 67 of file SolveGraph.h.
| typedef boost::shared_ptr< ::ccny_rgbd::SolveGraphResponse> ccny_rgbd::SolveGraphResponsePtr |
Definition at line 66 of file SolveGraph.h.
| typedef dynamic_reconfigure::Server<StarDetectorConfig> ccny_rgbd::StarDetectorConfigServer |
| typedef boost::shared_ptr<StarDetectorConfigServer> ccny_rgbd::StarDetectorConfigServerPtr |
| typedef boost::shared_ptr<StarDetector> ccny_rgbd::StarDetectorPtr |
Definition at line 72 of file star_detector.h.
| typedef dynamic_reconfigure::Server<SurfDetectorConfig> ccny_rgbd::SurfDetectorConfigServer |
| typedef boost::shared_ptr<SurfDetectorConfigServer> ccny_rgbd::SurfDetectorConfigServerPtr |
| typedef boost::shared_ptr<SurfDetector> ccny_rgbd::SurfDetectorPtr |
Definition at line 70 of file surf_detector.h.
| typedef Eigen::Vector3f ccny_rgbd::Vector3f |
| typedef std::vector<Eigen::Vector3f> ccny_rgbd::Vector3fVector |
Polynomial fit modes for depth unwarping.
The modes include:
The recommended mode is DEPTH_FIT_QUADRATIC
Definition at line 41 of file proc_util.h.
| void ccny_rgbd::buildPointCloud | ( | const cv::Mat & | depth_img_rect, |
| const cv::Mat & | intr_rect_ir, | ||
| PointCloudT & | cloud | ||
| ) |
Constructs a point cloud, a depth image and instrinsic matrix.
| depth_img_rect | rectified depth image (16UC1, in mm) |
| intr_rect_ir | intinsic matrix of the rectified depth image |
| cloud | reference to teh output point cloud |
Definition at line 308 of file rgbd_util.cpp.
| void ccny_rgbd::buildPointCloud | ( | const cv::Mat & | depth_img_rect_reg, |
| const cv::Mat & | rgb_img_rect, | ||
| const cv::Mat & | intr_rect_rgb, | ||
| PointCloudT & | cloud | ||
| ) |
Constructs a point cloud with color.
Prior to calling this functions, both images need to be rectified, and the depth image has to be registered into the frame of the RGB image.
| depth_img_rect_reg | rectified and registered depth image (16UC1, in mm) |
| rgb_img_rect | rectified rgb image (8UC3) |
| intr_rect_rgb | intrinsic matrix |
| cloud | reference to the output point cloud |
Definition at line 348 of file rgbd_util.cpp.
| void ccny_rgbd::buildRegisteredDepthImage | ( | const cv::Mat & | intr_rect_ir, |
| const cv::Mat & | intr_rect_rgb, | ||
| const cv::Mat & | ir2rgb, | ||
| const cv::Mat & | depth_img_rect, | ||
| cv::Mat & | depth_img_rect_reg | ||
| ) |
reprojects a depth image to another depth image, registered in the rgb camera's frame.
Both images need to be rectified first. ir2rgb is a matrix such that for any point P_IR in the depth camera frame P_RGB = ir2rgb * P_IR
| intr_rect_ir | intrinsic matrix of the rectified depth image |
| intr_rect_rgb | intrinsic matrix of the rectified RGB image |
| ir2rgb | extrinsic matrix between the IR(depth) and RGB cameras |
| depth_img_rect | the input image: rectified depth image |
| depth_img_rect_reg | the output image: rectified and registered into the RGB frame |
Definition at line 395 of file rgbd_util.cpp.
| void ccny_rgbd::convertCameraInfoToMats | ( | const CameraInfoMsg::ConstPtr | camera_info_msg, |
| cv::Mat & | intr, | ||
| cv::Mat & | dist | ||
| ) |
Create OpenCV matrices from a CameraInfoMsg.
| camera_info_msg | input CameraInfoMsg |
| intr | output OpenCV intrinsic matrix |
| dist | output OpenCV distortion vector |
Definition at line 201 of file rgbd_util.cpp.
| void ccny_rgbd::convertMatToCameraInfo | ( | const cv::Mat & | intr, |
| CameraInfoMsg & | camera_info_msg | ||
| ) |
Create CameraInfoMsg from OpenCV matrices (assumes no distortion)
| intr | input OpenCV intrinsic matrix |
| camera_info_msg | output CameraInfoMsg |
Definition at line 224 of file rgbd_util.cpp.
| void ccny_rgbd::depthImageFloatTo16bit | ( | const cv::Mat & | depth_image_in, |
| cv::Mat & | depth_image_out | ||
| ) |
converts a 32FC1 depth image (in meters) to a 16UC1 depth image (in mm).
| depth_image_in | the input 32FC1 image |
| depth_image_out | the output 16UC1 image |
Definition at line 475 of file rgbd_util.cpp.
| Eigen::Matrix4f ccny_rgbd::eigenFromTf | ( | const tf::Transform & | tf | ) |
Converts an tf::Transform transform to an Eigen transform.
| tf | the tf transform |
Definition at line 53 of file rgbd_util.cpp.
| double ccny_rgbd::getMsDuration | ( | const ros::WallTime & | start | ) |
Returns the duration, in ms, from a given time.
| start | the start time |
Definition at line 101 of file rgbd_util.cpp.
| void ccny_rgbd::getTfDifference | ( | const tf::Transform & | motion, |
| double & | dist, | ||
| double & | angle | ||
| ) |
Given a transform, calculates the linear and angular distance between it and identity.
| motion | the incremental motion |
| dist | reference to linear distance |
| angle | reference to angular distance |
Definition at line 28 of file rgbd_util.cpp.
| void ccny_rgbd::getTfDifference | ( | const tf::Transform & | a, |
| const tf::Transform | b, | ||
| double & | dist, | ||
| double & | angle | ||
| ) |
Given two transformss, calculates the linear and angular distance between them, or the linear and angular components of a.inv() * b.
| a | the first transform |
| b | the second transform |
| dist | reference to the linear distance |
| angle | reference to the angular distance |
Definition at line 35 of file rgbd_util.cpp.
| bool ccny_rgbd::loadKeyframes | ( | KeyframeVector & | keyframes, |
| const std::string & | path | ||
| ) |
Loads a vector of RGBD keyframes to disk.
| keyframes | Reference to the keyframe being saved |
| path | The path to the folder where everything will be stored |
| true | Successfully saved the data |
| false | Saving failed - for example, cannot create directory |
Definition at line 126 of file rgbd_keyframe.cpp.
| void ccny_rgbd::openCVRtToTf | ( | const cv::Mat & | R, |
| const cv::Mat & | t, | ||
| tf::Transform & | transform | ||
| ) |
Creates a tf transform from a 3x3 OpenCV rotation matrix and a 3x1 OpenCV translation vector.
| R | the 3x3 OpenCV matrix |
| t | the 3x1 OpenCV vector |
| transform | reference to the output transform |
Definition at line 182 of file rgbd_util.cpp.
| ccny_rgbd::PLUGINLIB_DECLARE_CLASS | ( | ccny_rgbd | , |
| RGBDImageProcNodelet | , | ||
| RGBDImageProcNodelet | , | ||
| nodelet::Nodelet | |||
| ) |
| void ccny_rgbd::pointCloudFromMeans | ( | const Vector3fVector & | means, |
| PointCloudFeature & | cloud | ||
| ) |
Creates a pcl point cloud form a vector of eigen matrix means.
| means | vector of 3x1 matrices of positions (3D means) |
| cloud | reference to the output cloud |
Definition at line 286 of file rgbd_util.cpp.
| void ccny_rgbd::removeInvalidDistributions | ( | const Vector3fVector & | means, |
| const Matrix3fVector & | covariances, | ||
| const BoolVector & | valid, | ||
| Vector3fVector & | means_f, | ||
| Matrix3fVector & | covariances_f | ||
| ) |
Filters out a vector of means and a vector of covariances given a mask of valid entries.
| means | input vector of 3x1 matrices |
| covariances | input vector of 3x3 matrices |
| valid | vector mask of valid flags |
| means_f | output vector of 3x1 matrices |
| covariances_f | output vector of 3x1 matrices |
Definition at line 122 of file rgbd_util.cpp.
| void ccny_rgbd::removeInvalidMeans | ( | const Vector3fVector & | means, |
| const BoolVector & | valid, | ||
| Vector3fVector & | means_f | ||
| ) |
Filters out a vector of means given a mask of valid entries.
| means | input vector of 3x1 matrices |
| valid | vector mask of valid flags |
| means_f | output vector of 3x1 matrices |
Definition at line 106 of file rgbd_util.cpp.
| bool ccny_rgbd::saveKeyframes | ( | const KeyframeVector & | keyframes, |
| const std::string & | path | ||
| ) |
Saves a vector of RGBD keyframes to disk.
| keyframes | Reference to the keyframe being saved |
| path | The path to the folder where everything will be stored |
| true | Successfully saved the data |
| false | Saving failed - for example, cannot create directory |
Definition at line 108 of file rgbd_keyframe.cpp.
| tf::Transform ccny_rgbd::tfFromEigen | ( | Eigen::Matrix4f | trans | ) |
Converts an Eigen transform to a tf::Transform.
| trans | Eigen transform |
Definition at line 41 of file rgbd_util.cpp.
| bool ccny_rgbd::tfGreaterThan | ( | const tf::Transform & | a, |
| double | dist, | ||
| double | angle | ||
| ) |
Given a transfom (possibly computed as a difference between two transforms) checks if either its angular or linar component exceeds a threshold.
| a | input transform |
| dist | linear distance trheshold |
| angle | angular distance threshold |
Definition at line 87 of file rgbd_util.cpp.
| void ccny_rgbd::tfToEigenRt | ( | const tf::Transform & | tf, |
| Matrix3f & | R, | ||
| Vector3f & | t | ||
| ) |
Decomposes a tf into an Eigen 3x3 rotation matrix and Eigen 3x1 rotation vector.
| tf | the transform |
| R | reference to the 3x3 Eigen matrix |
| t | reference to the 3x1 Eigen vector |
Definition at line 143 of file rgbd_util.cpp.
| void ccny_rgbd::tfToOpenCVRt | ( | const tf::Transform & | transform, |
| cv::Mat & | R, | ||
| cv::Mat & | t | ||
| ) |
Decomposes a tf::Transform into a 3x3 OpenCV rotation matrix and a 3x1 OpenCV translation vector.
| transform | the transform |
| R | reference to the 3x3 OpenCV matrix |
| t | reference to the 3x1 OpenCV vector |
Definition at line 162 of file rgbd_util.cpp.
| void ccny_rgbd::tfToXYZRPY | ( | const tf::Transform & | t, |
| double & | x, | ||
| double & | y, | ||
| double & | z, | ||
| double & | roll, | ||
| double & | pitch, | ||
| double & | yaw | ||
| ) |
Decomposes a tf::Transform into x, y, z, roll, pitch, yaw.
| t | the input transform |
| x | the output x component |
| y | the output y component |
| z | the output z component |
| roll | the output roll component |
| pitch | the output pitch component |
| yaw | the output yaw component |
Definition at line 74 of file rgbd_util.cpp.
| void ccny_rgbd::transformDistributions | ( | Vector3fVector & | means, |
| Matrix3fVector & | covariances, | ||
| const tf::Transform & | transform | ||
| ) |
Transforms a vector of means and covariances.
| means | vector of 3x1 matrices of positions (3D means) |
| covariances | vector of 3x3 covariance matrices |
| transform | the tranformation to be applied to all the means and covariances |
Definition at line 266 of file rgbd_util.cpp.
| void ccny_rgbd::transformMeans | ( | Vector3fVector & | means, |
| const tf::Transform & | transform | ||
| ) |
Transforms a vector of means.
| means | vector of 3x1 matrices of positions (3D means) |
| transform | the tranformation to be applied to all the means |
Definition at line 250 of file rgbd_util.cpp.
| void ccny_rgbd::unwarpDepthImage | ( | cv::Mat & | depth_img_in, |
| const cv::Mat & | coeff0, | ||
| const cv::Mat & | coeff1, | ||
| const cv::Mat & | coeff2, | ||
| int | fit_mode = DEPTH_FIT_QUADRATIC |
||
| ) |
Given a depth image, uwarps it according to a polynomial model.
The size of the c matrices should be equal to the image size.
| depth_img_in | depth image to be unwarped (16UC1, in mm) |
| coeff0 | matrix of c0 coefficients |
| coeff1 | matrix of c1 coefficients |
| coeff2 | matrix of c2 coefficients |
| fit_mode | the polynomial fitting mode, see DepthFitMode. d = c0 + c1*d + c2*d^2 |
Definition at line 28 of file proc_util.cpp.