ximea_ros_driver.h
Go to the documentation of this file.
00001 /******************************************************************************
00002 
00003 Copyright 2015  Abdelhamid El-Bably (University of Waterloo)
00004                       [ahelbably@uwaterloo.ca]
00005                 Arun Das (University of Waterloo)
00006                       [adas@uwaterloo.ca]
00007                 Michael Tribou (University of Waterloo)
00008                       [mjtribou@uwaterloo.ca]
00009 
00010 All rights reserved.
00011 
00012 ********************************************************************************/
00013 
00014 #ifndef XIMEA_CAMERA_XIMEA_ROS_DRIVER_H
00015 #define XIMEA_CAMERA_XIMEA_ROS_DRIVER_H
00016 
00017 #include <ximea_camera/ximea_driver.h>
00018 #include <ros/ros.h>
00019 #include <image_transport/image_transport.h>
00020 #include <image_transport/publisher.h>
00021 #include <sensor_msgs/Image.h>
00022 #include <sensor_msgs/CameraInfo.h>
00023 #include <camera_info_manager/camera_info_manager.h>
00024 #include <string>
00025 #include <boost/shared_ptr.hpp>
00026 
00027 class ximea_ros_driver : public ximea_driver
00028 {
00029 public:
00030   ximea_ros_driver(const ros::NodeHandle &nh, std::string cam_name, int serial_no , std::string yaml_url);
00031   ximea_ros_driver(const ros::NodeHandle &nh, std::string file_name);
00032   virtual void setImageDataFormat(std::string s);
00033   void publishImage(const ros::Time & now);  // since these 2 functions should have the same time stamp we leave it up to the user to specify the timeif it is needed to do one or the other
00034   void publishCamInfo(const ros::Time &now);
00035   void publishImageAndCamInfo();
00036 
00037 protected:
00038   ros::NodeHandle pnh_;
00039   boost::shared_ptr<camera_info_manager::CameraInfoManager> cam_info_manager_;
00040   boost::shared_ptr<image_transport::ImageTransport> it_;
00041   image_transport::Publisher ros_cam_pub_;
00042   ros::Publisher cam_info_pub_;
00043 
00044   sensor_msgs::Image ros_image_;
00045   sensor_msgs::CameraInfo cam_info_;
00046   char * cam_buffer_;
00047   int cam_buffer_size_;
00048   int bpp_;  // the next 2 paramaeters are used by the ros_image_transport publisher
00049   std::string encoding_;
00050 
00051 private:
00052   void common_initialize(const ros::NodeHandle &nh);
00053 };
00054 
00055 #endif  // XIMEA_CAMERA_XIMEA_ROS_DRIVER_H


ximea_camera
Author(s): Abdelhamid El-Bably, Arun Das, Michael Tribou
autogenerated on Thu Jun 6 2019 21:17:12