diff --git a/lidar_localization/include/lidar_localization/subscriber/cloud_subscriber.hpp b/lidar_localization/include/lidar_localization/subscriber/cloud_subscriber.hpp index 67a3038..5e4d269 100644 --- a/lidar_localization/include/lidar_localization/subscriber/cloud_subscriber.hpp +++ b/lidar_localization/include/lidar_localization/subscriber/cloud_subscriber.hpp @@ -8,6 +8,8 @@ #define LIDAR_LOCALIZATION_SUBSCRIBER_CLOUD_SUBSCRIBER_HPP_ #include +#include +#include #include #include @@ -30,8 +32,9 @@ class CloudSubscriber { private: ros::NodeHandle nh_; ros::Subscriber subscriber_; - std::deque new_cloud_data_; + + std::mutex buff_mutex_; }; } diff --git a/lidar_localization/include/lidar_localization/subscriber/gnss_subscriber.hpp b/lidar_localization/include/lidar_localization/subscriber/gnss_subscriber.hpp index dc5f6d8..2f34d22 100644 --- a/lidar_localization/include/lidar_localization/subscriber/gnss_subscriber.hpp +++ b/lidar_localization/include/lidar_localization/subscriber/gnss_subscriber.hpp @@ -7,8 +7,12 @@ #define LIDAR_LOCALIZATION_SUBSCRIBER_GNSS_SUBSCRIBER_HPP_ #include +#include +#include + #include #include "sensor_msgs/NavSatFix.h" + #include "lidar_localization/sensor_data/gnss_data.hpp" namespace lidar_localization { @@ -24,8 +28,9 @@ class GNSSSubscriber { private: ros::NodeHandle nh_; ros::Subscriber subscriber_; - std::deque new_gnss_data_; + + std::mutex buff_mutex_; }; } #endif \ No newline at end of file diff --git a/lidar_localization/include/lidar_localization/subscriber/imu_subscriber.hpp b/lidar_localization/include/lidar_localization/subscriber/imu_subscriber.hpp index 8145fcc..ae527ee 100644 --- a/lidar_localization/include/lidar_localization/subscriber/imu_subscriber.hpp +++ b/lidar_localization/include/lidar_localization/subscriber/imu_subscriber.hpp @@ -7,8 +7,12 @@ #define LIDAR_LOCALIZATION_SUBSCRIBER_IMU_SUBSCRIBER_HPP_ #include +#include +#include + #include #include "sensor_msgs/Imu.h" + #include "lidar_localization/sensor_data/imu_data.hpp" namespace lidar_localization { @@ -24,8 +28,9 @@ class IMUSubscriber { private: ros::NodeHandle nh_; ros::Subscriber subscriber_; + std::deque new_imu_data_; - std::deque new_imu_data_; + std::mutex buff_mutex_; }; } #endif \ No newline at end of file diff --git a/lidar_localization/include/lidar_localization/subscriber/key_frame_subscriber.hpp b/lidar_localization/include/lidar_localization/subscriber/key_frame_subscriber.hpp index fdb59ce..40f2b90 100644 --- a/lidar_localization/include/lidar_localization/subscriber/key_frame_subscriber.hpp +++ b/lidar_localization/include/lidar_localization/subscriber/key_frame_subscriber.hpp @@ -7,6 +7,9 @@ #define LIDAR_LOCALIZATION_SUBSCRIBER_KEY_FRAME_SUBSCRIBER_HPP_ #include +#include +#include + #include #include @@ -25,8 +28,9 @@ class KeyFrameSubscriber { private: ros::NodeHandle nh_; ros::Subscriber subscriber_; + std::deque new_key_frame_; - std::deque new_key_frame_; + std::mutex buff_mutex_; }; } #endif \ No newline at end of file diff --git a/lidar_localization/include/lidar_localization/subscriber/key_frames_subscriber.hpp b/lidar_localization/include/lidar_localization/subscriber/key_frames_subscriber.hpp index 8fc3fde..81566f9 100644 --- a/lidar_localization/include/lidar_localization/subscriber/key_frames_subscriber.hpp +++ b/lidar_localization/include/lidar_localization/subscriber/key_frames_subscriber.hpp @@ -7,6 +7,9 @@ #define LIDAR_LOCALIZATION_SUBSCRIBER_KEY_FRAMES_SUBSCRIBER_HPP_ #include +#include +#include + #include #include #include @@ -26,8 +29,9 @@ class KeyFramesSubscriber { private: ros::NodeHandle nh_; ros::Subscriber subscriber_; + std::deque new_key_frames_; - std::deque new_key_frames_; + std::mutex buff_mutex_; }; } #endif \ No newline at end of file diff --git a/lidar_localization/include/lidar_localization/subscriber/loop_pose_subscriber.hpp b/lidar_localization/include/lidar_localization/subscriber/loop_pose_subscriber.hpp index dc8de26..72beb2f 100644 --- a/lidar_localization/include/lidar_localization/subscriber/loop_pose_subscriber.hpp +++ b/lidar_localization/include/lidar_localization/subscriber/loop_pose_subscriber.hpp @@ -7,6 +7,9 @@ #define LIDAR_LOCALIZATION_SUBSCRIBER_LOOP_POSE_SUBSCRIBER_HPP_ #include +#include +#include + #include #include @@ -25,8 +28,9 @@ class LoopPoseSubscriber { private: ros::NodeHandle nh_; ros::Subscriber subscriber_; + std::deque new_loop_pose_; - std::deque new_loop_pose_; + std::mutex buff_mutex_; }; } #endif \ No newline at end of file diff --git a/lidar_localization/include/lidar_localization/subscriber/odometry_subscriber.hpp b/lidar_localization/include/lidar_localization/subscriber/odometry_subscriber.hpp index 07e2c90..9c5c232 100644 --- a/lidar_localization/include/lidar_localization/subscriber/odometry_subscriber.hpp +++ b/lidar_localization/include/lidar_localization/subscriber/odometry_subscriber.hpp @@ -7,8 +7,12 @@ #define LIDAR_LOCALIZATION_SUBSCRIBER_ODOMETRY_SUBSCRIBER_HPP_ #include +#include +#include + #include #include + #include "lidar_localization/sensor_data/pose_data.hpp" namespace lidar_localization { @@ -24,8 +28,9 @@ class OdometrySubscriber { private: ros::NodeHandle nh_; ros::Subscriber subscriber_; + std::deque new_pose_data_; - std::deque new_pose_data_; + std::mutex buff_mutex_; }; } #endif \ No newline at end of file diff --git a/lidar_localization/include/lidar_localization/subscriber/velocity_subscriber.hpp b/lidar_localization/include/lidar_localization/subscriber/velocity_subscriber.hpp index 0d752a5..96ad94e 100644 --- a/lidar_localization/include/lidar_localization/subscriber/velocity_subscriber.hpp +++ b/lidar_localization/include/lidar_localization/subscriber/velocity_subscriber.hpp @@ -7,8 +7,12 @@ #define LIDAR_LOCALIZATION_SUBSCRIBER_VELOCITY_SUBSCRIBER_HPP_ #include +#include +#include + #include #include "geometry_msgs/TwistStamped.h" + #include "lidar_localization/sensor_data/velocity_data.hpp" namespace lidar_localization { @@ -24,8 +28,9 @@ class VelocitySubscriber { private: ros::NodeHandle nh_; ros::Subscriber subscriber_; + std::deque new_velocity_data_; - std::deque new_velocity_data_; + std::mutex buff_mutex_; }; } #endif \ No newline at end of file diff --git a/lidar_localization/src/subscriber/cloud_subscriber.cpp b/lidar_localization/src/subscriber/cloud_subscriber.cpp index 9da3d37..e5772b5 100644 --- a/lidar_localization/src/subscriber/cloud_subscriber.cpp +++ b/lidar_localization/src/subscriber/cloud_subscriber.cpp @@ -15,17 +15,21 @@ CloudSubscriber::CloudSubscriber(ros::NodeHandle& nh, std::string topic_name, si } void CloudSubscriber::msg_callback(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg_ptr) { + buff_mutex_.lock(); CloudData cloud_data; cloud_data.time = cloud_msg_ptr->header.stamp.toSec(); pcl::fromROSMsg(*cloud_msg_ptr, *(cloud_data.cloud_ptr)); new_cloud_data_.push_back(cloud_data); + buff_mutex_.unlock(); } void CloudSubscriber::ParseData(std::deque& cloud_data_buff) { + buff_mutex_.lock(); if (new_cloud_data_.size() > 0) { cloud_data_buff.insert(cloud_data_buff.end(), new_cloud_data_.begin(), new_cloud_data_.end()); new_cloud_data_.clear(); } + buff_mutex_.unlock(); } } // namespace data_input \ No newline at end of file diff --git a/lidar_localization/src/subscriber/gnss_subscriber.cpp b/lidar_localization/src/subscriber/gnss_subscriber.cpp index 9a07181..120e705 100644 --- a/lidar_localization/src/subscriber/gnss_subscriber.cpp +++ b/lidar_localization/src/subscriber/gnss_subscriber.cpp @@ -14,6 +14,7 @@ GNSSSubscriber::GNSSSubscriber(ros::NodeHandle& nh, std::string topic_name, size } void GNSSSubscriber::msg_callback(const sensor_msgs::NavSatFixConstPtr& nav_sat_fix_ptr) { + buff_mutex_.lock(); GNSSData gnss_data; gnss_data.time = nav_sat_fix_ptr->header.stamp.toSec(); gnss_data.latitude = nav_sat_fix_ptr->latitude; @@ -23,12 +24,15 @@ void GNSSSubscriber::msg_callback(const sensor_msgs::NavSatFixConstPtr& nav_sat_ gnss_data.service = nav_sat_fix_ptr->status.service; new_gnss_data_.push_back(gnss_data); + buff_mutex_.unlock(); } void GNSSSubscriber::ParseData(std::deque& gnss_data_buff) { + buff_mutex_.lock(); if (new_gnss_data_.size() > 0) { gnss_data_buff.insert(gnss_data_buff.end(), new_gnss_data_.begin(), new_gnss_data_.end()); new_gnss_data_.clear(); } + buff_mutex_.unlock(); } } \ No newline at end of file diff --git a/lidar_localization/src/subscriber/imu_subscriber.cpp b/lidar_localization/src/subscriber/imu_subscriber.cpp index 60b32b1..44d9bb4 100644 --- a/lidar_localization/src/subscriber/imu_subscriber.cpp +++ b/lidar_localization/src/subscriber/imu_subscriber.cpp @@ -13,6 +13,7 @@ IMUSubscriber::IMUSubscriber(ros::NodeHandle& nh, std::string topic_name, size_t } void IMUSubscriber::msg_callback(const sensor_msgs::ImuConstPtr& imu_msg_ptr) { + buff_mutex_.lock(); IMUData imu_data; imu_data.time = imu_msg_ptr->header.stamp.toSec(); @@ -30,12 +31,15 @@ void IMUSubscriber::msg_callback(const sensor_msgs::ImuConstPtr& imu_msg_ptr) { imu_data.orientation.w = imu_msg_ptr->orientation.w; new_imu_data_.push_back(imu_data); + buff_mutex_.unlock(); } void IMUSubscriber::ParseData(std::deque& imu_data_buff) { + buff_mutex_.lock(); if (new_imu_data_.size() > 0) { imu_data_buff.insert(imu_data_buff.end(), new_imu_data_.begin(), new_imu_data_.end()); new_imu_data_.clear(); } + buff_mutex_.unlock(); } } \ No newline at end of file diff --git a/lidar_localization/src/subscriber/key_frame_subscriber.cpp b/lidar_localization/src/subscriber/key_frame_subscriber.cpp index 2e94a98..8d8fdde 100644 --- a/lidar_localization/src/subscriber/key_frame_subscriber.cpp +++ b/lidar_localization/src/subscriber/key_frame_subscriber.cpp @@ -13,6 +13,7 @@ KeyFrameSubscriber::KeyFrameSubscriber(ros::NodeHandle& nh, std::string topic_na } void KeyFrameSubscriber::msg_callback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& key_frame_msg_ptr) { + buff_mutex_.lock(); KeyFrame key_frame; key_frame.time = key_frame_msg_ptr->header.stamp.toSec(); key_frame.index = (unsigned int)key_frame_msg_ptr->pose.covariance[0]; @@ -29,12 +30,15 @@ void KeyFrameSubscriber::msg_callback(const geometry_msgs::PoseWithCovarianceSta key_frame.pose.block<3,3>(0,0) = q.matrix(); new_key_frame_.push_back(key_frame); + buff_mutex_.unlock(); } void KeyFrameSubscriber::ParseData(std::deque& key_frame_buff) { + buff_mutex_.lock(); if (new_key_frame_.size() > 0) { key_frame_buff.insert(key_frame_buff.end(), new_key_frame_.begin(), new_key_frame_.end()); new_key_frame_.clear(); } + buff_mutex_.unlock(); } } \ No newline at end of file diff --git a/lidar_localization/src/subscriber/key_frames_subscriber.cpp b/lidar_localization/src/subscriber/key_frames_subscriber.cpp index a6911cf..0d4a9b0 100644 --- a/lidar_localization/src/subscriber/key_frames_subscriber.cpp +++ b/lidar_localization/src/subscriber/key_frames_subscriber.cpp @@ -13,6 +13,7 @@ KeyFramesSubscriber::KeyFramesSubscriber(ros::NodeHandle& nh, std::string topic_ } void KeyFramesSubscriber::msg_callback(const nav_msgs::Path::ConstPtr& key_frames_msg_ptr) { + buff_mutex_.lock(); new_key_frames_.clear(); for (size_t i = 0; i < key_frames_msg_ptr->poses.size(); i++) { @@ -33,12 +34,15 @@ void KeyFramesSubscriber::msg_callback(const nav_msgs::Path::ConstPtr& key_frame new_key_frames_.push_back(key_frame); } + buff_mutex_.unlock(); } void KeyFramesSubscriber::ParseData(std::deque& key_frames_buff) { + buff_mutex_.lock(); if (new_key_frames_.size() > 0) { key_frames_buff = new_key_frames_; new_key_frames_.clear(); } + buff_mutex_.unlock(); } } \ No newline at end of file diff --git a/lidar_localization/src/subscriber/loop_pose_subscriber.cpp b/lidar_localization/src/subscriber/loop_pose_subscriber.cpp index e70517c..9da7862 100644 --- a/lidar_localization/src/subscriber/loop_pose_subscriber.cpp +++ b/lidar_localization/src/subscriber/loop_pose_subscriber.cpp @@ -13,6 +13,7 @@ LoopPoseSubscriber::LoopPoseSubscriber(ros::NodeHandle& nh, std::string topic_na } void LoopPoseSubscriber::msg_callback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& loop_pose_msg_ptr) { + buff_mutex_.lock(); LoopPose loop_pose; loop_pose.time = loop_pose_msg_ptr->header.stamp.toSec(); loop_pose.index0 = (unsigned int)loop_pose_msg_ptr->pose.covariance[0]; @@ -30,12 +31,15 @@ void LoopPoseSubscriber::msg_callback(const geometry_msgs::PoseWithCovarianceSta loop_pose.pose.block<3,3>(0,0) = q.matrix(); new_loop_pose_.push_back(loop_pose); + buff_mutex_.unlock(); } void LoopPoseSubscriber::ParseData(std::deque& loop_pose_buff) { + buff_mutex_.lock(); if (new_loop_pose_.size() > 0) { loop_pose_buff.insert(loop_pose_buff.end(), new_loop_pose_.begin(), new_loop_pose_.end()); new_loop_pose_.clear(); } + buff_mutex_.unlock(); } } \ No newline at end of file diff --git a/lidar_localization/src/subscriber/odometry_subscriber.cpp b/lidar_localization/src/subscriber/odometry_subscriber.cpp index 835428d..8cedfd4 100644 --- a/lidar_localization/src/subscriber/odometry_subscriber.cpp +++ b/lidar_localization/src/subscriber/odometry_subscriber.cpp @@ -13,6 +13,7 @@ OdometrySubscriber::OdometrySubscriber(ros::NodeHandle& nh, std::string topic_na } void OdometrySubscriber::msg_callback(const nav_msgs::OdometryConstPtr& odom_msg_ptr) { + buff_mutex_.lock(); PoseData pose_data; pose_data.time = odom_msg_ptr->header.stamp.toSec(); @@ -29,12 +30,15 @@ void OdometrySubscriber::msg_callback(const nav_msgs::OdometryConstPtr& odom_msg pose_data.pose.block<3,3>(0,0) = q.matrix(); new_pose_data_.push_back(pose_data); + buff_mutex_.unlock(); } void OdometrySubscriber::ParseData(std::deque& pose_data_buff) { + buff_mutex_.lock(); if (new_pose_data_.size() > 0) { pose_data_buff.insert(pose_data_buff.end(), new_pose_data_.begin(), new_pose_data_.end()); new_pose_data_.clear(); } + buff_mutex_.unlock(); } } \ No newline at end of file diff --git a/lidar_localization/src/subscriber/velocity_subscriber.cpp b/lidar_localization/src/subscriber/velocity_subscriber.cpp index 24b9b55..b54eaff 100644 --- a/lidar_localization/src/subscriber/velocity_subscriber.cpp +++ b/lidar_localization/src/subscriber/velocity_subscriber.cpp @@ -14,6 +14,7 @@ VelocitySubscriber::VelocitySubscriber(ros::NodeHandle& nh, std::string topic_na } void VelocitySubscriber::msg_callback(const geometry_msgs::TwistStampedConstPtr& twist_msg_ptr) { + buff_mutex_.lock(); VelocityData velocity_data; velocity_data.time = twist_msg_ptr->header.stamp.toSec(); @@ -26,12 +27,15 @@ void VelocitySubscriber::msg_callback(const geometry_msgs::TwistStampedConstPtr& velocity_data.angular_velocity.z = twist_msg_ptr->twist.angular.z; new_velocity_data_.push_back(velocity_data); + buff_mutex_.unlock(); } void VelocitySubscriber::ParseData(std::deque& velocity_data_buff) { + buff_mutex_.lock(); if (new_velocity_data_.size() > 0) { velocity_data_buff.insert(velocity_data_buff.end(), new_velocity_data_.begin(), new_velocity_data_.end()); new_velocity_data_.clear(); } + buff_mutex_.unlock(); } } \ No newline at end of file