Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
rtabmap_ros::OdometryROS Class Referenceabstract

#include <OdometryROS.h>

Inheritance diagram for rtabmap_ros::OdometryROS:
Inheritance graph
[legend]

Public Member Functions

const std::string & frameId () const
 
rtabmap::Transform getTransform (const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp) const
 
bool isPaused () const
 
 OdometryROS (bool stereoParams, bool visParams, bool icpParams)
 
const std::string & odomFrameId () const
 
const rtabmap::ParametersMapparameters () const
 
bool pause (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
void processData (const rtabmap::SensorData &data, const ros::Time &stamp)
 
bool reset (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
bool resetToPose (rtabmap_ros::ResetPose::Request &, rtabmap_ros::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 ()
 

Protected Member Functions

void callbackCalled ()
 
virtual void flushCallbacks ()=0
 
void startWarningThread (const std::string &subscribedTopicsMsg, bool approxSync)
 
tf::TransformListenertfListener ()
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Private Member Functions

virtual void onInit ()
 
virtual void onOdomInit ()=0
 
virtual void updateParameters (rtabmap::ParametersMap &parameters)
 
void warningLoop (const std::string &subscribedTopicsMsg, bool approxSync)
 

Private Attributes

bool callbackCalled_
 
std::string frameId_
 
std::string groundTruthBaseFrameId_
 
std::string groundTruthFrameId_
 
rtabmap::Transform guess_
 
std::string guessFrameId_
 
double guessMinRotation_
 
double guessMinTranslation_
 
double guessStamp_
 
bool icpParams_
 
rtabmap::Odometryodometry_
 
std::string odomFrameId_
 
ros::Publisher odomInfoPub_
 
ros::Publisher odomLastFrame_
 
ros::Publisher odomLocalMap_
 
ros::Publisher odomLocalScanMap_
 
ros::Publisher odomPub_
 
rtabmap::ParametersMap parameters_
 
bool paused_
 
ros::ServiceServer pauseSrv_
 
bool publishNullWhenLost_
 
bool publishTf_
 
int resetCountdown_
 
int resetCurrentCount_
 
ros::ServiceServer resetSrv_
 
ros::ServiceServer resetToPoseSrv_
 
ros::ServiceServer resumeSrv_
 
ros::ServiceServer setLogDebugSrv_
 
ros::ServiceServer setLogErrorSrv_
 
ros::ServiceServer setLogInfoSrv_
 
ros::ServiceServer setLogWarnSrv_
 
bool stereoParams_
 
tf2_ros::TransformBroadcaster tfBroadcaster_
 
tf::TransformListener tfListener_
 
bool visParams_
 
bool waitForTransform_
 
double waitForTransformDuration_
 
boost::thread * warningThread_
 

Detailed Description

Definition at line 52 of file OdometryROS.h.

Constructor & Destructor Documentation

rtabmap_ros::OdometryROS::OdometryROS ( bool  stereoParams,
bool  visParams,
bool  icpParams 
)

Definition at line 60 of file OdometryROS.cpp.

rtabmap_ros::OdometryROS::~OdometryROS ( )
virtual

Definition at line 86 of file OdometryROS.cpp.

Member Function Documentation

void rtabmap_ros::OdometryROS::callbackCalled ( )
inlineprotected

Definition at line 78 of file OdometryROS.h.

virtual void rtabmap_ros::OdometryROS::flushCallbacks ( )
protectedpure virtual
const std::string& rtabmap_ros::OdometryROS::frameId ( ) const
inline

Definition at line 70 of file OdometryROS.h.

Transform rtabmap_ros::OdometryROS::getTransform ( const std::string &  fromFrameId,
const std::string &  toFrameId,
const ros::Time stamp 
) const

Definition at line 350 of file OdometryROS.cpp.

bool rtabmap_ros::OdometryROS::isPaused ( ) const
inline

Definition at line 73 of file OdometryROS.h.

const std::string& rtabmap_ros::OdometryROS::odomFrameId ( ) const
inline

Definition at line 71 of file OdometryROS.h.

void rtabmap_ros::OdometryROS::onInit ( )
privatevirtual

Implements nodelet::Nodelet.

Definition at line 106 of file OdometryROS.cpp.

virtual void rtabmap_ros::OdometryROS::onOdomInit ( )
privatepure virtual
const rtabmap::ParametersMap& rtabmap_ros::OdometryROS::parameters ( ) const
inline

Definition at line 72 of file OdometryROS.h.

bool rtabmap_ros::OdometryROS::pause ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)

Definition at line 730 of file OdometryROS.cpp.

void rtabmap_ros::OdometryROS::processData ( const rtabmap::SensorData data,
const ros::Time stamp 
)

Definition at line 379 of file OdometryROS.cpp.

bool rtabmap_ros::OdometryROS::reset ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)

Definition at line 707 of file OdometryROS.cpp.

bool rtabmap_ros::OdometryROS::resetToPose ( rtabmap_ros::ResetPose::Request &  req,
rtabmap_ros::ResetPose::Response &   
)

Definition at line 718 of file OdometryROS.cpp.

bool rtabmap_ros::OdometryROS::resume ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)

Definition at line 744 of file OdometryROS.cpp.

bool rtabmap_ros::OdometryROS::setLogDebug ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)

Definition at line 758 of file OdometryROS.cpp.

bool rtabmap_ros::OdometryROS::setLogError ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)

Definition at line 776 of file OdometryROS.cpp.

bool rtabmap_ros::OdometryROS::setLogInfo ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)

Definition at line 764 of file OdometryROS.cpp.

bool rtabmap_ros::OdometryROS::setLogWarn ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)

Definition at line 770 of file OdometryROS.cpp.

void rtabmap_ros::OdometryROS::startWarningThread ( const std::string &  subscribedTopicsMsg,
bool  approxSync 
)
protected

Definition at line 325 of file OdometryROS.cpp.

tf::TransformListener& rtabmap_ros::OdometryROS::tfListener ( )
inlineprotected

Definition at line 81 of file OdometryROS.h.

virtual void rtabmap_ros::OdometryROS::updateParameters ( rtabmap::ParametersMap parameters)
inlineprivatevirtual

Definition at line 87 of file OdometryROS.h.

void rtabmap_ros::OdometryROS::warningLoop ( const std::string &  subscribedTopicsMsg,
bool  approxSync 
)
private

Definition at line 331 of file OdometryROS.cpp.

Member Data Documentation

bool rtabmap_ros::OdometryROS::callbackCalled_
private

Definition at line 92 of file OdometryROS.h.

std::string rtabmap_ros::OdometryROS::frameId_
private

Definition at line 95 of file OdometryROS.h.

std::string rtabmap_ros::OdometryROS::groundTruthBaseFrameId_
private

Definition at line 98 of file OdometryROS.h.

std::string rtabmap_ros::OdometryROS::groundTruthFrameId_
private

Definition at line 97 of file OdometryROS.h.

rtabmap::Transform rtabmap_ros::OdometryROS::guess_
private

Definition at line 130 of file OdometryROS.h.

std::string rtabmap_ros::OdometryROS::guessFrameId_
private

Definition at line 99 of file OdometryROS.h.

double rtabmap_ros::OdometryROS::guessMinRotation_
private

Definition at line 101 of file OdometryROS.h.

double rtabmap_ros::OdometryROS::guessMinTranslation_
private

Definition at line 100 of file OdometryROS.h.

double rtabmap_ros::OdometryROS::guessStamp_
private

Definition at line 131 of file OdometryROS.h.

bool rtabmap_ros::OdometryROS::icpParams_
private

Definition at line 129 of file OdometryROS.h.

rtabmap::Odometry* rtabmap_ros::OdometryROS::odometry_
private

Definition at line 90 of file OdometryROS.h.

std::string rtabmap_ros::OdometryROS::odomFrameId_
private

Definition at line 96 of file OdometryROS.h.

ros::Publisher rtabmap_ros::OdometryROS::odomInfoPub_
private

Definition at line 109 of file OdometryROS.h.

ros::Publisher rtabmap_ros::OdometryROS::odomLastFrame_
private

Definition at line 112 of file OdometryROS.h.

ros::Publisher rtabmap_ros::OdometryROS::odomLocalMap_
private

Definition at line 110 of file OdometryROS.h.

ros::Publisher rtabmap_ros::OdometryROS::odomLocalScanMap_
private

Definition at line 111 of file OdometryROS.h.

ros::Publisher rtabmap_ros::OdometryROS::odomPub_
private

Definition at line 108 of file OdometryROS.h.

rtabmap::ParametersMap rtabmap_ros::OdometryROS::parameters_
private

Definition at line 106 of file OdometryROS.h.

bool rtabmap_ros::OdometryROS::paused_
private

Definition at line 124 of file OdometryROS.h.

ros::ServiceServer rtabmap_ros::OdometryROS::pauseSrv_
private

Definition at line 115 of file OdometryROS.h.

bool rtabmap_ros::OdometryROS::publishNullWhenLost_
private

Definition at line 105 of file OdometryROS.h.

bool rtabmap_ros::OdometryROS::publishTf_
private

Definition at line 102 of file OdometryROS.h.

int rtabmap_ros::OdometryROS::resetCountdown_
private

Definition at line 125 of file OdometryROS.h.

int rtabmap_ros::OdometryROS::resetCurrentCount_
private

Definition at line 126 of file OdometryROS.h.

ros::ServiceServer rtabmap_ros::OdometryROS::resetSrv_
private

Definition at line 113 of file OdometryROS.h.

ros::ServiceServer rtabmap_ros::OdometryROS::resetToPoseSrv_
private

Definition at line 114 of file OdometryROS.h.

ros::ServiceServer rtabmap_ros::OdometryROS::resumeSrv_
private

Definition at line 116 of file OdometryROS.h.

ros::ServiceServer rtabmap_ros::OdometryROS::setLogDebugSrv_
private

Definition at line 117 of file OdometryROS.h.

ros::ServiceServer rtabmap_ros::OdometryROS::setLogErrorSrv_
private

Definition at line 120 of file OdometryROS.h.

ros::ServiceServer rtabmap_ros::OdometryROS::setLogInfoSrv_
private

Definition at line 118 of file OdometryROS.h.

ros::ServiceServer rtabmap_ros::OdometryROS::setLogWarnSrv_
private

Definition at line 119 of file OdometryROS.h.

bool rtabmap_ros::OdometryROS::stereoParams_
private

Definition at line 127 of file OdometryROS.h.

tf2_ros::TransformBroadcaster rtabmap_ros::OdometryROS::tfBroadcaster_
private

Definition at line 121 of file OdometryROS.h.

tf::TransformListener rtabmap_ros::OdometryROS::tfListener_
private

Definition at line 122 of file OdometryROS.h.

bool rtabmap_ros::OdometryROS::visParams_
private

Definition at line 128 of file OdometryROS.h.

bool rtabmap_ros::OdometryROS::waitForTransform_
private

Definition at line 103 of file OdometryROS.h.

double rtabmap_ros::OdometryROS::waitForTransformDuration_
private

Definition at line 104 of file OdometryROS.h.

boost::thread* rtabmap_ros::OdometryROS::warningThread_
private

Definition at line 91 of file OdometryROS.h.


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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:05