28 #ifndef ODOMETRYROS_H_    29 #define ODOMETRYROS_H_    37 #include <std_srvs/Empty.h>    38 #include <std_msgs/Header.h>    39 #include <sensor_msgs/Imu.h>    41 #include <rtabmap_ros/ResetPose.h>    45 #include <boost/thread.hpp>    59         OdometryROS(
bool stereoParams, 
bool visParams, 
bool icpParams);
    64         bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
    65         bool resetToPose(rtabmap_ros::ResetPose::Request&, rtabmap_ros::ResetPose::Response&);
    66         bool pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
    67         bool resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
    68         bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
    69         bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
    70         bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
    71         bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
    73         const std::string & 
frameId()
 const {
return frameId_;}
    74         const std::string & 
odomFrameId()
 const {
return odomFrameId_;}
    80         void startWarningThread(
const std::string & subscribedTopicsMsg, 
bool approxSync);
    83         virtual void flushCallbacks() = 0;
    91         void warningLoop(
const std::string & subscribedTopicsMsg, 
bool approxSync);
    92         virtual void onInit();
    93         virtual void onOdomInit() = 0;
    96         void callbackIMU(
const sensor_msgs::ImuConstPtr& msg);
   153         std::map<double, rtabmap::IMU> 
imus_;
 std::string groundTruthBaseFrameId_
std::pair< rtabmap::SensorData, std_msgs::Header > bufferedData_
double expectedUpdateRate_
ros::Publisher odomRgbdImagePub_
tf2_ros::TransformBroadcaster tfBroadcaster_
virtual void updateParameters(rtabmap::ParametersMap ¶meters)
const std::string & frameId() const
double waitForTransformDuration_
boost::thread * warningThread_
const std::string & odomFrameId() const
ros::Publisher odomLocalScanMap_
double previousStamp() const
ros::ServiceServer setLogInfoSrv_
std::map< std::string, std::string > ParametersMap
bool publishNullWhenLost_
virtual void postProcessData(const rtabmap::SensorData &data, const std_msgs::Header &header) const
std::string groundTruthFrameId_
ros::ServiceServer setLogDebugSrv_
ULogToRosout ulogToRosout_
tf::TransformListener & tfListener()
ros::ServiceServer setLogWarnSrv_
ros::ServiceServer resetToPoseSrv_
rtabmap::ParametersMap parameters_
double waitForTransformDuration() const
ros::ServiceServer setLogErrorSrv_
ros::ServiceServer resetSrv_
std::map< double, rtabmap::IMU > imus_
ros::ServiceServer pauseSrv_
ros::ServiceServer resumeSrv_
ros::Publisher odomLocalMap_
rtabmap::Transform guessPreviousPose_
rtabmap::Odometry * odometry_
ros::Publisher odomInfoPub_
tf::TransformListener tfListener_
rtabmap::Transform guess_
double guessMinTranslation_
std::string guessFrameId_
ros::Publisher odomInfoLitePub_
const std::string & guessFrameId() const
const rtabmap::ParametersMap & parameters() const
ros::Publisher odomLastFrame_