Classes |
| class | FeatureViewer |
| | Application to test and visualize the different type of feature detectors. More...
|
| class | KeyframeMapper |
| | Builds a 3D map from a series of RGBD keyframes. More...
|
| class | Navigator |
| | Builds a 3D map from a series of RGBD keyframes. 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 | RGBNavigator |
| | Builds a 3D map from a series of RGBD keyframes. More...
|
| class | VisualOdometry |
| | Subscribes to incoming RGBD images and outputs the position of the moving (base) frame wrt some fixed frame. More...
|
Typedefs |
| typedef Eigen::Affine3f | AffineTransform |
typedef
Eigen::aligned_allocator
< AffineTransform > | AffineTransformAllocator |
typedef std::vector
< AffineTransform,
AffineTransformAllocator > | AffineTransformVector |
| typedef std::vector< bool > | BoolVector |
| typedef sensor_msgs::CameraInfo | CameraInfoMsg |
typedef
message_filters::Subscriber
< CameraInfoMsg > | CameraInfoSubFilter |
typedef
dynamic_reconfigure::Server
< FeatureDetectorConfig > | FeatureDetectorConfigServer |
| typedef std::vector< float > | FloatVector |
typedef
dynamic_reconfigure::Server
< GftDetectorConfig > | GftDetectorConfigServer |
typedef boost::shared_ptr
< GftDetectorConfigServer > | GftDetectorConfigServerPtr |
| 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 std::vector< cv::KeyPoint > | KeypointVector |
| 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 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 Eigen::Affine3f | Pose |
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
message_filters::Synchronizer
< RGBSyncPolicy > | RGBSynchronizer |
typedef
message_filters::sync_policies::ApproximateTime
< ImageMsg, CameraInfoMsg > | RGBSyncPolicy |
typedef
dynamic_reconfigure::Server
< StarDetectorConfig > | StarDetectorConfigServer |
typedef boost::shared_ptr
< StarDetectorConfigServer > | StarDetectorConfigServerPtr |
typedef
dynamic_reconfigure::Server
< SurfDetectorConfig > | SurfDetectorConfigServer |
typedef boost::shared_ptr
< SurfDetectorConfigServer > | SurfDetectorConfigServerPtr |
typedef
pcl::registration::TransformationEstimationSVD
< PointFeature, PointFeature > | TransformationEstimationSVD |
| typedef Eigen::Vector3f | Vector3f |
typedef std::vector
< Eigen::Vector3f > | Vector3fVector |
Functions |
| 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 | createRGBDFrameFromROSMessages (const ImageMsg::ConstPtr &rgb_msg, const ImageMsg::ConstPtr &depth_msg, const CameraInfoMsg::ConstPtr &info_msg, rgbdtools::RGBDFrame &frame) |
| AffineTransform | eigenAffineFromTf (const tf::Transform &tf) |
| Eigen::Matrix4f | eigenFromTf (const tf::Transform &tf) |
| | Converts an tf::Transform transform to an Eigen transform.
|
| int | getmaxheight (PathMsg path_msg) |
| int | getminheight (PathMsg path_msg) |
| 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.
|
| 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.
|
| void | pathEigenAffineToROS (const AffineTransformVector &path, PathMsg &path_msg) |
| | Copies over the poses from a Eigen vector to a ROS message. Assumes the message is already correctly resized, and preserves the headers of each pose in the message.
|
| void | pathROSToEigenAffine (const PathMsg &path_msg, AffineTransformVector &path) |
| | copies over the poses from a ROS message Eigen vector. The eigen vector will be cleared and resized appropriately.
|
| | PLUGINLIB_DECLARE_CLASS (ccny_rgbd, RGBDImageProcNodelet, RGBDImageProcNodelet, nodelet::Nodelet) |
| void | removeInvalidDistributions (const Vector3fVector &means, const Matrix3fVector &covariances, const BoolVector &valid, Vector3fVector &means_f, Matrix3fVector &covariances_f) |
| void | removeInvalidMeans (const Vector3fVector &means, const BoolVector &valid, Vector3fVector &means_f) |
| tf::Transform | tfFromEigen (Eigen::Matrix4f trans) |
| | Converts an Eigen transform to a tf::Transform.
|
| tf::Transform | tfFromEigenAffine (const AffineTransform &trans) |
| 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.
|
Variables |
| cv::Size | CamSize |
| cv::Mat | dist |
| bool | first = true |
| cv::Mat | intr |
| aruco::MarkerDetector | MDetector |
| aruco::CameraParameters | param |
| rgbdtools::KeyframeGraphSolverISAM | solver_ |
| int | triple_add = 0 |