1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283 |
- //
- // Created by wk on 2020/9/17.
- //
- #ifndef SRC_PROCESSING_MESSAGE_H
- #define SRC_PROCESSING_MESSAGE_H
- #include <nnxx/socket>
- #include <nnxx/message>
- #include <thread>
- #include <ros/ros.h>
- #include <sensor_msgs/PointCloud.h>
- #include <pcl/point_types.h>
- #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 "../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, //连接正常
- };
- private:
- // 父类的构造函数必须保护,子类的构造函数必须私有。
- Processing_message();
- 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_connect(std::string);
- void Processing_message_band(std::string);
- void Processing_message_run();
- void Processing_message_uninit();
- sensor_msgs::PointCloud create_cloudmsg(message::PointCloud_msg);//填充消息
- geometry_msgs::PoseStamped create_posemsg(message::Pose2d_msg);//填充消息
- static void goalCallback(const geometry_msgs::PoseStamped::ConstPtr&);
- public://get or set member variable
- ros::Publisher* find_topic(std::string);
- Connect_statu get_connect_statu();
- protected:
- void socket_receive_data_thread();
- void ros_public_thread();
- void socket_send_data_thread();
- protected://member variable
- nnxx::socket m_socket { nnxx::SP, nnxx::BUS };
- std::mutex m_socket_mutex; //m_socket的锁
- Connect_statu m_connect_statu; //连接状态
- Thread_safe_queue<std::string> m_socket_data_queue; //存放数据的queue
- Thread_safe_queue<std::string> m_send_data_queue; //存放发送数据的queue
- 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; //发送的条件变量
- ros::Subscriber m_subscriber; //用于就收rviz上的消息
- ros::NodeHandle m_nodehandele; //用于创建新的发布器
- std::map<std::string,ros::Publisher*> m_ros_publisher_map; //用于查询是否存在topic
- private:
- };
- #endif //SRC_PROCESSING_MESSAGE_H
|