diff --git a/rtabmap_odom/include/rtabmap_odom/OdometryROS.h b/rtabmap_odom/include/rtabmap_odom/OdometryROS.h index ee1d8277e..b42ebbe0c 100644 --- a/rtabmap_odom/include/rtabmap_odom/OdometryROS.h +++ b/rtabmap_odom/include/rtabmap_odom/OdometryROS.h @@ -155,19 +155,12 @@ class OdometryROS : public rclcpp::Node, public UThread rclcpp::Subscription::SharedPtr imuSub_; rclcpp::CallbackGroup::SharedPtr imuCallbackGroup_; - UMutex dataMutex_; - UMutex imuMutex_; - USemaphore dataReady_; - - rtabmap::SensorData dataToProcess_; - std_msgs::msg::Header dataHeaderToProcess_; - // Safe-threading UMutex imuMutex_; UMutex dataMutex_; USemaphore dataReady_; rtabmap::SensorData dataToProcess_; - std_msgs::Header dataHeaderToProcess_; + std_msgs::msg::Header dataHeaderToProcess_; bool paused_; int resetCountdown_; diff --git a/rtabmap_odom/src/OdometryROS.cpp b/rtabmap_odom/src/OdometryROS.cpp index 6a030c2c7..caa436a42 100644 --- a/rtabmap_odom/src/OdometryROS.cpp +++ b/rtabmap_odom/src/OdometryROS.cpp @@ -1113,7 +1113,7 @@ void OdometryROS::reset(const Transform & pose) resetCurrentCount_ = resetCountdown_; imuProcessed_ = false; dataToProcess_ = SensorData(); - dataHeaderToProcess_ = std_msgs::Header(); + dataHeaderToProcess_ = std_msgs::msg::Header(); imuMutex_.lock(); imus_.clear(); imuMutex_.unlock();