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

Public Member Functions

 ICPOdometry ()
 
virtual ~ICPOdometry ()
 
- 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 ()
 
void postProcessData (const SensorData &data, const std_msgs::Header &header) const
 
- Protected Member Functions inherited from rtabmap_odom::OdometryROS
void initDiagnosticMsg (const std::string &subscribedTopicsMsg, bool approxSync, const std::string &subscribedTopic="")
 
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 Member Functions

void callbackCloud (const sensor_msgs::PointCloud2ConstPtr &pointCloudMsg)
 
void callbackScan (const sensor_msgs::LaserScanConstPtr &scanMsg)
 
virtual void onOdomInit ()
 
virtual void updateParameters (ParametersMap &parameters)
 

Private Attributes

ros::Subscriber cloud_sub_
 
bool cloudReceived_ = false
 
bool deskewing_
 
bool deskewingSlerp_
 
ros::Publisher filtered_scan_pub_
 
pluginlib::ClassLoader< rtabmap_odom::PluginInterfaceplugin_loader_
 
std::vector< boost::shared_ptr< rtabmap_odom::PluginInterface > > plugins_
 
ros::Subscriber scan_sub_
 
bool scanCloudIs2d_
 
int scanCloudMaxPoints_
 
int scanDownsamplingStep_
 
double scanNormalGroundUp_
 
int scanNormalK_
 
double scanNormalRadius_
 
double scanRangeMax_
 
double scanRangeMin_
 
bool scanReceived_ = false
 
double scanVoxelSize_
 

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 59 of file icp_odometry.cpp.

Constructor & Destructor Documentation

◆ ICPOdometry()

rtabmap_odom::ICPOdometry::ICPOdometry ( )
inline

Definition at line 62 of file icp_odometry.cpp.

◆ ~ICPOdometry()

virtual rtabmap_odom::ICPOdometry::~ICPOdometry ( )
inlinevirtual

Definition at line 81 of file icp_odometry.cpp.

Member Function Documentation

◆ callbackCloud()

void rtabmap_odom::ICPOdometry::callbackCloud ( const sensor_msgs::PointCloud2ConstPtr &  pointCloudMsg)
inlineprivate

Definition at line 566 of file icp_odometry.cpp.

◆ callbackScan()

void rtabmap_odom::ICPOdometry::callbackScan ( const sensor_msgs::LaserScanConstPtr &  scanMsg)
inlineprivate

Definition at line 326 of file icp_odometry.cpp.

◆ flushCallbacks()

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

Implements rtabmap_odom::OdometryROS.

Definition at line 885 of file icp_odometry.cpp.

◆ onOdomInit()

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

Implements rtabmap_odom::OdometryROS.

Definition at line 88 of file icp_odometry.cpp.

◆ postProcessData()

void rtabmap_odom::ICPOdometry::postProcessData ( const SensorData data,
const std_msgs::Header header 
) const
inlineprotectedvirtual

Reimplemented from rtabmap_odom::OdometryROS.

Definition at line 890 of file icp_odometry.cpp.

◆ updateParameters()

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

Reimplemented from rtabmap_odom::OdometryROS.

Definition at line 167 of file icp_odometry.cpp.

Member Data Documentation

◆ cloud_sub_

ros::Subscriber rtabmap_odom::ICPOdometry::cloud_sub_
private

Definition at line 903 of file icp_odometry.cpp.

◆ cloudReceived_

bool rtabmap_odom::ICPOdometry::cloudReceived_ = false
private

Definition at line 919 of file icp_odometry.cpp.

◆ deskewing_

bool rtabmap_odom::ICPOdometry::deskewing_
private

Definition at line 914 of file icp_odometry.cpp.

◆ deskewingSlerp_

bool rtabmap_odom::ICPOdometry::deskewingSlerp_
private

Definition at line 915 of file icp_odometry.cpp.

◆ filtered_scan_pub_

ros::Publisher rtabmap_odom::ICPOdometry::filtered_scan_pub_
private

Definition at line 904 of file icp_odometry.cpp.

◆ plugin_loader_

pluginlib::ClassLoader<rtabmap_odom::PluginInterface> rtabmap_odom::ICPOdometry::plugin_loader_
private

Definition at line 917 of file icp_odometry.cpp.

◆ plugins_

std::vector<boost::shared_ptr<rtabmap_odom::PluginInterface> > rtabmap_odom::ICPOdometry::plugins_
private

Definition at line 916 of file icp_odometry.cpp.

◆ scan_sub_

ros::Subscriber rtabmap_odom::ICPOdometry::scan_sub_
private

Definition at line 902 of file icp_odometry.cpp.

◆ scanCloudIs2d_

bool rtabmap_odom::ICPOdometry::scanCloudIs2d_
private

Definition at line 906 of file icp_odometry.cpp.

◆ scanCloudMaxPoints_

int rtabmap_odom::ICPOdometry::scanCloudMaxPoints_
private

Definition at line 905 of file icp_odometry.cpp.

◆ scanDownsamplingStep_

int rtabmap_odom::ICPOdometry::scanDownsamplingStep_
private

Definition at line 907 of file icp_odometry.cpp.

◆ scanNormalGroundUp_

double rtabmap_odom::ICPOdometry::scanNormalGroundUp_
private

Definition at line 913 of file icp_odometry.cpp.

◆ scanNormalK_

int rtabmap_odom::ICPOdometry::scanNormalK_
private

Definition at line 911 of file icp_odometry.cpp.

◆ scanNormalRadius_

double rtabmap_odom::ICPOdometry::scanNormalRadius_
private

Definition at line 912 of file icp_odometry.cpp.

◆ scanRangeMax_

double rtabmap_odom::ICPOdometry::scanRangeMax_
private

Definition at line 909 of file icp_odometry.cpp.

◆ scanRangeMin_

double rtabmap_odom::ICPOdometry::scanRangeMin_
private

Definition at line 908 of file icp_odometry.cpp.

◆ scanReceived_

bool rtabmap_odom::ICPOdometry::scanReceived_ = false
private

Definition at line 918 of file icp_odometry.cpp.

◆ scanVoxelSize_

double rtabmap_odom::ICPOdometry::scanVoxelSize_
private

Definition at line 910 of file icp_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