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> 57 OdometryROS(
bool stereoParams,
bool visParams,
bool icpParams);
62 bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
63 bool resetToPose(rtabmap_ros::ResetPose::Request&, rtabmap_ros::ResetPose::Response&);
64 bool pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
65 bool resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
66 bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
67 bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
68 bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
69 bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
71 const std::string &
frameId()
const {
return frameId_;}
72 const std::string &
odomFrameId()
const {
return odomFrameId_;}
78 void startWarningThread(
const std::string & subscribedTopicsMsg,
bool approxSync);
81 virtual void flushCallbacks() = 0;
85 void warningLoop(
const std::string & subscribedTopicsMsg,
bool approxSync);
86 virtual void onInit();
87 virtual void onOdomInit() = 0;
90 void callbackIMU(
const sensor_msgs::ImuConstPtr& msg);
145 std::map<double, rtabmap::IMU>
imus_;
146 std::pair<rtabmap::SensorData, std::pair<ros::Time, std::string> >
bufferedData_;
std::string groundTruthBaseFrameId_
const rtabmap::ParametersMap & parameters() const
double expectedUpdateRate_
ros::Publisher odomRgbdImagePub_
const std::string & frameId() const
tf2_ros::TransformBroadcaster tfBroadcaster_
virtual void updateParameters(rtabmap::ParametersMap ¶meters)
double waitForTransformDuration_
boost::thread * warningThread_
ros::Publisher odomLocalScanMap_
ros::ServiceServer setLogInfoSrv_
std::map< std::string, std::string > ParametersMap
bool publishNullWhenLost_
std::string groundTruthFrameId_
ros::ServiceServer setLogDebugSrv_
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
tf::TransformListener & tfListener()
ros::ServiceServer setLogWarnSrv_
ros::ServiceServer resetToPoseSrv_
rtabmap::ParametersMap parameters_
ros::ServiceServer setLogErrorSrv_
ros::ServiceServer resetSrv_
std::map< double, rtabmap::IMU > imus_
ros::ServiceServer pauseSrv_
ros::ServiceServer resumeSrv_
ros::Publisher odomLocalMap_
rtabmap::Transform guessPreviousPose_
const std::string & odomFrameId() const
rtabmap::Odometry * odometry_
ros::Publisher odomInfoPub_
tf::TransformListener tfListener_
rtabmap::Transform guess_
double guessMinTranslation_
std::string guessFrameId_
ros::Publisher odomLastFrame_
std::pair< rtabmap::SensorData, std::pair< ros::Time, std::string > > bufferedData_