28 #ifndef ODOMETRYROS_H_ 29 #define ODOMETRYROS_H_ 37 #include <std_srvs/Empty.h> 38 #include <std_msgs/Header.h> 40 #include <rtabmap_ros/ResetPose.h> 44 #include <boost/thread.hpp> 56 OdometryROS(
bool stereoParams,
bool visParams,
bool icpParams);
61 bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
62 bool resetToPose(rtabmap_ros::ResetPose::Request&, rtabmap_ros::ResetPose::Response&);
63 bool pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
64 bool resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
65 bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
66 bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
67 bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
68 bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
70 const std::string &
frameId()
const {
return frameId_;}
71 const std::string &
odomFrameId()
const {
return odomFrameId_;}
77 void startWarningThread(
const std::string & subscribedTopicsMsg,
bool approxSync);
80 virtual void flushCallbacks() = 0;
84 void warningLoop(
const std::string & subscribedTopicsMsg,
bool approxSync);
85 virtual void onInit();
86 virtual void onOdomInit() = 0;
std::string groundTruthBaseFrameId_
const rtabmap::ParametersMap & parameters() const
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_
ros::ServiceServer pauseSrv_
ros::ServiceServer resumeSrv_
ros::Publisher odomLocalMap_
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_