Public Types | |
typedef pcl::PointCloud < pcl::PointXYZRGB > | PointCloud |
Public Member Functions | |
StereoOdometer (const std::string &transport) | |
Protected Member Functions | |
void | computeAndPublishPointCloud (const sensor_msgs::CameraInfoConstPtr &l_info_msg, const sensor_msgs::ImageConstPtr &l_image_msg, const sensor_msgs::CameraInfoConstPtr &r_info_msg, const std::vector< Matcher::p_match > &matches, const std::vector< int32_t > &inlier_indices) |
double | computeFeatureFlow (const std::vector< Matcher::p_match > &matches) |
void | imageCallback (const sensor_msgs::ImageConstPtr &l_image_msg, const sensor_msgs::ImageConstPtr &r_image_msg, const sensor_msgs::CameraInfoConstPtr &l_info_msg, const sensor_msgs::CameraInfoConstPtr &r_info_msg) |
void | initOdometer (const sensor_msgs::CameraInfoConstPtr &l_info_msg, const sensor_msgs::CameraInfoConstPtr &r_info_msg) |
Private Attributes | |
bool | change_reference_frame_ |
bool | got_lost_ |
ros::Publisher | info_pub_ |
ros::Publisher | point_cloud_pub_ |
int | ref_frame_change_method_ |
int | ref_frame_inlier_threshold_ |
double | ref_frame_motion_threshold_ |
Matrix | reference_motion_ |
boost::shared_ptr < VisualOdometryStereo > | visual_odometer_ |
VisualOdometryStereo::parameters | visual_odometer_params_ |
Definition at line 46 of file stereo_odometer.cpp.
typedef pcl::PointCloud<pcl::PointXYZRGB> viso2_ros::StereoOdometer::PointCloud |
Definition at line 68 of file stereo_odometer.cpp.
viso2_ros::StereoOdometer::StereoOdometer | ( | const std::string & | transport | ) | [inline] |
Definition at line 70 of file stereo_odometer.cpp.
void viso2_ros::StereoOdometer::computeAndPublishPointCloud | ( | const sensor_msgs::CameraInfoConstPtr & | l_info_msg, |
const sensor_msgs::ImageConstPtr & | l_image_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | r_info_msg, | ||
const std::vector< Matcher::p_match > & | matches, | ||
const std::vector< int32_t > & | inlier_indices | ||
) | [inline, protected] |
Definition at line 281 of file stereo_odometer.cpp.
double viso2_ros::StereoOdometer::computeFeatureFlow | ( | const std::vector< Matcher::p_match > & | matches | ) | [inline, protected] |
Definition at line 268 of file stereo_odometer.cpp.
void viso2_ros::StereoOdometer::imageCallback | ( | const sensor_msgs::ImageConstPtr & | l_image_msg, |
const sensor_msgs::ImageConstPtr & | r_image_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | l_info_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | r_info_msg | ||
) | [inline, protected, virtual] |
Implement this method in sub-classes
Implements viso2_ros::StereoProcessor.
Definition at line 121 of file stereo_odometer.cpp.
void viso2_ros::StereoOdometer::initOdometer | ( | const sensor_msgs::CameraInfoConstPtr & | l_info_msg, |
const sensor_msgs::CameraInfoConstPtr & | r_info_msg | ||
) | [inline, protected] |
Definition at line 90 of file stereo_odometer.cpp.
bool viso2_ros::StereoOdometer::change_reference_frame_ [private] |
Definition at line 61 of file stereo_odometer.cpp.
bool viso2_ros::StereoOdometer::got_lost_ [private] |
Definition at line 57 of file stereo_odometer.cpp.
Definition at line 55 of file stereo_odometer.cpp.
Definition at line 54 of file stereo_odometer.cpp.
int viso2_ros::StereoOdometer::ref_frame_change_method_ [private] |
Definition at line 60 of file stereo_odometer.cpp.
int viso2_ros::StereoOdometer::ref_frame_inlier_threshold_ [private] |
Definition at line 63 of file stereo_odometer.cpp.
double viso2_ros::StereoOdometer::ref_frame_motion_threshold_ [private] |
Definition at line 62 of file stereo_odometer.cpp.
Definition at line 64 of file stereo_odometer.cpp.
boost::shared_ptr<VisualOdometryStereo> viso2_ros::StereoOdometer::visual_odometer_ [private] |
Definition at line 51 of file stereo_odometer.cpp.
Definition at line 52 of file stereo_odometer.cpp.