Bläddra i källkod

2020/09/23 ros消息转换与发送

wk 4 år sedan
förälder
incheckning
8619859ae3

+ 3 - 3
CMakeLists.txt

@@ -35,7 +35,7 @@ catkin_package(
 
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/Processing_Message PROCESSING_MESSAGE_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/message MESSAGE_SRC )
-aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/thread_condition THREAD_CONDITION_SRC )
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/tool TOOL_SRC )
 
 include_directories(
         /usr/local/include
@@ -43,7 +43,7 @@ include_directories(
         ${PCL_INCLUDE_DIRS}
         ${PROTOBUF_INCLUDE_DIRS}
         message
-        thread_condition
+        tool
         Processing_Message
 )
 
@@ -52,7 +52,7 @@ include_directories(
 add_executable(test_node
         ./src/main.cpp
         ${PROCESSING_MESSAGE_SRC}
-        ${THREAD_CONDITION_SRC}
+        ${TOOL_SRC}
         ${MESSAGE_SRC}
         )
 

+ 129 - 70
Processing_Message/Processing_message.cpp

@@ -6,136 +6,163 @@
 Processing_message::Processing_message()
 {
 	m_connect_statu=CONNECT_ERROR;
-	mp_receive_data_thread=NULL;
-	mp_send_data_thread=NULL;
+	mp_socket_receive_data_thread=NULL;
+	mp_ros_public_thread=NULL;
+	mp_socket_send_data_thread=NULL;
 }
 Processing_message::~Processing_message()
 {
 	Processing_message_uninit();
 }
 void Processing_message::Processing_message_init(std::string server_ip)
+{
+	Processing_message_connect(server_ip);
+}
+void Processing_message::Processing_message_connect(std::string server_ip)
 {
 	m_socket.connect(server_ip);//连接目标地址
 	Processing_message_run();
 }
+void Processing_message::Processing_message_band(std::string ip)
+{
+	m_socket.bind(ip);
+	Processing_message_run();
+}
 //启动程序
 void Processing_message::Processing_message_run()
 {
+
+
 	m_connect_statu = CONNECT_NORMAL;
-	m_receive_condition.reset(false, false, false);
-	mp_receive_data_thread = new std::thread(&Processing_message::receive_data_thread,this);//用于接收消息的线程
+	//默认循环 内部recv等待
+	m_socket_receive_condition.reset(false, false, false);
+	mp_socket_receive_data_thread = new std::thread(&Processing_message::socket_receive_data_thread,this);//用于接收消息的线程
+
+	//默认循环
+	m_ros_public_condition.reset(false, true, false);
+	mp_ros_public_thread = new std::thread(&Processing_message::ros_public_thread, this);
 
-	m_send_data_condition.reset(false, false, false);
-	mp_send_data_thread = new std::thread(&Processing_message::send_data_thread, this);
 }
 //反初始化
 void Processing_message::Processing_message_uninit()
 {
+	m_socket_data_queue.termination_queue();
 	//杀死线程,强制退出
-	if (mp_receive_data_thread)
+	if (mp_socket_receive_data_thread)
 	{
-		m_receive_condition.kill_all();
+		m_socket_receive_condition.kill_all();
 	}
-	if (mp_send_data_thread)
+
+	if (mp_ros_public_thread)
 	{
-		m_send_data_condition.kill_all();
+		m_ros_public_condition.kill_all();
 	}
 	//回收线程的资源
-	if (mp_receive_data_thread)
+	if (mp_socket_receive_data_thread)
 	{
-		mp_receive_data_thread->join();
-		delete mp_receive_data_thread;
-		mp_receive_data_thread = NULL;
+		mp_socket_receive_data_thread->join();
+		delete mp_socket_receive_data_thread;
+		mp_socket_receive_data_thread = NULL;
 	}
-	if (mp_send_data_thread)
+	if (mp_ros_public_thread)
 	{
-		mp_send_data_thread->join();
-		delete mp_send_data_thread;
-		mp_send_data_thread = NULL;
+		mp_ros_public_thread->join();
+		delete mp_ros_public_thread;
+		mp_ros_public_thread = NULL;
 	}
+	if (mp_socket_send_data_thread)
+	{
+		mp_socket_send_data_thread->join();
+		delete mp_socket_send_data_thread;
+		mp_socket_send_data_thread = NULL;
+	}
+	for (auto iter = m_ros_publisher_map.begin(); iter != m_ros_publisher_map.end(); ++iter)
+	{
+	    delete iter->second;
+	}
+	m_ros_publisher_map.clear();
 	m_connect_statu = CONNECT_ERROR;
 	m_socket.close();
 }
 //接收发送过来的消息
-void Processing_message::receive_data_thread()
+void Processing_message::socket_receive_data_thread()
 {
-	while (m_receive_condition.is_alive())
+	while (m_socket_receive_condition.is_alive())
 	{
-		m_receive_condition.wait_for_ex(std::chrono::microseconds(1));
-		if ( m_receive_condition.is_alive() )
+		m_socket_receive_condition.wait_for_ex(std::chrono::microseconds(1));
+		if ( m_socket_receive_condition.is_alive() )
 		{
 			std::this_thread::yield();
 			std::string t_receive_string;
 			{
-				std::unique_lock<std::mutex> lk(m_mutex);
+				std::unique_lock<std::mutex> lk(m_socket_mutex);
 				t_receive_string = m_socket.recv<std::string>(1);
 			}
 			if(t_receive_string.size()>0)//数据长度大于0则说明接收到了消息
 			{
-				rosDataMsg.ParseFromString(t_receive_string);
-				if(rosDataMsg.base_info().msg_type() == message::eRos_data_msg)//筛选出我需要的消息
-				{
-					std::cout<<"唤醒..."<<std::endl;
-					m_send_data_condition.notify_all(false,true);
-				}
-				else if(rosDataMsg.base_info().msg_type() == message::eGoal_msg)
-				{
+					if(m_socket_data_queue.push(t_receive_string))
+					{
+//						std::cout<<"data push success!"<<std::endl;
+					}
 
-				}
 			}
 			t_receive_string.clear();
 		}
 	}
 
 }
-void Processing_message::send_data_thread()
+void Processing_message::ros_public_thread()
 {
-	while (m_send_data_condition.is_alive())
+	//通信解析线程, 负责巡检m_receive_data_list, 并解析和处理消息
+	while (m_ros_public_condition.is_alive())
 	{
-		m_send_data_condition.wait();
-		if (m_send_data_condition.is_alive())
+	//	m_analysis_data_condition.wait_for_ex(std::chrono::microseconds(1));
+		if ( m_ros_public_condition.is_alive() )
 		{
 			std::this_thread::yield();
-
-			ros::NodeHandle nh;
-			ros::Publisher pubCloudL = nh.advertise<sensor_msgs::PointCloud> (rosDataMsg.cloud_msg().topic(), 1);
-			ros::Publisher trajectory = nh.advertise<sensor_msgs::PointCloud> (rosDataMsg.trajectory().topic(), 1);
-			ros::Publisher pose = nh.advertise<geometry_msgs::PoseStamped>(rosDataMsg.target_pose().topic(),true);
-			ros::Rate loop_rate(20);
-
-			while(ros::ok())
+			//如果解析线程被主动唤醒, 那么就表示 收到新的消息
+			std::string t_queue_data;
+			if(m_socket_data_queue.wait_and_pop(t_queue_data))
 			{
-				//填充pose信息
-				geometry_msgs::PoseStamped poseStamped;
-				poseStamped.header.frame_id=rosDataMsg.target_pose().frame_id();
-
-				poseStamped.pose.position.x=rosDataMsg.target_pose().x();
-				poseStamped.pose.position.y=rosDataMsg.target_pose().y();
-				poseStamped.pose.position.z=0;
-				poseStamped.pose.orientation.x=0*sin(rosDataMsg.target_pose().theta()/2);
-				poseStamped.pose.orientation.y=0*sin(rosDataMsg.target_pose().theta()/2);
-				poseStamped.pose.orientation.z=1*sin(rosDataMsg.target_pose().theta()/2);
-				poseStamped.pose.orientation.w=cos(rosDataMsg.target_pose().theta()/2);
-
-				sensor_msgs::PointCloud cloud_msg=create_cloudmsg(rosDataMsg.cloud_msg());
-				sensor_msgs::PointCloud trajectory_msg=create_cloudmsg(rosDataMsg.trajectory());
-
-				pubCloudL.publish(cloud_msg);
-				trajectory.publish(trajectory_msg);
-				pose.publish(poseStamped);
+				message::Base_msg baseMsg;
+				baseMsg.ParseFromString(t_queue_data);//第一次解析  判断数据类型
+				std::string topic;
+				if (baseMsg.base_info().msg_type() == message::ePointCloud_msg )
+				{
+					message::PointCloud_msg pointCloudMsg;
+					pointCloudMsg.ParseFromString(t_queue_data);
+					ros::Publisher* search_results=find_topic(pointCloudMsg.topic());
+					if( !search_results )//查找是否已存在此topic 若不存在才可new
+					{
+						search_results=new ros::Publisher(m_nodehandele.advertise<sensor_msgs::PointCloud>(pointCloudMsg.topic(),0));
+						m_ros_publisher_map.insert(std::pair<std::string,ros::Publisher*>(pointCloudMsg.topic(),search_results));
+						std::this_thread::sleep_for(std::chrono::seconds(1));
+					}
+					std::cout<<"绘制pointCloud..."<<std::endl;
+					sensor_msgs::PointCloud cloud_msg=create_cloudmsg(pointCloudMsg);
+					search_results->publish(cloud_msg);
+				}
+				else if(baseMsg.base_info().msg_type() == message::ePose2d_msg )
+				{
 
-				ros::spinOnce();
-				loop_rate.sleep();
+					message::Pose2d_msg pose2DMsg;
+					pose2DMsg.ParseFromString(t_queue_data);
+					ros::Publisher* search_results=find_topic(pose2DMsg.topic());
+					if( !search_results )//查找是否已存在此topic 若不存在才可new
+					{
+						search_results=new ros::Publisher(m_nodehandele.advertise<geometry_msgs::PoseStamped>(pose2DMsg.topic(),true));
+						m_ros_publisher_map.insert(std::pair<std::string,ros::Publisher*>(pose2DMsg.topic(),search_results));
+					}
+					std::cout<<"绘制pose2d..."<<std::endl;
+					geometry_msgs::PoseStamped poseStamped=create_posemsg(pose2DMsg);
+					search_results->publish(poseStamped);
+				}
 			}
 		}
 	}
-
+	return;
 }
-nnxx::socket& Processing_message::get_socket()
-{
-	return m_socket;
-}
-sensor_msgs::PointCloud Processing_message::create_cloudmsg(message::PointCloud cloud_pcl)
+sensor_msgs::PointCloud Processing_message::create_cloudmsg(message::PointCloud_msg cloud_pcl)
 {
 	sensor_msgs::PointCloud cloud;
 	cloud.header.stamp = ros::Time::now();
@@ -156,3 +183,35 @@ sensor_msgs::PointCloud Processing_message::create_cloudmsg(message::PointCloud
 	}
 	return cloud;
 }
+geometry_msgs::PoseStamped Processing_message::create_posemsg(message::Pose2d_msg pose2DMsg)
+{
+	geometry_msgs::PoseStamped poseStamped;
+	poseStamped.header.frame_id=pose2DMsg.frame_id();
+
+	poseStamped.pose.position.x=pose2DMsg.x();
+	poseStamped.pose.position.y=pose2DMsg.y();
+	poseStamped.pose.position.z=0;
+	poseStamped.pose.orientation.x=0*sin(pose2DMsg.theta()/2);
+	poseStamped.pose.orientation.y=0*sin(pose2DMsg.theta()/2);
+	poseStamped.pose.orientation.z=1*sin(pose2DMsg.theta()/2);
+	poseStamped.pose.orientation.w=cos(pose2DMsg.theta()/2);
+
+	return poseStamped;
+}
+ros::Publisher* Processing_message::find_topic(std::string topic)
+{
+	for(auto &v : m_ros_publisher_map)
+	{
+		if(topic==v.first)
+			return v.second;
+	}
+	return NULL;
+}
+nnxx::socket& Processing_message::get_socket()
+{
+	return m_socket;
+}
+ros::NodeHandle& Processing_message::get_nodehandele()
+{
+	return m_nodehandele;
+}

+ 41 - 19
Processing_Message/Processing_message.h

@@ -13,46 +13,68 @@
 #include <pcl/point_cloud.h>
 #include <math.h>
 #include <geometry_msgs/PoseStamped.h>
+#include <map>
 #include "../message/message_base.pb.h"
 #include "../message/ros_message.pb.h"
-#include "../thread_condition/thread_condition.h"
-class Processing_message
+#include "../tool/thread_condition.h"
+#include "../tool/thread_safe_queue.h"
+#include "../tool/singleton.h"
+class Processing_message:public Singleton<Processing_message>
 {
+	// 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
+	friend class Singleton<Processing_message>;
 public:
 	enum Connect_statu
 	{
 		CONNECT_ERROR		=0,	        //连接错误
 		CONNECT_NORMAL		=1,			//连接正常
 	};
-public:
+private:
+	// 父类的构造函数必须保护,子类的构造函数必须私有。
 	Processing_message();
-	Processing_message(const Processing_message& other)= default;
-	Processing_message& operator =(const Processing_message& other)= default;
+
+public:
+	//必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
+	Processing_message(const Processing_message& other)= delete;
+	Processing_message& operator =(const Processing_message& other)= delete;
 	~Processing_message();
 public://API functions
-	void Processing_message_init(std::string);
+	void Processing_message_init(std::string);//默认为连接
+	void Processing_message_connect(std::string);
+	void Processing_message_band(std::string);
 	void Processing_message_run();
 	void Processing_message_uninit();
-	void Processing_node(message::Ros_data_msg&);
-	sensor_msgs::PointCloud create_cloudmsg(message::PointCloud);
+	sensor_msgs::PointCloud create_cloudmsg(message::PointCloud_msg);//填充消息
+	geometry_msgs::PoseStamped create_posemsg(message::Pose2d_msg);//填充消息
 public://get or set member variable
-	Connect_statu get_connect_staty();
+	ros::Publisher* find_topic(std::string);
+	Connect_statu get_connect_statu();
 	nnxx::socket& get_socket();
-protected:
-	void receive_data_thread();
-	void send_data_thread();
+	ros::NodeHandle& get_nodehandele();
 
+protected:
+	void socket_receive_data_thread();
+	void ros_public_thread();
 protected://member variable
 	nnxx::socket 						m_socket { nnxx::SP, nnxx::BUS  };
-	std::mutex 							m_mutex;				//m_socket的锁
-	Connect_statu 						m_connect_statu;		//连接状态
+	std::mutex 							m_socket_mutex;					//m_socket的锁
+	Connect_statu 						m_connect_statu;				//连接状态
+
+	Thread_safe_queue<std::string>		m_socket_data_queue;			//存放数据的queue
+	std::mutex							m_data_mutex;					//数据锁
+
+	std::thread*						mp_socket_receive_data_thread; 	//接收消息线程
+	Thread_condition					m_socket_receive_condition;		//接受的条件变量
+
+	std::thread*						mp_ros_public_thread;    		//发布的线程指针
+	Thread_condition					m_ros_public_condition;			//发布的条件变量
+
+	std::thread*						mp_socket_send_data_thread;    	//发送的线程指针
+	Thread_condition					m_socket_send_data_condition;	//发送的条件变量
 
-	std::thread*						mp_receive_data_thread; //接收消息线程
-	Thread_condition					m_receive_condition;	//接受的条件变量
+	ros::NodeHandle 					m_nodehandele;					//用于创建新的发布器
+	std::map<std::string,ros::Publisher*>		m_ros_publisher_map;	//用于查询是否存在topic
 
-	std::thread*						mp_send_data_thread;    //发送的线程指针
-	Thread_condition					m_send_data_condition;	//发送的条件变量
-	message::Ros_data_msg				rosDataMsg;				//接受的消息存放体
 private:
 
 };

+ 87 - 21
message/measure_message.pb.cc

@@ -202,6 +202,7 @@ void InitDefaultsLocate_sift_response_msgImpl() {
 #endif  // GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS
   protobuf_message_5fbase_2eproto::InitDefaultsBase_info();
   protobuf_measure_5fmessage_2eproto::InitDefaultsCloud_type();
+  protobuf_message_5fbase_2eproto::InitDefaultsError_manager();
   {
     void* ptr = &::message::_Locate_sift_response_msg_default_instance_;
     new (ptr) ::message::Locate_sift_response_msg();
@@ -304,10 +305,12 @@ const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUT
   GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::message::Locate_sift_response_msg, command_key_),
   GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::message::Locate_sift_response_msg, terminal_id_),
   GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::message::Locate_sift_response_msg, cloud_type_),
+  GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::message::Locate_sift_response_msg, error_manager_),
   1,
   0,
-  2,
+  3,
   ~0u,
+  2,
 };
 static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = {
   { 0, 12, sizeof(::message::Measure_status_msg)},
@@ -316,7 +319,7 @@ static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROT
   { 45, 53, sizeof(::message::Cloud_coordinate)},
   { 56, 62, sizeof(::message::Cloud_type)},
   { 63, 72, sizeof(::message::Locate_sift_request_msg)},
-  { 76, 85, sizeof(::message::Locate_sift_response_msg)},
+  { 76, 86, sizeof(::message::Locate_sift_response_msg)},
 };
 
 static ::google::protobuf::Message const * const file_default_instances[] = {
@@ -375,24 +378,26 @@ void AddDescriptorsImpl() {
       "t_msg\022%\n\tbase_info\030\001 \002(\0132\022.message.Base_"
       "info\022\023\n\013command_key\030\002 \002(\t\022\023\n\013terminal_id"
       "\030\003 \002(\005\0224\n\021cloud_coordinates\030\004 \003(\0132\031.mess"
-      "age.Cloud_coordinate\"\224\001\n\030Locate_sift_res"
+      "age.Cloud_coordinate\"\303\001\n\030Locate_sift_res"
       "ponse_msg\022%\n\tbase_info\030\001 \002(\0132\022.message.B"
       "ase_info\022\023\n\013command_key\030\002 \002(\t\022\023\n\013termina"
       "l_id\030\003 \002(\005\022\'\n\ncloud_type\030\004 \003(\0132\023.message"
-      ".Cloud_type*\237\001\n\024Laser_manager_status\022\030\n\024"
-      "LASER_MANAGER_UNKNOW\020\000\022\027\n\023LASER_MANAGER_"
-      "READY\020\001\022\035\n\031LASER_MANAGER_ISSUED_TASK\020\002\022\034"
-      "\n\030LASER_MANAGER_WAIT_REPLY\020\003\022\027\n\023LASER_MA"
-      "NAGER_FAULT\020\004*U\n\013Laser_statu\022\024\n\020LASER_DI"
-      "SCONNECT\020\000\022\017\n\013LASER_READY\020\001\022\016\n\nLASER_BUS"
-      "Y\020\002\022\017\n\013LASER_FAULT\020\003*\261\001\n\025Locate_manager_"
-      "status\022\031\n\025LOCATE_MANAGER_UNKNOW\020\000\022\030\n\024LOC"
-      "ATE_MANAGER_READY\020\001\022\027\n\023LOCATE_MANAGER_SI"
-      "FT\020\002\022\026\n\022LOCATE_MANAGER_CAR\020\003\022\030\n\024LOCATE_M"
-      "ANAGER_WHEEL\020\004\022\030\n\024LOCATE_MANAGER_FAULT\020\005"
+      ".Cloud_type\022-\n\rerror_manager\030\005 \002(\0132\026.mes"
+      "sage.Error_manager*\237\001\n\024Laser_manager_sta"
+      "tus\022\030\n\024LASER_MANAGER_UNKNOW\020\000\022\027\n\023LASER_M"
+      "ANAGER_READY\020\001\022\035\n\031LASER_MANAGER_ISSUED_T"
+      "ASK\020\002\022\034\n\030LASER_MANAGER_WAIT_REPLY\020\003\022\027\n\023L"
+      "ASER_MANAGER_FAULT\020\004*U\n\013Laser_statu\022\024\n\020L"
+      "ASER_DISCONNECT\020\000\022\017\n\013LASER_READY\020\001\022\016\n\nLA"
+      "SER_BUSY\020\002\022\017\n\013LASER_FAULT\020\003*\261\001\n\025Locate_m"
+      "anager_status\022\031\n\025LOCATE_MANAGER_UNKNOW\020\000"
+      "\022\030\n\024LOCATE_MANAGER_READY\020\001\022\027\n\023LOCATE_MAN"
+      "AGER_SIFT\020\002\022\026\n\022LOCATE_MANAGER_CAR\020\003\022\030\n\024L"
+      "OCATE_MANAGER_WHEEL\020\004\022\030\n\024LOCATE_MANAGER_"
+      "FAULT\020\005"
   };
   ::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
-      descriptor, 1560);
+      descriptor, 1607);
   ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
     "measure_message.proto", &protobuf_RegisterTypes);
   ::protobuf_message_5fbase_2eproto::AddDescriptors();
@@ -2988,16 +2993,23 @@ void Locate_sift_request_msg::InternalSwap(Locate_sift_request_msg* other) {
 void Locate_sift_response_msg::InitAsDefaultInstance() {
   ::message::_Locate_sift_response_msg_default_instance_._instance.get_mutable()->base_info_ = const_cast< ::message::Base_info*>(
       ::message::Base_info::internal_default_instance());
+  ::message::_Locate_sift_response_msg_default_instance_._instance.get_mutable()->error_manager_ = const_cast< ::message::Error_manager*>(
+      ::message::Error_manager::internal_default_instance());
 }
 void Locate_sift_response_msg::clear_base_info() {
   if (base_info_ != NULL) base_info_->Clear();
   clear_has_base_info();
 }
+void Locate_sift_response_msg::clear_error_manager() {
+  if (error_manager_ != NULL) error_manager_->Clear();
+  clear_has_error_manager();
+}
 #if !defined(_MSC_VER) || _MSC_VER >= 1900
 const int Locate_sift_response_msg::kBaseInfoFieldNumber;
 const int Locate_sift_response_msg::kCommandKeyFieldNumber;
 const int Locate_sift_response_msg::kTerminalIdFieldNumber;
 const int Locate_sift_response_msg::kCloudTypeFieldNumber;
+const int Locate_sift_response_msg::kErrorManagerFieldNumber;
 #endif  // !defined(_MSC_VER) || _MSC_VER >= 1900
 
 Locate_sift_response_msg::Locate_sift_response_msg()
@@ -3024,6 +3036,11 @@ Locate_sift_response_msg::Locate_sift_response_msg(const Locate_sift_response_ms
   } else {
     base_info_ = NULL;
   }
+  if (from.has_error_manager()) {
+    error_manager_ = new ::message::Error_manager(*from.error_manager_);
+  } else {
+    error_manager_ = NULL;
+  }
   terminal_id_ = from.terminal_id_;
   // @@protoc_insertion_point(copy_constructor:message.Locate_sift_response_msg)
 }
@@ -3044,6 +3061,7 @@ Locate_sift_response_msg::~Locate_sift_response_msg() {
 void Locate_sift_response_msg::SharedDtor() {
   command_key_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited());
   if (this != internal_default_instance()) delete base_info_;
+  if (this != internal_default_instance()) delete error_manager_;
 }
 
 void Locate_sift_response_msg::SetCachedSize(int size) const {
@@ -3077,7 +3095,7 @@ void Locate_sift_response_msg::Clear() {
 
   cloud_type_.Clear();
   cached_has_bits = _has_bits_[0];
-  if (cached_has_bits & 3u) {
+  if (cached_has_bits & 7u) {
     if (cached_has_bits & 0x00000001u) {
       GOOGLE_DCHECK(!command_key_.IsDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()));
       (*command_key_.UnsafeRawStringPointer())->clear();
@@ -3086,6 +3104,10 @@ void Locate_sift_response_msg::Clear() {
       GOOGLE_DCHECK(base_info_ != NULL);
       base_info_->Clear();
     }
+    if (cached_has_bits & 0x00000004u) {
+      GOOGLE_DCHECK(error_manager_ != NULL);
+      error_manager_->Clear();
+    }
   }
   terminal_id_ = 0;
   _has_bits_.Clear();
@@ -3155,6 +3177,18 @@ bool Locate_sift_response_msg::MergePartialFromCodedStream(
         break;
       }
 
+      // required .message.Error_manager error_manager = 5;
+      case 5: {
+        if (static_cast< ::google::protobuf::uint8>(tag) ==
+            static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) {
+          DO_(::google::protobuf::internal::WireFormatLite::ReadMessage(
+               input, mutable_error_manager()));
+        } else {
+          goto handle_unusual;
+        }
+        break;
+      }
+
       default: {
       handle_unusual:
         if (tag == 0) {
@@ -3199,7 +3233,7 @@ void Locate_sift_response_msg::SerializeWithCachedSizes(
   }
 
   // required int32 terminal_id = 3;
-  if (cached_has_bits & 0x00000004u) {
+  if (cached_has_bits & 0x00000008u) {
     ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->terminal_id(), output);
   }
 
@@ -3210,6 +3244,12 @@ void Locate_sift_response_msg::SerializeWithCachedSizes(
       4, this->cloud_type(static_cast<int>(i)), output);
   }
 
+  // required .message.Error_manager error_manager = 5;
+  if (cached_has_bits & 0x00000004u) {
+    ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
+      5, *this->error_manager_, output);
+  }
+
   if (_internal_metadata_.have_unknown_fields()) {
     ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
         _internal_metadata_.unknown_fields(), output);
@@ -3244,7 +3284,7 @@ void Locate_sift_response_msg::SerializeWithCachedSizes(
   }
 
   // required int32 terminal_id = 3;
-  if (cached_has_bits & 0x00000004u) {
+  if (cached_has_bits & 0x00000008u) {
     target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->terminal_id(), target);
   }
 
@@ -3256,6 +3296,13 @@ void Locate_sift_response_msg::SerializeWithCachedSizes(
         4, this->cloud_type(static_cast<int>(i)), deterministic, target);
   }
 
+  // required .message.Error_manager error_manager = 5;
+  if (cached_has_bits & 0x00000004u) {
+    target = ::google::protobuf::internal::WireFormatLite::
+      InternalWriteMessageToArray(
+        5, *this->error_manager_, deterministic, target);
+  }
+
   if (_internal_metadata_.have_unknown_fields()) {
     target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
         _internal_metadata_.unknown_fields(), target);
@@ -3282,6 +3329,13 @@ size_t Locate_sift_response_msg::RequiredFieldsByteSizeFallback() const {
         *this->base_info_);
   }
 
+  if (has_error_manager()) {
+    // required .message.Error_manager error_manager = 5;
+    total_size += 1 +
+      ::google::protobuf::internal::WireFormatLite::MessageSize(
+        *this->error_manager_);
+  }
+
   if (has_terminal_id()) {
     // required int32 terminal_id = 3;
     total_size += 1 +
@@ -3300,7 +3354,7 @@ size_t Locate_sift_response_msg::ByteSizeLong() const {
       ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
         _internal_metadata_.unknown_fields());
   }
-  if (((_has_bits_[0] & 0x00000007) ^ 0x00000007) == 0) {  // All required fields are present.
+  if (((_has_bits_[0] & 0x0000000f) ^ 0x0000000f) == 0) {  // All required fields are present.
     // required string command_key = 2;
     total_size += 1 +
       ::google::protobuf::internal::WireFormatLite::StringSize(
@@ -3311,6 +3365,11 @@ size_t Locate_sift_response_msg::ByteSizeLong() const {
       ::google::protobuf::internal::WireFormatLite::MessageSize(
         *this->base_info_);
 
+    // required .message.Error_manager error_manager = 5;
+    total_size += 1 +
+      ::google::protobuf::internal::WireFormatLite::MessageSize(
+        *this->error_manager_);
+
     // required int32 terminal_id = 3;
     total_size += 1 +
       ::google::protobuf::internal::WireFormatLite::Int32Size(
@@ -3361,7 +3420,7 @@ void Locate_sift_response_msg::MergeFrom(const Locate_sift_response_msg& from) {
 
   cloud_type_.MergeFrom(from.cloud_type_);
   cached_has_bits = from._has_bits_[0];
-  if (cached_has_bits & 7u) {
+  if (cached_has_bits & 15u) {
     if (cached_has_bits & 0x00000001u) {
       set_has_command_key();
       command_key_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.command_key_);
@@ -3370,6 +3429,9 @@ void Locate_sift_response_msg::MergeFrom(const Locate_sift_response_msg& from) {
       mutable_base_info()->::message::Base_info::MergeFrom(from.base_info());
     }
     if (cached_has_bits & 0x00000004u) {
+      mutable_error_manager()->::message::Error_manager::MergeFrom(from.error_manager());
+    }
+    if (cached_has_bits & 0x00000008u) {
       terminal_id_ = from.terminal_id_;
     }
     _has_bits_[0] |= cached_has_bits;
@@ -3391,11 +3453,14 @@ void Locate_sift_response_msg::CopyFrom(const Locate_sift_response_msg& from) {
 }
 
 bool Locate_sift_response_msg::IsInitialized() const {
-  if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false;
+  if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false;
   if (!::google::protobuf::internal::AllAreInitialized(this->cloud_type())) return false;
   if (has_base_info()) {
     if (!this->base_info_->IsInitialized()) return false;
   }
+  if (has_error_manager()) {
+    if (!this->error_manager_->IsInitialized()) return false;
+  }
   return true;
 }
 
@@ -3408,6 +3473,7 @@ void Locate_sift_response_msg::InternalSwap(Locate_sift_response_msg* other) {
   cloud_type_.InternalSwap(&other->cloud_type_);
   command_key_.Swap(&other->command_key_);
   swap(base_info_, other->base_info_);
+  swap(error_manager_, other->error_manager_);
   swap(terminal_id_, other->terminal_id_);
   swap(_has_bits_[0], other->_has_bits_[0]);
   _internal_metadata_.Swap(&other->_internal_metadata_);

+ 65 - 3
message/measure_message.pb.h

@@ -1175,6 +1175,15 @@ class Locate_sift_response_msg : public ::google::protobuf::Message /* @@protoc_
   ::message::Base_info* mutable_base_info();
   void set_allocated_base_info(::message::Base_info* base_info);
 
+  // required .message.Error_manager error_manager = 5;
+  bool has_error_manager() const;
+  void clear_error_manager();
+  static const int kErrorManagerFieldNumber = 5;
+  const ::message::Error_manager& error_manager() const;
+  ::message::Error_manager* release_error_manager();
+  ::message::Error_manager* mutable_error_manager();
+  void set_allocated_error_manager(::message::Error_manager* error_manager);
+
   // required int32 terminal_id = 3;
   bool has_terminal_id() const;
   void clear_terminal_id();
@@ -1190,6 +1199,8 @@ class Locate_sift_response_msg : public ::google::protobuf::Message /* @@protoc_
   void clear_has_command_key();
   void set_has_terminal_id();
   void clear_has_terminal_id();
+  void set_has_error_manager();
+  void clear_has_error_manager();
 
   // helper for ByteSizeLong()
   size_t RequiredFieldsByteSizeFallback() const;
@@ -1200,6 +1211,7 @@ class Locate_sift_response_msg : public ::google::protobuf::Message /* @@protoc_
   ::google::protobuf::RepeatedPtrField< ::message::Cloud_type > cloud_type_;
   ::google::protobuf::internal::ArenaStringPtr command_key_;
   ::message::Base_info* base_info_;
+  ::message::Error_manager* error_manager_;
   ::google::protobuf::int32 terminal_id_;
   friend struct ::protobuf_measure_5fmessage_2eproto::TableStruct;
   friend void ::protobuf_measure_5fmessage_2eproto::InitDefaultsLocate_sift_response_msgImpl();
@@ -2247,13 +2259,13 @@ inline void Locate_sift_response_msg::set_allocated_command_key(::std::string* c
 
 // required int32 terminal_id = 3;
 inline bool Locate_sift_response_msg::has_terminal_id() const {
-  return (_has_bits_[0] & 0x00000004u) != 0;
+  return (_has_bits_[0] & 0x00000008u) != 0;
 }
 inline void Locate_sift_response_msg::set_has_terminal_id() {
-  _has_bits_[0] |= 0x00000004u;
+  _has_bits_[0] |= 0x00000008u;
 }
 inline void Locate_sift_response_msg::clear_has_terminal_id() {
-  _has_bits_[0] &= ~0x00000004u;
+  _has_bits_[0] &= ~0x00000008u;
 }
 inline void Locate_sift_response_msg::clear_terminal_id() {
   terminal_id_ = 0;
@@ -2299,6 +2311,56 @@ Locate_sift_response_msg::cloud_type() const {
   return cloud_type_;
 }
 
+// required .message.Error_manager error_manager = 5;
+inline bool Locate_sift_response_msg::has_error_manager() const {
+  return (_has_bits_[0] & 0x00000004u) != 0;
+}
+inline void Locate_sift_response_msg::set_has_error_manager() {
+  _has_bits_[0] |= 0x00000004u;
+}
+inline void Locate_sift_response_msg::clear_has_error_manager() {
+  _has_bits_[0] &= ~0x00000004u;
+}
+inline const ::message::Error_manager& Locate_sift_response_msg::error_manager() const {
+  const ::message::Error_manager* p = error_manager_;
+  // @@protoc_insertion_point(field_get:message.Locate_sift_response_msg.error_manager)
+  return p != NULL ? *p : *reinterpret_cast<const ::message::Error_manager*>(
+      &::message::_Error_manager_default_instance_);
+}
+inline ::message::Error_manager* Locate_sift_response_msg::release_error_manager() {
+  // @@protoc_insertion_point(field_release:message.Locate_sift_response_msg.error_manager)
+  clear_has_error_manager();
+  ::message::Error_manager* temp = error_manager_;
+  error_manager_ = NULL;
+  return temp;
+}
+inline ::message::Error_manager* Locate_sift_response_msg::mutable_error_manager() {
+  set_has_error_manager();
+  if (error_manager_ == NULL) {
+    error_manager_ = new ::message::Error_manager;
+  }
+  // @@protoc_insertion_point(field_mutable:message.Locate_sift_response_msg.error_manager)
+  return error_manager_;
+}
+inline void Locate_sift_response_msg::set_allocated_error_manager(::message::Error_manager* error_manager) {
+  ::google::protobuf::Arena* message_arena = GetArenaNoVirtual();
+  if (message_arena == NULL) {
+    delete reinterpret_cast< ::google::protobuf::MessageLite*>(error_manager_);
+  }
+  if (error_manager) {
+    ::google::protobuf::Arena* submessage_arena = NULL;
+    if (message_arena != submessage_arena) {
+      error_manager = ::google::protobuf::internal::GetOwnedMessage(
+          message_arena, error_manager, submessage_arena);
+    }
+    set_has_error_manager();
+  } else {
+    clear_has_error_manager();
+  }
+  error_manager_ = error_manager;
+  // @@protoc_insertion_point(field_set_allocated:message.Locate_sift_response_msg.error_manager)
+}
+
 #ifdef __GNUC__
   #pragma GCC diagnostic pop
 #endif  // __GNUC__

+ 26 - 25
message/message_base.pb.cc

@@ -342,7 +342,7 @@ void AddDescriptorsImpl() {
       "\016\n\006height\030\007 \001(\002\0223\n\020parkspace_status\030\010 \001("
       "\0162\031.message.Parkspace_status\022#\n\010car_info"
       "\030\t \001(\0132\021.message.Car_info\022\022\n\nentry_time\030"
-      "\n \001(\t\022\022\n\nleave_time\030\013 \001(\t*\317\007\n\014Message_ty"
+      "\n \001(\t\022\022\n\nleave_time\030\013 \001(\t*\343\007\n\014Message_ty"
       "pe\022\r\n\teBase_msg\020\000\022\020\n\014eCommand_msg\020\001\022\026\n\022e"
       "Locate_status_msg\020\021\022\027\n\023eLocate_request_m"
       "sg\020\022\022\030\n\024eLocate_response_msg\020\023\022\030\n\024eDispa"
@@ -366,32 +366,32 @@ void AddDescriptorsImpl() {
       "ocess_statu_msg\020\221\001\022\"\n\035eCentral_controlle"
       "r_statu_msg\020\240\001\022#\n\036eEntrance_manual_opera"
       "tion_msg\020\260\001\022\"\n\035eProcess_manual_operation"
-      "_msg\020\261\001\022\022\n\reRos_data_msg\020\360\001\022\016\n\teGoal_msg"
-      "\020\361\001*q\n\014Communicator\022\n\n\006eEmpty\020\000\022\t\n\005eMain"
-      "\020\001\022\016\n\teTerminor\020\200\002\022\017\n\neParkspace\020\200\004\022\016\n\te"
-      "Measurer\020\200\006\022\016\n\teDispatch\020\200\010\022\t\n\004eAGV\020\200\036**"
-      "\n\014Process_type\022\014\n\010eStoring\020\001\022\014\n\010ePicking"
-      "\020\002*e\n\013Error_level\022\n\n\006NORMAL\020\000\022\024\n\020NEGLIGI"
-      "BLE_ERROR\020\001\022\017\n\013MINOR_ERROR\020\002\022\017\n\013MAJOR_ER"
-      "ROR\020\003\022\022\n\016CRITICAL_ERROR\020\004*q\n\020Parkspace_s"
-      "tatus\022\024\n\020eParkspace_empty\020\000\022\027\n\023eParkspac"
-      "e_occupied\020\001\022\030\n\024eParkspace_reserverd\020\002\022\024"
-      "\n\020eParkspace_error\020\003*(\n\tDirection\022\014\n\010eFo"
-      "rward\020\001\022\r\n\teBackward\020\002*\335\002\n\tStep_type\022\017\n\013"
-      "eAlloc_step\020\000\022\021\n\reMeasure_step\020\001\022\021\n\reCom"
-      "pare_step\020\002\022\022\n\016eDispatch_step\020\003\022\021\n\reConf"
-      "irm_step\020\004\022\020\n\014eSearch_step\020\005\022\016\n\neWait_st"
-      "ep\020\006\022\021\n\reRelease_step\020\007\022\r\n\teComplete\020\010\022\025"
-      "\n\021eBackConfirm_step\020\t\022\026\n\022eBack_compare_s"
-      "tep\020\n\022\025\n\021eBackMeasure_step\020\013\022\023\n\017eBackAll"
-      "oc_step\020\014\022\022\n\016eBackWait_step\020\r\022\026\n\022eBackDi"
-      "spatch_step\020\016\022\024\n\020eBackSearch_step\020\017\022\021\n\re"
-      "BackComplete\020\020*C\n\nStep_statu\022\014\n\010eWaiting"
-      "\020\000\022\014\n\010eWorking\020\001\022\n\n\006eError\020\002\022\r\n\teFinishe"
-      "d\020\003"
+      "_msg\020\261\001\022\016\n\teGoal_msg\020\360\001\022\024\n\017ePointCloud_m"
+      "sg\020\361\001\022\020\n\013ePose2d_msg\020\362\001*q\n\014Communicator\022"
+      "\n\n\006eEmpty\020\000\022\t\n\005eMain\020\001\022\016\n\teTerminor\020\200\002\022\017"
+      "\n\neParkspace\020\200\004\022\016\n\teMeasurer\020\200\006\022\016\n\teDisp"
+      "atch\020\200\010\022\t\n\004eAGV\020\200\036**\n\014Process_type\022\014\n\010eS"
+      "toring\020\001\022\014\n\010ePicking\020\002*e\n\013Error_level\022\n\n"
+      "\006NORMAL\020\000\022\024\n\020NEGLIGIBLE_ERROR\020\001\022\017\n\013MINOR"
+      "_ERROR\020\002\022\017\n\013MAJOR_ERROR\020\003\022\022\n\016CRITICAL_ER"
+      "ROR\020\004*q\n\020Parkspace_status\022\024\n\020eParkspace_"
+      "empty\020\000\022\027\n\023eParkspace_occupied\020\001\022\030\n\024ePar"
+      "kspace_reserverd\020\002\022\024\n\020eParkspace_error\020\003"
+      "*(\n\tDirection\022\014\n\010eForward\020\001\022\r\n\teBackward"
+      "\020\002*\335\002\n\tStep_type\022\017\n\013eAlloc_step\020\000\022\021\n\reMe"
+      "asure_step\020\001\022\021\n\reCompare_step\020\002\022\022\n\016eDisp"
+      "atch_step\020\003\022\021\n\reConfirm_step\020\004\022\020\n\014eSearc"
+      "h_step\020\005\022\016\n\neWait_step\020\006\022\021\n\reRelease_ste"
+      "p\020\007\022\r\n\teComplete\020\010\022\025\n\021eBackConfirm_step\020"
+      "\t\022\026\n\022eBack_compare_step\020\n\022\025\n\021eBackMeasur"
+      "e_step\020\013\022\023\n\017eBackAlloc_step\020\014\022\022\n\016eBackWa"
+      "it_step\020\r\022\026\n\022eBackDispatch_step\020\016\022\024\n\020eBa"
+      "ckSearch_step\020\017\022\021\n\reBackComplete\020\020*C\n\nSt"
+      "ep_statu\022\014\n\010eWaiting\020\000\022\014\n\010eWorking\020\001\022\n\n\006"
+      "eError\020\002\022\r\n\teFinished\020\003"
   };
   ::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
-      descriptor, 2763);
+      descriptor, 2783);
   ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
     "message_base.proto", &protobuf_RegisterTypes);
 }
@@ -444,6 +444,7 @@ bool Message_type_IsValid(int value) {
     case 177:
     case 240:
     case 241:
+    case 242:
       return true;
     default:
       return false;

+ 4 - 3
message/message_base.pb.h

@@ -115,12 +115,13 @@ enum Message_type {
   eCentral_controller_statu_msg = 160,
   eEntrance_manual_operation_msg = 176,
   eProcess_manual_operation_msg = 177,
-  eRos_data_msg = 240,
-  eGoal_msg = 241
+  eGoal_msg = 240,
+  ePointCloud_msg = 241,
+  ePose2d_msg = 242
 };
 bool Message_type_IsValid(int value);
 const Message_type Message_type_MIN = eBase_msg;
-const Message_type Message_type_MAX = eGoal_msg;
+const Message_type Message_type_MAX = ePose2d_msg;
 const int Message_type_ARRAYSIZE = Message_type_MAX + 1;
 
 const ::google::protobuf::EnumDescriptor* Message_type_descriptor();

+ 3 - 6
message/message_base.proto

@@ -47,12 +47,9 @@ enum Message_type
     eEntrance_manual_operation_msg=0xb0;            //针对出入口状态操作的手动消息
     eProcess_manual_operation_msg=0xb1;             //针对流程的手动消息
 
-
-
-    eRos_data_msg=0xf0;
-    eGoal_msg=0xf1;
-
-
+    eGoal_msg=0xf0;
+    ePointCloud_msg=0xf1;
+    ePose2d_msg=0xf2;
 }
 
 //通讯单元

Filskillnaden har hållts tillbaka eftersom den är för stor
+ 500 - 780
message/ros_message.pb.cc


Filskillnaden har hållts tillbaka eftersom den är för stor
+ 414 - 626
message/ros_message.pb.h


+ 15 - 18
message/ros_message.proto

@@ -9,32 +9,29 @@ message PointXYZ
     optional float z=3 [default=0];
 }
 
-message PointCloud
+message PointCloud_msg
 {
-    required string                     frame_id=1;
-    required string                     topic=2;
-    repeated PointXYZ                   points=3;
-}
-
-message Pose2d
-{
-    required string                     frame_id=1;
-    required string                     topic=2;
-    required float                      x=3 [default=0];
-    required float                      y=4 [default=0];
-    required float                      theta=5 [default=0];
+    required Base_info                  base_info=1;
+    required string                     frame_id=2;
+    required string                     topic=3;
+    repeated PointXYZ                   points=4;
 }
 
-message Ros_data_msg
+message Pose2d_msg
 {
     required Base_info                  base_info=1;
-    optional PointCloud                 cloud_msg=2;
-    optional PointCloud                 trajectory=3;
-    optional Pose2d                     target_pose=4;
+    required string                     frame_id=2;
+    required string                     topic=3;
+    required float                      x=4 [default=0];
+    required float                      y=5 [default=0];
+    required float                      theta=6 [default=0];
 }
 
+
 message Goal_msg
 {
     required Base_info                  base_info=1;
-    required Pose2d                     target=2;
+    required float                      x=2 [default=0];
+    required float                      y=3 [default=0];
+    required float                      theta=4 [default=0];
 }

+ 36 - 12
src/main.cpp

@@ -1,20 +1,44 @@
 //#include "Processing_message.h"
 #include "../Processing_Message/Processing_message.h"
 
+void  goalCallback(const geometry_msgs::PoseStamped::ConstPtr& msg)
+{
+	//填充数据
+
+	double x=msg->pose.position.x;
+	double y=msg->pose.position.y;
+	double z=msg->pose.position.z;
+	double qx=msg->pose.orientation.x;
+	double qy=msg->pose.orientation.y;
+	double qz=msg->pose.orientation.z;
+	double qw=msg->pose.orientation.w;
+
+	std::cout<<"  post goal "<<qx<<","<<qy<<","<<qz<<","<<qw<<std::endl;
+	double theta=acos(qw)*2.0;
+	theta=(qz>0)?theta:-theta;
+
+	message::Goal_msg goal;
+	message::Base_info base_info;
+	base_info.set_sender(message::eEmpty);
+	base_info.set_receiver(message::eAGV);
+	base_info.set_msg_type(message::eGoal_msg);
+	goal.mutable_base_info()->CopyFrom(base_info);
+
+	goal.set_x(x);
+	goal.set_y(y);
+	goal.set_theta(theta);
+
+	std::cout<<Processing_message::get_instance_references().get_socket().send(goal.SerializeAsString())<<std::endl;//发送数据
+}
+
 int main(int argc,char** argv)
 {
 //"tcp://192.168.2.183:30001"
 	ros::init(argc, argv, "test_node");
-	Processing_message a;
-	a.Processing_message_init("tcp://192.168.2.115:5000");
-	while (1)
-	{
-		int i;
-		std::cin>>i;
-		if ( i==888 )
-		{
-		    break;
-		}
-	}
-	a.Processing_message_uninit();
+	Processing_message& t_processing_message=Processing_message::get_instance_references();//获取单例
+	ros::Subscriber subscriber=t_processing_message.get_nodehandele().subscribe("/move_base_simple/goal",1,goalCallback);//订阅话题
+
+	t_processing_message.Processing_message_init("tcp://192.168.2.182:30001");//默认为连接
+	ros::spin();
+	t_processing_message.Processing_message_uninit();
 }

+ 0 - 175
thread_condition/thread_condition.cpp

@@ -1,175 +0,0 @@
-
-
-/* Thread_condition 是多线程的条件控制类,主要是控制线程的启停和退出
- * 线程创建后,一般是循环运行,
- * 为了防止线程暂满整个cpu,那么需要线程在不工作的是否进入等待状态。
- * Thread_condition 就可以控制线程的运行状态。
- *
-	std::atomic<bool> m_pass_ever		//线程能否直接通过等待,对后面的线程也生效。
-	std::atomic<bool> m_pass_once		//线程能否直接通过等待,一次(通过一次之后,wait里面自动改为false)
- * 外部调用notify系列的函数,唤醒等待的线程,让线程执行功能函数。
- * 如果需要线程循环多次执行功能函数,那么就使用 notify_all(true),后面的线程可以直接通过等待了。
- * 再使用 notify_all(false) ,即可停止线程,让其继续等待。
- * 如果只想要线程执行一次,那就使用 notify_all(false, true)
- * 注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
- *
- * m_kill_flag //是否杀死线程,让线程强制退出,
- * 外部调用 kill_all() 函数,可以直接通知线程自动退出。
-	//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
-	//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
-	// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
-	//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
-
- 注:notify唤醒线程之后,wait里面的判断函数会重新判断。
- */
-
-#include "thread_condition.h"
-
-Thread_condition::Thread_condition()
-{
-	m_kill_flag = false;
-	m_pass_ever = false;
-	m_pass_once = false;
-	m_working_flag = false;
-}
-Thread_condition::~Thread_condition()
-{
-	kill_all();
-}
-
-//无限等待,由 is_pass_wait 决定是否阻塞。
-//返回m_pass,
-bool Thread_condition::wait()
-{
-	std::unique_lock<std::mutex> loc(m_mutex);
-	m_condition_variable.wait(loc,std::bind(is_pass_wait,this));
-	bool t_pass = is_pass_wait(this);
-	m_pass_once = false;
-
-	//只要前面通过了, 那就进入工作状态
-	m_working_flag = true;
-
-	return t_pass;
-}
-//等待一定的时间(默认时间单位:毫秒ms),由 is_pass_wait 决定是否阻塞。
-//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
-//注意了:线程阻塞期间,是不会return的。
-bool Thread_condition::wait_for_millisecond(unsigned int millisecond)
-{
-	std::unique_lock<std::mutex> loc(m_mutex);
-	m_condition_variable.wait_for(loc, std::chrono::milliseconds(millisecond), std::bind(is_pass_wait, this));
-	bool t_pass = is_pass_wait(this);
-	m_pass_once = false;
-
-	//只要前面通过了, 那就进入工作状态 , 超时通过也算通过
-	m_working_flag = true;
-
-	return t_pass;
-}
-
-
-//唤醒已经阻塞的线程,唤醒一个线程
-//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
-void Thread_condition::notify_one(bool pass_ever, bool pass_once)
-{
-	std::unique_lock<std::mutex> loc(m_mutex);
-	m_pass_ever = pass_ever;
-	m_pass_once = pass_once;
-	m_condition_variable.notify_one();
-}
-//唤醒已经阻塞的线程,唤醒全部线程
-//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
-void Thread_condition::notify_all(bool pass_ever, bool pass_once)
-{
-	std::unique_lock<std::mutex> loc(m_mutex);
-	m_pass_ever = pass_ever;
-	m_pass_once = pass_once;
-	m_condition_variable.notify_all();
-}
-//注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
-
-
-//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
-//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
-// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
-//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
-void Thread_condition::kill_all()
-{
-	std::unique_lock<std::mutex> loc(m_mutex);
-	m_kill_flag = true;
-	m_condition_variable.notify_all();
-}
-
-//判断是否存活,只有活着才能继续支持子线程从功能函数,否则需要强制退出函数并结束子线程
-bool Thread_condition::is_alive()
-{
-	return !m_kill_flag;
-}
-
-
-//判断是否等待, 外部线程通过这个函数来查询this线程的工作状态,
-bool Thread_condition::is_waiting()
-{
-	return !m_working_flag;
-}
-//判断是否工作, 外部线程通过这个函数来查询this线程的工作状态,
-bool Thread_condition::is_working()
-{
-	return m_working_flag;
-}
-
-
-bool Thread_condition::get_kill_flag()
-{
-	return m_kill_flag;
-}
-bool Thread_condition::get_pass_ever()
-{
-	return m_pass_ever;
-}
-bool Thread_condition::get_pass_once()
-{
-	return m_pass_once;
-}
-void Thread_condition::set_kill_flag(bool kill)
-{
-	m_kill_flag = kill;
-}
-void Thread_condition::set_pass_ever(bool pass_ever)
-{
-	m_pass_ever = pass_ever;
-}
-void Thread_condition::set_pass_once(bool pass_once)
-{
-	m_pass_once = pass_once;
-}
-void Thread_condition::reset(bool kill, bool pass_ever, bool pass_once)
-{
-	m_kill_flag = kill;
-	m_pass_ever = pass_ever;
-	m_pass_once = pass_once;
-}
-
-
-//判断线程是否可以通过等待,wait系列函数的判断标志
-//注:m_kill或者m_pass为真时,return true
-bool Thread_condition::is_pass_wait(Thread_condition * other)
-{
-	if ( other == NULL )
-	{
-		throw (other);
-		return false;
-	}
-
-	bool result = (other->m_kill_flag || other->m_pass_ever || other->m_pass_once);
-
-	//如果不能通过等待, 那么线程状态改为等待中,
-	if ( !result )
-	{
-		other->m_working_flag = false;
-	}
-
-
-	return result;
-}
-

+ 0 - 182
thread_condition/thread_condition.h

@@ -1,182 +0,0 @@
-
-
-/* Thread_condition 是多线程的条件控制类,主要是控制线程的启停和退出
- * 线程创建后,一般是循环运行,
- * 为了防止线程暂满整个cpu,那么需要线程在不工作的是否进入等待状态。
- * Thread_condition 就可以控制线程的运行状态。
- *
-	std::atomic<bool> m_pass_ever		//线程能否直接通过等待,对后面的线程也生效。
-	std::atomic<bool> m_pass_once		//线程能否直接通过等待,一次(通过一次之后,wait里面自动改为false)
- * 外部调用notify系列的函数,唤醒等待的线程,让线程执行功能函数。
- * 如果需要线程循环多次执行功能函数,那么就使用 notify_all(true),后面的线程可以直接通过等待了。
- * 再使用 notify_all(false) ,即可停止线程,让其继续等待。
- * 如果只想要线程执行一次,那就使用 notify_all(false, true)
- * 注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
- *
- * m_kill_flag //是否杀死线程,让线程强制退出,
- * 外部调用 kill_all() 函数,可以直接通知线程自动退出。
-	//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
-	//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
-	// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
-	//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
-
- 注:notify唤醒线程之后,wait里面的判断函数会重新判断。
-
-
- 最下面有使用样例,
-
- */
-
-#ifndef LIDARMEASURE_THREAD_CONDITION_H
-#define LIDARMEASURE_THREAD_CONDITION_H
-
-#include <ratio>
-#include <chrono>
-#include <thread>
-#include <atomic>
-#include <mutex>
-#include <condition_variable>
-#include <iostream>
-#include<functional>
-
-class Thread_condition
-{
-public:
-	Thread_condition();
-	Thread_condition(const Thread_condition& other) = delete;
-	~Thread_condition();
-
-	//无限等待,由 is_pass_wait 决定是否阻塞。
-	//返回m_pass,
-	bool wait();
-	//等待一定的时间(默认时间单位:毫秒ms),由 is_pass_wait 决定是否阻塞。
-	//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
-	//注意了:线程阻塞期间,是不会return的。
-	bool wait_for_millisecond(unsigned int millisecond);
-
-	//等待一定的时间(时间单位可调),由 is_pass_wait 决定是否阻塞。
-	//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
-	//注意了:线程阻塞期间,是不会return的。
-	template<typename _Rep, typename _Period>
-	bool wait_for_ex(const std::chrono::duration<_Rep, _Period>& time_duration);
-
-	//唤醒已经阻塞的线程,唤醒一个线程
-	//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
-	void notify_one(bool pass_ever, bool pass_once = false);
-	//唤醒已经阻塞的线程,唤醒全部线程
-	//pass_ever 或者 pass_once 为真时,才能唤醒线程。都为假时,线程进入等待。
-	void notify_all(bool pass_ever, bool pass_once = false);
-	//注:notify_all(false, true)和notify_one(false, true) 一样,只能让其中一个线程执行一次
-
-	//杀死所有的线程,强制退出线程函数,只是操作受当前Thread_condition影响的所有线程
-	//唤醒所有线程,使其通过等待,但是不能运行功能函数,必须直接return
-	// 注:只是修改m_kill为true,需要线程函数实时检测kill的状态,来return线程。
-	//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
-	void kill_all();
-
-	//判断是否存活,只有活着才能继续支持子线程从功能函数,否则需要强制退出函数并结束子线程
-	bool is_alive();
-
-	//判断是否等待, 外部线程通过这个函数来查询this线程的工作状态,
-	bool is_waiting();
-	//判断是否工作, 外部线程通过这个函数来查询this线程的工作状态,
-	bool is_working();
-
-public:
-
-	bool get_kill_flag();
-	bool get_pass_ever();
-	bool get_pass_once();
-	void set_kill_flag(bool kill);
-	void set_pass_ever(bool pass_ever);
-	void set_pass_once(bool pass_once);
-	void reset(bool kill = false, bool pass_ever = false, bool pass_once = false);
-
-protected:
-	//判断线程是否可以通过等待,wait系列函数的判断标志
-	//注:m_kill或者m_pass为真时,return true
-	static bool is_pass_wait(Thread_condition * other);
-
-	std::atomic<bool> 		m_kill_flag;			//是否杀死线程,让线程强制退出,
-	std::atomic<bool> 		m_pass_ever;			//线程能否直接通过等待,对后面的线程也生效。
-	std::atomic<bool> 		m_pass_once;			//线程能否直接通过等待,一次(通过一次之后,wait里面自动改为false)
-
-	std::atomic<bool> 		m_working_flag;			//线程是否进入工作的标志位, false:表示线程进行进入wait等待, true:表示线程仍然在运行中,
-
-	std::mutex 				m_mutex;				//线程的锁
-	std::condition_variable m_condition_variable;	//线程的条件变量
-
-private:
-
-};
-
-//等待一定的时间(时间单位可调),由 is_pass_wait 决定是否阻塞。
-//return:is_pass_wait的结果,	true:线程直接通过等待,false:线程超时了,然后通过等待。
-//注意了:线程阻塞期间,是不会return的。
-template<typename _Rep, typename _Period>
-bool Thread_condition::wait_for_ex(const std::chrono::duration<_Rep, _Period>& time_duration)
-{
-	std::unique_lock<std::mutex> loc(m_mutex);
-	m_condition_variable.wait_for(loc, std::chrono::duration<_Rep, _Period>(time_duration), std::bind(is_pass_wait, this));
-	bool t_pass = is_pass_wait(this);
-	m_pass_once = false;
-	return t_pass;
-}
-
-#endif //LIDARMEASURE_THREAD_CONDITION_H
-
-/*
-
-//使用样例:
-std::thread*						mp_thread_receive;    		//接受缓存的线程指针
-Thread_condition					m_condition_receive;		//接受缓存的条件变量
-
-void thread_receive()
-{
-	while (m_condition_receive.is_alive())
-	{
-		m_condition_receive.wait();
-		if ( m_condition_receive.is_alive() )
-		{
-			//do everything
-
-		}
-	}
-
-	return;
-}
-
-//main函数的主线程
-int main(int argc,char* argv[])
-{
- 	//线程创建之后, 默认等待
-	m_condition_receive.reset(false, false, false);
-	mp_thread_receive = new std::thread(& thread_receive );
-
-
-	//唤醒所有线程, 然后线程可以一直通过wait等待, 线程进入无限制的循环工作.
-	m_condition_receive.notify_all(true);
-
-	//暂停所有线程, 然后线程还是继续工作, 直到下一次循环, 进入wait等待
-	m_condition_receive.notify_all(false);
-
-	//如果线程单次循环运行时间较长, 需要等待线程完全停止, 才能读写公共的内存,
-	if ( m_condition_receive.is_waiting() )
-	{
-	    // 读写公共的内存,
-	}
-
-	//唤醒一个线程, 然后线程循环一次, 然后下次循环进入等待
-	m_condition_receive.notify_all(false, true);
-
-
-	//杀死线程,
-	m_condition_receive.kill_all();
-
-	//在线程join结束之后, 就可以可以回收线程内存资源
-	mp_thread_receive->join();
-	delete mp_thread_receive;
-	mp_thread_receive = NULL;
-}
-
-*/