00001 #ifndef _MOFA_BRIDGE_H_ 00002 #define _MOFA_BRIDGE_H_ 00003 00004 #include "termios.h" 00005 00006 #include <fstream> 00007 #include <sstream> 00008 #include <iomanip> 00009 00010 #include "cv.h" 00011 #include "highgui.h" 00012 00013 #include "ros/ros.h" 00014 #include "ros/callback_queue.h" 00015 00016 #include "tf/tf.h" 00017 00018 // [PCL_ROS] 00019 #include "pcl_ros/point_cloud.h" 00020 #include "pcl/point_types.h" 00021 #include "pcl/ros/register_point_struct.h" 00022 00023 //pcl::toROSMsg 00024 #include <pcl/io/pcd_io.h> 00025 00026 00027 // [publisher subscriber headers] 00028 #include "sensor_msgs/PointCloud2.h" 00029 #include "sensor_msgs/Image.h" 00030 #include "geometry_msgs/PoseStamped.h" 00031 #include "iri_wam_common_msgs/obs_request.h" 00032 00033 //vanila socket 00034 #include "socket.h" 00035 #include "socketclient.h" 00036 #include "mutex.h" 00037 #include "thread.h" 00038 #include "eventexceptions.h" 00039 00040 #define ERROR_POS 0 00041 #define RX_ID_POS 1 00042 #define MAXCONN 5 00043 #define BUFFERSIZE 512 00044 #define DATASIZE 512 00045 00046 typedef union { 00047 struct /*anonymous*/ 00048 { 00049 unsigned char Blue; 00050 unsigned char Green; 00051 unsigned char Red; 00052 unsigned char Alpha; 00053 }; 00054 float float_value; 00055 long long_value; 00056 } RGBValue; 00057 00058 class DummyMofaBridge { 00059 public: 00060 DummyMofaBridge(); 00061 ~DummyMofaBridge(); 00062 void open(); 00063 void close(); 00064 private: 00065 00066 //vanila socket 00067 bool connected; 00068 std::string serverip; 00069 int port; 00071 CMutex socketmutex; 00072 00074 CSocketClient *csocket; 00075 00077 CEventServer *eventserver; 00078 00080 std::list<std::string> events; 00081 00082 int num_objects; 00083 00084 //service activation parameters 00085 bool flag_mpcl2; 00086 00087 int idx; 00088 int nr; 00089 int nc; 00090 sensor_msgs::PointCloud2ConstPtr* msg_; 00091 pcl::PointCloud<pcl::PointXYZRGB> pcl_xyzrgb; 00092 00093 std::ofstream matlab_xyzrgb; 00094 std::ifstream matlab_xyzrgb_in; 00095 00096 // ROS Handlers 00097 ros::NodeHandle nh; 00098 00099 // ROS Publishers 00100 ros::Publisher labeled_pcl2_publisher; 00101 00102 // ROS Subscribers 00103 ros::Subscriber pcl2_sub; 00104 00105 // ROS Services 00106 ros::ServiceServer obs_request; 00107 00108 void pcl2_sub_callback(const sensor_msgs::PointCloud2ConstPtr& msg); 00109 bool obs_request_callback(iri_wam_common_msgs::obs_request::Request &req, iri_wam_common_msgs::obs_request::Response &res); 00110 00111 void reloadRGB(); 00112 }; 00113 #endif