Go to the documentation of this file.
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>
43 #include <rtabmap_msgs/ResetPose.h>
48 #include <boost/thread.hpp>
63 OdometryROS(
bool stereoParams,
bool visParams,
bool icpParams);
68 bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
69 bool resetToPose(rtabmap_msgs::ResetPose::Request&, rtabmap_msgs::ResetPose::Response&);
70 bool pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
71 bool resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
72 bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
73 bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
74 bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
75 bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
84 void initDiagnosticMsg(
const std::string & subscribedTopicsMsg,
bool approxSync,
const std::string & subscribedTopic =
"");
101 void callbackIMU(
const sensor_msgs::ImuConstPtr& msg);
170 std::map<double, rtabmap::IMU>
imus_;
ros::ServiceServer resumeSrv_
void processData(rtabmap::SensorData &data, const std_msgs::Header &header)
rtabmap::Odometry * odometry_
bool publishCompressedSensorData_
std::map< double, rtabmap::IMU > imus_
std::string groundTruthBaseFrameId_
OdomStatusTask statusDiagnostic_
bool resume(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Publisher odomInfoLitePub_
rtabmap::Transform velocityGuess() const
ros::Publisher odomSensorDataFeaturesPub_
rtabmap_util::ULogToRosout ulogToRosout_
ros::Publisher odomLocalMap_
double previousStamp() const
void initDiagnosticMsg(const std::string &subscribedTopicsMsg, bool approxSync, const std::string &subscribedTopic="")
tf::TransformListener tfListener_
std::map< std::string, std::string > ParametersMap
std_msgs::Header dataHeaderToProcess_
bool publishNullWhenLost_
rtabmap::Transform guessPreviousPose_
void callbackIMU(const sensor_msgs::ImuConstPtr &msg)
OdometryROS(bool stereoParams, bool visParams, bool icpParams)
bool pause(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
std::string compressionImgFormat_
rtabmap::ParametersMap parameters_
const std::string & odomFrameId() const
bool compressionParallelized_
virtual void flushCallbacks()=0
std::unique_ptr< rtabmap_sync::SyncDiagnostic > syncDiagnostic_
ros::Publisher odomSensorDataCompressedPub_
ros::Publisher odomSensorDataPub_
ros::ServiceServer resetSrv_
double expectedUpdateRate_
double waitForTransformDuration() const
bool setLogWarn(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
const rtabmap::ParametersMap & parameters() const
ros::ServiceServer setLogErrorSrv_
ros::Publisher odomLastFrame_
const std::string & guessFrameId() const
ros::Publisher odomInfoPub_
ros::Publisher odomLocalScanMap_
bool setLogInfo(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool setLogError(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
rtabmap::Transform guess_
tf2_ros::TransformBroadcaster tfBroadcaster_
bool bufferedDataToProcess_
tf::TransformListener & tfListener()
virtual void onOdomInit()=0
bool reset(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::Publisher odomRgbdImagePub_
std::string guessFrameId_
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::ServiceServer pauseSrv_
virtual void postProcessData(const rtabmap::SensorData &data, const std_msgs::Header &header) const
virtual void updateParameters(rtabmap::ParametersMap ¶meters)
ros::ServiceServer setLogInfoSrv_
ros::ServiceServer setLogDebugSrv_
std::string groundTruthFrameId_
double waitForTransformDuration_
void setStatus(bool isLost)
ros::ServiceServer resetToPoseSrv_
bool resetToPose(rtabmap_msgs::ResetPose::Request &, rtabmap_msgs::ResetPose::Response &)
GenericOdometry< Point2 > Odometry
ros::ServiceServer setLogWarnSrv_
virtual void mainLoopKill()
const std::string & frameId() const
rtabmap::SensorData dataToProcess_
double guessMinTranslation_
rtabmap_odom
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:42:24