#include <tracking.h>
Classes | |
| struct | Params | 
Public Types | |
| enum | trackingState { NOT_INITIALIZED = 0, INITIALIZING = 1, WORKING = 2, LOST = 3 } | 
Public Member Functions | |
| Frame | getCurrentFrame () const | 
| Get current frame.   | |
| Params | getParams () const | 
| Get class params.   | |
| void | run () | 
| Starts tracking.   | |
| void | setParams (const Params ¶ms) | 
| Set class params.   | |
| Tracking (Publisher *f_pub, Graph *graph) | |
| Class constructor.   | |
Protected Member Functions | |
| bool | addFrameToMap (double range) | 
| Add a frame to the graph if enough inliers.   | |
| PointCloudRGB::Ptr | filterCloud (PointCloudRGB::Ptr in_cloud) | 
| Filters a pointcloud.   | |
| bool | getOdom2CameraTf (nav_msgs::Odometry odom_msg, sensor_msgs::Image img_msg, tf::StampedTransform &transform) | 
| Get the transform between odometry frame and camera frame.   | |
| void | msgsCallback (const nav_msgs::Odometry::ConstPtr &odom_msg, const sensor_msgs::Range::ConstPtr &range_msg, const sensor_msgs::ImageConstPtr &l_img_msg, const sensor_msgs::ImageConstPtr &r_img_msg, const sensor_msgs::CameraInfoConstPtr &l_info_msg, const sensor_msgs::CameraInfoConstPtr &r_info_msg, const sensor_msgs::PointCloud2ConstPtr &cloud_msg) | 
| Messages callback. This function is called when synchronized odometry and image message are received.   | |
| bool | needNewKeyFrame (double range) | 
| Decide if new keyframe is needed.   | |
| void | publishOverlap (PointCloudXYZ::Ptr cloud, tf::Transform movement, float overlap) | 
| Publishes the overlapping debug image.   | |
| bool | refinePose (Frame c_frame, Frame p_frame, tf::Transform &out, int &num_inliers) | 
| Refine the keyframe to keyframe position using SolvePnP.   | |
Private Types | |
| typedef  message_filters::Synchronizer < SyncPolicy >  | Sync | 
| typedef  message_filters::sync_policies::ApproximateTime < nav_msgs::Odometry, sensor_msgs::Range, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 >  | SyncPolicy | 
| > Number of seconds that filter will be applied   | |
Private Attributes | |
| Frame | c_frame_ | 
| > Listen for tf between robot and camera.   | |
| cv::Mat | camera_matrix_ | 
| > Previous frame   | |
| image_geometry::StereoCameraModel | camera_model_ | 
| > Publish transform   | |
| Publisher * | f_pub_ | 
| > Camera matrix   | |
| int | frame_id_ | 
| Graph * | graph_ | 
| > Stereo camera model   | |
| bool | jump_detected_ | 
| > Stores the time at which the jump starts   | |
| ros::WallTime | jump_time_ | 
| > Stores the previous corrected odometry pose   | |
| int | kf_id_ | 
| > Processed frames counter   | |
| tf::Transform | last_fixed_frame_pose_ | 
| > Graph   | |
| Eigen::Vector4f | last_max_pt_ | 
| Eigen::Vector4f | last_min_pt_ | 
| > Stores the last fixed frame pose   | |
| tf::StampedTransform | odom2camera_ | 
| > Tracking state   | |
| vector< tf::Transform > | odom_pose_history_ | 
| > Processed keyframes counter   | |
| ros::Publisher | overlapping_pub_ | 
| > Corrected pose publisher   | |
| Frame | p_frame_ | 
| > Current frame   | |
| Params | params_ | 
| ros::Publisher | pc_pub_ | 
| > Frame publisher   | |
| ros::Publisher | pose_pub_ | 
| > Pointcloud publisher   | |
| tf::Transform | prev_robot_pose_ | 
| > Stores the odometry poses, relative to camera frame   | |
| double | secs_to_filter_ | 
| > Indicates when a big correction is detected   | |
| trackingState | state_ | 
| > Stores parameters.   | |
| tf::TransformBroadcaster | tf_broadcaster_ | 
| > Consecutive image overlapping publisher   | |
| tf::TransformListener | tf_listener_ | 
| > Transformation between robot odometry frame and camera frame.   | |
Definition at line 54 of file tracking.h.
typedef message_filters::Synchronizer<SyncPolicy> slam::Tracking::Sync [private] | 
        
Definition at line 228 of file tracking.h.
typedef message_filters::sync_policies::ApproximateTime<nav_msgs::Odometry, sensor_msgs::Range, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> slam::Tracking::SyncPolicy [private] | 
        
> Number of seconds that filter will be applied
Definition at line 227 of file tracking.h.
Definition at line 79 of file tracking.h.
| slam::Tracking::Tracking | ( | Publisher * | f_pub, | 
| Graph * | graph | ||
| ) | 
Class constructor.
Definition at line 11 of file tracking.cpp.
| bool slam::Tracking::addFrameToMap | ( | double | range | ) |  [protected] | 
        
Add a frame to the graph if enough inliers.
Definition at line 307 of file tracking.cpp.
| PointCloudRGB::Ptr slam::Tracking::filterCloud | ( | PointCloudRGB::Ptr | in_cloud | ) |  [protected] | 
        
Filters a pointcloud.
| input | cloud | 
Definition at line 429 of file tracking.cpp.
| Frame slam::Tracking::getCurrentFrame | ( | ) |  const [inline] | 
        
Get current frame.
Definition at line 103 of file tracking.h.
| bool slam::Tracking::getOdom2CameraTf | ( | nav_msgs::Odometry | odom_msg, | 
| sensor_msgs::Image | img_msg, | ||
| tf::StampedTransform & | transform | ||
| ) |  [protected] | 
        
Get the transform between odometry frame and camera frame.
| Odometry | msg | 
| Image | msg | 
| Output | transform | 
Definition at line 230 of file tracking.cpp.
| Params slam::Tracking::getParams | ( | ) |  const [inline] | 
        
Get class params.
Definition at line 99 of file tracking.h.
| void slam::Tracking::msgsCallback | ( | const nav_msgs::Odometry::ConstPtr & | odom_msg, | 
| const sensor_msgs::Range::ConstPtr & | range_msg, | ||
| const sensor_msgs::ImageConstPtr & | l_img_msg, | ||
| const sensor_msgs::ImageConstPtr & | r_img_msg, | ||
| const sensor_msgs::CameraInfoConstPtr & | l_info_msg, | ||
| const sensor_msgs::CameraInfoConstPtr & | r_info_msg, | ||
| const sensor_msgs::PointCloud2ConstPtr & | cloud_msg | ||
| ) |  [protected] | 
        
Messages callback. This function is called when synchronized odometry and image message are received.
| odom_msg | ros odometry message of type nav_msgs::Odometry | 
| l_img | left stereo image message of type sensor_msgs::Image | 
| r_img | right stereo image message of type sensor_msgs::Image | 
| l_info | left stereo info message of type sensor_msgs::CameraInfo | 
| r_info | right stereo info message of type sensor_msgs::CameraInfo | 
| pointcloud | 
Definition at line 66 of file tracking.cpp.
| bool slam::Tracking::needNewKeyFrame | ( | double | range | ) |  [protected] | 
        
Decide if new keyframe is needed.
Definition at line 253 of file tracking.cpp.
| void slam::Tracking::publishOverlap | ( | PointCloudXYZ::Ptr | cloud, | 
| tf::Transform | movement, | ||
| float | overlap | ||
| ) |  [protected] | 
        
Publishes the overlapping debug image.
| current | pointcloud | 
| the | transformation of current pointcloud to the last fixed frame | 
| the | overlap | 
Definition at line 446 of file tracking.cpp.
| bool slam::Tracking::refinePose | ( | Frame | c_frame, | 
| Frame | p_frame, | ||
| tf::Transform & | out, | ||
| int & | num_inliers | ||
| ) |  [protected] | 
        
Refine the keyframe to keyframe position using SolvePnP.
| current | frame | 
| previous | frame | 
| the | estimated transform | 
| number | of inliers for the refined pose | 
Definition at line 361 of file tracking.cpp.
| void slam::Tracking::run | ( | ) | 
Starts tracking.
Definition at line 15 of file tracking.cpp.
| void slam::Tracking::setParams | ( | const Params & | params | ) |  [inline] | 
        
Frame slam::Tracking::c_frame_ [private] | 
        
> Listen for tf between robot and camera.
Definition at line 182 of file tracking.h.
cv::Mat slam::Tracking::camera_matrix_ [private] | 
        
> Previous frame
Definition at line 186 of file tracking.h.
> Publish transform
Definition at line 198 of file tracking.h.
Publisher* slam::Tracking::f_pub_ [private] | 
        
> Camera matrix
Definition at line 188 of file tracking.h.
int slam::Tracking::frame_id_ [private] | 
        
Definition at line 206 of file tracking.h.
Graph* slam::Tracking::graph_ [private] | 
        
> Stereo camera model
Definition at line 200 of file tracking.h.
bool slam::Tracking::jump_detected_ [private] | 
        
> Stores the time at which the jump starts
Definition at line 216 of file tracking.h.
ros::WallTime slam::Tracking::jump_time_ [private] | 
        
> Stores the previous corrected odometry pose
Definition at line 214 of file tracking.h.
int slam::Tracking::kf_id_ [private] | 
        
> Processed frames counter
Definition at line 208 of file tracking.h.
> Graph
Definition at line 202 of file tracking.h.
Eigen::Vector4f slam::Tracking::last_max_pt_ [private] | 
        
Definition at line 204 of file tracking.h.
Eigen::Vector4f slam::Tracking::last_min_pt_ [private] | 
        
> Stores the last fixed frame pose
Definition at line 204 of file tracking.h.
> Tracking state
Definition at line 178 of file tracking.h.
vector<tf::Transform> slam::Tracking::odom_pose_history_ [private] | 
        
> Processed keyframes counter
Definition at line 210 of file tracking.h.
> Corrected pose publisher
Definition at line 194 of file tracking.h.
Frame slam::Tracking::p_frame_ [private] | 
        
> Current frame
Definition at line 184 of file tracking.h.
Params slam::Tracking::params_ [private] | 
        
Definition at line 174 of file tracking.h.
ros::Publisher slam::Tracking::pc_pub_ [private] | 
        
> Frame publisher
Definition at line 190 of file tracking.h.
ros::Publisher slam::Tracking::pose_pub_ [private] | 
        
> Pointcloud publisher
Definition at line 192 of file tracking.h.
> Stores the odometry poses, relative to camera frame
Definition at line 212 of file tracking.h.
double slam::Tracking::secs_to_filter_ [private] | 
        
> Indicates when a big correction is detected
Definition at line 218 of file tracking.h.
trackingState slam::Tracking::state_ [private] | 
        
> Stores parameters.
Definition at line 176 of file tracking.h.
> Consecutive image overlapping publisher
Definition at line 196 of file tracking.h.
> Transformation between robot odometry frame and camera frame.
Definition at line 180 of file tracking.h.