Public Member Functions | |
RGBDICPOdometry () | |
virtual | ~RGBDICPOdometry () |
Protected Member Functions | |
virtual void | flushCallbacks () |
Private Types | |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > | MyApproxCloudSyncPolicy |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan > | MyApproxScanSyncPolicy |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > | MyExactCloudSyncPolicy |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan > | MyExactScanSyncPolicy |
Private Member Functions | |
void | callbackCloud (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::PointCloud2ConstPtr &cloudMsg) |
void | callbackCommon (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::LaserScanConstPtr &scanMsg, const sensor_msgs::PointCloud2ConstPtr &cloudMsg) |
void | callbackScan (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo, const sensor_msgs::LaserScanConstPtr &scanMsg) |
virtual void | onOdomInit () |
virtual void | updateParameters (ParametersMap ¶meters) |
Private Attributes | |
message_filters::Synchronizer < MyApproxCloudSyncPolicy > * | approxCloudSync_ |
message_filters::Synchronizer < MyApproxScanSyncPolicy > * | approxScanSync_ |
message_filters::Subscriber < sensor_msgs::PointCloud2 > | cloud_sub_ |
message_filters::Synchronizer < MyExactCloudSyncPolicy > * | exactCloudSync_ |
message_filters::Synchronizer < MyExactScanSyncPolicy > * | exactScanSync_ |
image_transport::SubscriberFilter | image_depth_sub_ |
image_transport::SubscriberFilter | image_mono_sub_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > | info_sub_ |
int | queueSize_ |
message_filters::Subscriber < sensor_msgs::LaserScan > | scan_sub_ |
int | scanCloudMaxPoints_ |
int | scanNormalK_ |
double | scanNormalRadius_ |
double | scanVoxelSize_ |
Definition at line 66 of file rgbdicp_odometry.cpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> rtabmap_ros::RGBDICPOdometry::MyApproxCloudSyncPolicy [private] |
Definition at line 460 of file rgbdicp_odometry.cpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan> rtabmap_ros::RGBDICPOdometry::MyApproxScanSyncPolicy [private] |
Definition at line 456 of file rgbdicp_odometry.cpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> rtabmap_ros::RGBDICPOdometry::MyExactCloudSyncPolicy [private] |
Definition at line 462 of file rgbdicp_odometry.cpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan> rtabmap_ros::RGBDICPOdometry::MyExactScanSyncPolicy [private] |
Definition at line 458 of file rgbdicp_odometry.cpp.
rtabmap_ros::RGBDICPOdometry::RGBDICPOdometry | ( | ) | [inline] |
Definition at line 69 of file rgbdicp_odometry.cpp.
virtual rtabmap_ros::RGBDICPOdometry::~RGBDICPOdometry | ( | ) | [inline, virtual] |
Definition at line 83 of file rgbdicp_odometry.cpp.
void rtabmap_ros::RGBDICPOdometry::callbackCloud | ( | const sensor_msgs::ImageConstPtr & | image, |
const sensor_msgs::ImageConstPtr & | depth, | ||
const sensor_msgs::CameraInfoConstPtr & | cameraInfo, | ||
const sensor_msgs::PointCloud2ConstPtr & | cloudMsg | ||
) | [inline, private] |
Definition at line 216 of file rgbdicp_odometry.cpp.
void rtabmap_ros::RGBDICPOdometry::callbackCommon | ( | const sensor_msgs::ImageConstPtr & | image, |
const sensor_msgs::ImageConstPtr & | depth, | ||
const sensor_msgs::CameraInfoConstPtr & | cameraInfo, | ||
const sensor_msgs::LaserScanConstPtr & | scanMsg, | ||
const sensor_msgs::PointCloud2ConstPtr & | cloudMsg | ||
) | [inline, private] |
Definition at line 226 of file rgbdicp_odometry.cpp.
void rtabmap_ros::RGBDICPOdometry::callbackScan | ( | const sensor_msgs::ImageConstPtr & | image, |
const sensor_msgs::ImageConstPtr & | depth, | ||
const sensor_msgs::CameraInfoConstPtr & | cameraInfo, | ||
const sensor_msgs::LaserScanConstPtr & | scanMsg | ||
) | [inline, private] |
Definition at line 206 of file rgbdicp_odometry.cpp.
virtual void rtabmap_ros::RGBDICPOdometry::flushCallbacks | ( | ) | [inline, protected, virtual] |
Implements rtabmap_ros::OdometryROS.
Definition at line 421 of file rgbdicp_odometry.cpp.
virtual void rtabmap_ros::RGBDICPOdometry::onOdomInit | ( | ) | [inline, private, virtual] |
Implements rtabmap_ros::OdometryROS.
Definition at line 105 of file rgbdicp_odometry.cpp.
virtual void rtabmap_ros::RGBDICPOdometry::updateParameters | ( | ParametersMap & | parameters | ) | [inline, private, virtual] |
Definition at line 195 of file rgbdicp_odometry.cpp.
message_filters::Synchronizer<MyApproxCloudSyncPolicy>* rtabmap_ros::RGBDICPOdometry::approxCloudSync_ [private] |
Definition at line 461 of file rgbdicp_odometry.cpp.
message_filters::Synchronizer<MyApproxScanSyncPolicy>* rtabmap_ros::RGBDICPOdometry::approxScanSync_ [private] |
Definition at line 457 of file rgbdicp_odometry.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::RGBDICPOdometry::cloud_sub_ [private] |
Definition at line 455 of file rgbdicp_odometry.cpp.
message_filters::Synchronizer<MyExactCloudSyncPolicy>* rtabmap_ros::RGBDICPOdometry::exactCloudSync_ [private] |
Definition at line 463 of file rgbdicp_odometry.cpp.
message_filters::Synchronizer<MyExactScanSyncPolicy>* rtabmap_ros::RGBDICPOdometry::exactScanSync_ [private] |
Definition at line 459 of file rgbdicp_odometry.cpp.
Definition at line 452 of file rgbdicp_odometry.cpp.
Definition at line 451 of file rgbdicp_odometry.cpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::RGBDICPOdometry::info_sub_ [private] |
Definition at line 453 of file rgbdicp_odometry.cpp.
int rtabmap_ros::RGBDICPOdometry::queueSize_ [private] |
Definition at line 464 of file rgbdicp_odometry.cpp.
message_filters::Subscriber<sensor_msgs::LaserScan> rtabmap_ros::RGBDICPOdometry::scan_sub_ [private] |
Definition at line 454 of file rgbdicp_odometry.cpp.
int rtabmap_ros::RGBDICPOdometry::scanCloudMaxPoints_ [private] |
Definition at line 465 of file rgbdicp_odometry.cpp.
int rtabmap_ros::RGBDICPOdometry::scanNormalK_ [private] |
Definition at line 467 of file rgbdicp_odometry.cpp.
double rtabmap_ros::RGBDICPOdometry::scanNormalRadius_ [private] |
Definition at line 468 of file rgbdicp_odometry.cpp.
double rtabmap_ros::RGBDICPOdometry::scanVoxelSize_ [private] |
Definition at line 466 of file rgbdicp_odometry.cpp.