Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
rtabmap_odom::RGBDICPOdometry Class Reference
Inheritance diagram for rtabmap_odom::RGBDICPOdometry:
Inheritance graph
[legend]

Public Member Functions

 RGBDICPOdometry ()
 
virtual ~RGBDICPOdometry ()
 
- Public Member Functions inherited from rtabmap_odom::OdometryROS
const std::stringframeId () const
 
const std::stringguessFrameId () const
 
bool isPaused () const
 
 OdometryROS (bool stereoParams, bool visParams, bool icpParams)
 
const std::stringodomFrameId () const
 
const rtabmap::ParametersMapparameters () const
 
bool pause (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
void processData (rtabmap::SensorData &data, const std_msgs::Header &header)
 
bool reset (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
bool resetToPose (rtabmap_msgs::ResetPose::Request &, rtabmap_msgs::ResetPose::Response &)
 
bool resume (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
bool setLogDebug (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
bool setLogError (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
bool setLogInfo (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
bool setLogWarn (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
virtual ~OdometryROS ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 
- Public Member Functions inherited from UThread
Handle getThreadHandle () const
 
unsigned long getThreadId () const
 
bool isCreating () const
 
bool isIdle () const
 
bool isKilled () const
 
bool isRunning () const
 
void join (bool killFirst=false)
 
void kill ()
 
void setAffinity (int cpu=0)
 
void setPriority (Priority priority)
 
void start ()
 
 UThread (Priority priority=kPNormal)
 
virtual ~UThread ()
 
- Public Member Functions inherited from UThreadC< void >
int Create (Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const
 
int Create (Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const
 
int Create (unsigned long &ThreadId, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const
 
int Create (unsigned long &ThreadId, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false) const
 
virtual ~UThreadC ()
 
virtual ~UThreadC ()
 

Protected Member Functions

virtual void flushCallbacks ()
 
- Protected Member Functions inherited from rtabmap_odom::OdometryROS
void initDiagnosticMsg (const std::string &subscribedTopicsMsg, bool approxSync, const std::string &subscribedTopic="")
 
virtual void postProcessData (const rtabmap::SensorData &data, const std_msgs::Header &header) const
 
double previousStamp () const
 
tf::TransformListenertfListener ()
 
rtabmap::Transform velocityGuess () const
 
double waitForTransformDuration () const
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::stringgetName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 
- Protected Member Functions inherited from UThreadC< void >
 UThreadC ()
 
 UThreadC ()
 

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 &parameters)
 

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::CameraInfoinfo_sub_
 
bool keepColor_
 
int queueSize_
 
message_filters::Subscriber< sensor_msgs::LaserScan > scan_sub_
 
int scanCloudMaxPoints_
 
int scanNormalK_
 
double scanNormalRadius_
 
double scanVoxelSize_
 
int syncQueueSize_
 

Additional Inherited Members

- Public Types inherited from UThread
enum  Priority
 
- Public Types inherited from UThreadC< void >
typedef THREAD_HANDLE Handle
 
typedef THREAD_HANDLE Handle
 
typedef void(* Handler) ()
 
typedef void(* Handler) ()
 
- Static Public Member Functions inherited from UThread
static unsigned long currentThreadId ()
 
- Static Public Member Functions inherited from UThreadC< void >
static int Create (const Handler &Function, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false)
 
static int Create (const Handler &Function, Handle *const &H=0, const bool &CreateDetached=false, const unsigned int &StackSize=0, const bool &CancelEnable=false, const bool &CancelAsync=false)
 
static int Detach (const Handle &H)
 
static int Detach (Handle H)
 
static int Join (const Handle &H)
 
static int Join (Handle H)
 
static int Kill (const Handle &H)
 
static int Kill (Handle H)
 
- Public Attributes inherited from UThread
 kPAboveNormal
 
 kPBelowNormal
 
 kPLow
 
 kPNormal
 
 kPRealTime
 
- Static Protected Member Functions inherited from UThreadC< void >
static void Exit ()
 
static void Exit ()
 
static int Self ()
 
static Handle Self ()
 
static void TestCancel ()
 
static void TestCancel ()
 

Detailed Description

Definition at line 66 of file rgbdicp_odometry.cpp.

Member Typedef Documentation

◆ MyApproxCloudSyncPolicy

Definition at line 510 of file rgbdicp_odometry.cpp.

◆ MyApproxScanSyncPolicy

Definition at line 506 of file rgbdicp_odometry.cpp.

◆ MyExactCloudSyncPolicy

Definition at line 512 of file rgbdicp_odometry.cpp.

◆ MyExactScanSyncPolicy

Definition at line 508 of file rgbdicp_odometry.cpp.

Constructor & Destructor Documentation

◆ RGBDICPOdometry()

rtabmap_odom::RGBDICPOdometry::RGBDICPOdometry ( )
inline

Definition at line 69 of file rgbdicp_odometry.cpp.

◆ ~RGBDICPOdometry()

virtual rtabmap_odom::RGBDICPOdometry::~RGBDICPOdometry ( )
inlinevirtual

Definition at line 85 of file rgbdicp_odometry.cpp.

Member Function Documentation

◆ callbackCloud()

void rtabmap_odom::RGBDICPOdometry::callbackCloud ( const sensor_msgs::ImageConstPtr &  image,
const sensor_msgs::ImageConstPtr &  depth,
const sensor_msgs::CameraInfoConstPtr &  cameraInfo,
const sensor_msgs::PointCloud2ConstPtr &  cloudMsg 
)
inlineprivate

Definition at line 243 of file rgbdicp_odometry.cpp.

◆ callbackCommon()

void rtabmap_odom::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 
)
inlineprivate

Definition at line 253 of file rgbdicp_odometry.cpp.

◆ callbackScan()

void rtabmap_odom::RGBDICPOdometry::callbackScan ( const sensor_msgs::ImageConstPtr &  image,
const sensor_msgs::ImageConstPtr &  depth,
const sensor_msgs::CameraInfoConstPtr &  cameraInfo,
const sensor_msgs::LaserScanConstPtr &  scanMsg 
)
inlineprivate

Definition at line 233 of file rgbdicp_odometry.cpp.

◆ flushCallbacks()

virtual void rtabmap_odom::RGBDICPOdometry::flushCallbacks ( )
inlineprotectedvirtual

Implements rtabmap_odom::OdometryROS.

Definition at line 471 of file rgbdicp_odometry.cpp.

◆ onOdomInit()

virtual void rtabmap_odom::RGBDICPOdometry::onOdomInit ( )
inlineprivatevirtual

Implements rtabmap_odom::OdometryROS.

Definition at line 107 of file rgbdicp_odometry.cpp.

◆ updateParameters()

virtual void rtabmap_odom::RGBDICPOdometry::updateParameters ( ParametersMap parameters)
inlineprivatevirtual

Reimplemented from rtabmap_odom::OdometryROS.

Definition at line 222 of file rgbdicp_odometry.cpp.

Member Data Documentation

◆ approxCloudSync_

message_filters::Synchronizer<MyApproxCloudSyncPolicy>* rtabmap_odom::RGBDICPOdometry::approxCloudSync_
private

Definition at line 511 of file rgbdicp_odometry.cpp.

◆ approxScanSync_

message_filters::Synchronizer<MyApproxScanSyncPolicy>* rtabmap_odom::RGBDICPOdometry::approxScanSync_
private

Definition at line 507 of file rgbdicp_odometry.cpp.

◆ cloud_sub_

message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_odom::RGBDICPOdometry::cloud_sub_
private

Definition at line 505 of file rgbdicp_odometry.cpp.

◆ exactCloudSync_

message_filters::Synchronizer<MyExactCloudSyncPolicy>* rtabmap_odom::RGBDICPOdometry::exactCloudSync_
private

Definition at line 513 of file rgbdicp_odometry.cpp.

◆ exactScanSync_

message_filters::Synchronizer<MyExactScanSyncPolicy>* rtabmap_odom::RGBDICPOdometry::exactScanSync_
private

Definition at line 509 of file rgbdicp_odometry.cpp.

◆ image_depth_sub_

image_transport::SubscriberFilter rtabmap_odom::RGBDICPOdometry::image_depth_sub_
private

Definition at line 502 of file rgbdicp_odometry.cpp.

◆ image_mono_sub_

image_transport::SubscriberFilter rtabmap_odom::RGBDICPOdometry::image_mono_sub_
private

Definition at line 501 of file rgbdicp_odometry.cpp.

◆ info_sub_

message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_odom::RGBDICPOdometry::info_sub_
private

Definition at line 503 of file rgbdicp_odometry.cpp.

◆ keepColor_

bool rtabmap_odom::RGBDICPOdometry::keepColor_
private

Definition at line 516 of file rgbdicp_odometry.cpp.

◆ queueSize_

int rtabmap_odom::RGBDICPOdometry::queueSize_
private

Definition at line 514 of file rgbdicp_odometry.cpp.

◆ scan_sub_

message_filters::Subscriber<sensor_msgs::LaserScan> rtabmap_odom::RGBDICPOdometry::scan_sub_
private

Definition at line 504 of file rgbdicp_odometry.cpp.

◆ scanCloudMaxPoints_

int rtabmap_odom::RGBDICPOdometry::scanCloudMaxPoints_
private

Definition at line 517 of file rgbdicp_odometry.cpp.

◆ scanNormalK_

int rtabmap_odom::RGBDICPOdometry::scanNormalK_
private

Definition at line 519 of file rgbdicp_odometry.cpp.

◆ scanNormalRadius_

double rtabmap_odom::RGBDICPOdometry::scanNormalRadius_
private

Definition at line 520 of file rgbdicp_odometry.cpp.

◆ scanVoxelSize_

double rtabmap_odom::RGBDICPOdometry::scanVoxelSize_
private

Definition at line 518 of file rgbdicp_odometry.cpp.

◆ syncQueueSize_

int rtabmap_odom::RGBDICPOdometry::syncQueueSize_
private

Definition at line 515 of file rgbdicp_odometry.cpp.


The documentation for this class was generated from the following file:


rtabmap_odom
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:42:24