Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00042 #ifndef _BTA_ROS_HPP_
00043 #define _BTA_ROS_HPP_
00044 
00045 #include <bta.h>
00046 
00047 
00048 #include <ros/ros.h>
00049 #include <image_transport/image_transport.h>
00050 #include <camera_info_manager/camera_info_manager.h>
00051 #include <sensor_msgs/Image.h>
00052 #include <sensor_msgs/CameraInfo.h>
00053 #include <sensor_msgs/SetCameraInfo.h>
00054 #include <sensor_msgs/image_encodings.h>
00055 #include <sensor_msgs/PointCloud2.h>
00056 #include <sensor_msgs/point_cloud2_iterator.h>
00057 #include <tf2_ros/static_transform_broadcaster.h>
00058 #include <geometry_msgs/TransformStamped.h>
00059 
00060 #include <ros/console.h>
00061 #include <tf/transform_listener.h>
00062 
00063 
00064 #include <pcl_ros/point_cloud.h>
00065 #include <pcl/point_types.h>
00066 #include <pcl/conversions.h>
00067 
00068 
00069 #include <stdio.h>
00070 #include <time.h>
00071 #include <sstream>
00072 #include <string>
00073 
00074 
00075 #include <bta_ros/bta_rosConfig.h>
00076 #include <dynamic_reconfigure/server.h>
00077 
00078 
00079 
00080 namespace bta_ros {
00081 
00082 class BtaRos
00083 {
00084 
00085     typedef bta_ros::bta_rosConfig Config;
00086     typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00087 
00088 public:
00089 
00099     BtaRos(ros::NodeHandle nh_camera, ros::NodeHandle nh_private, std::string nodeName);
00100 
00106     virtual ~BtaRos();
00107 
00113     int initialize();
00114 
00120     int connectCamera();
00121 
00127     void close();
00128 
00129 
00135     void publishData();
00136 
00137     
00138 
00139     
00140 
00141     static void BTA_CALLCONV infoEventCb(BTA_EventId eventId, int8_t *msg) {
00142         ROS_DEBUG("   Callback: infoEvent (%d) %s\n", eventId, msg);
00143     }
00144 
00145 private:
00146     ros::NodeHandle nh_, nh_private_;
00147     std::string nodeName_;
00148     camera_info_manager::CameraInfoManager cim_tof_;
00149     image_transport::ImageTransport it_;
00150     image_transport::CameraPublisher pub_amp_, pub_dis_;
00151     tf2_ros::StaticTransformBroadcaster pub_tf;
00152     geometry_msgs::TransformStamped transformStamped;
00153     ros::Publisher pub_xyz_;
00154     
00155     boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00156     bool config_init_;
00157 
00158     boost::mutex connect_mutex_;
00159 
00160     
00161     uint8_t udpDataIpAddr_[6], udpControlOutIpAddr_[6],
00162     udpControlInIpAddr_[6], tcpDeviceIpAddr_[6];
00163     std::string uartPortName_, calibFileName_;
00164 
00165     sensor_msgs::PointCloud2Ptr _xyz;
00166 
00167     BTA_Handle handle_;
00168     BTA_Config config_;
00169 
00179     void callback(bta_ros::bta_rosConfig &config, uint32_t level);
00180 
00186     void parseConfig();
00187 
00193     size_t getDataSize(BTA_DataFormat dataFormat);
00194 
00200     std::string getDataType(BTA_DataFormat dataFormat);
00201 
00207     float getUnit2Meters(BTA_Unit unit);
00208 
00209     
00210     
00211 
00212 
00213 
00214 
00215 
00216 
00217 
00218 
00219 
00220 
00221 
00222 
00223 
00224 
00225 
00226 
00227 
00228 
00229 
00230 
00231 
00232 
00233 
00234 
00235 
00236 
00237 
00238 
00239 
00240 
00241 
00242 
00243 
00244 
00245 
00246 
00247 
00248 
00249 
00250 
00251 
00252 
00253 
00254 
00255 
00256 
00257 
00258 
00259 
00260 
00261 
00262 
00263 
00264 };
00265 }
00266 
00267 #endif
00268