38 #include <boost/thread/mutex.hpp> 42 #include <dynamic_reconfigure/server.h> 44 #include <sensor_msgs/CameraInfo.h> 47 #include "camera1394stereo/Camera1394StereoConfig.h" 48 typedef camera1394stereo::Camera1394StereoConfig
Config;
83 static const uint8_t CLOSED = 0;
84 static const uint8_t OPENED = 1;
85 static const uint8_t RUNNING = 2;
91 static const int NUM_CAMERAS = 2;
92 static const std::string CameraSelectorString[NUM_CAMERAS];
96 bool openCamera(
Config &newconfig);
97 void publish(
const sensor_msgs::ImagePtr image[NUM_CAMERAS]);
98 bool read(sensor_msgs::ImagePtr image[NUM_CAMERAS]);
99 void reconfig(camera1394stereo::Camera1394StereoConfig &newconfig, uint32_t level);
116 camera1394stereo::Camera1394StereoConfig
config_;
117 dynamic_reconfigure::Server<camera1394stereo::Camera1394StereoConfig>
srv_;
122 bool calibration_matches_[NUM_CAMERAS];
camera1394stereo::Camera1394StereoConfig Config
static const uint32_t RECONFIGURE_STOP
IEEE 1394 digital camera library interface.
boost::shared_ptr< camera1394stereo::Camera1394Stereo > dev_
camera1394stereo::Camera1394StereoConfig Config
camera1394stereo::Camera1394StereoConfig config_
ros::NodeHandle camera_nh_
dynamic_reconfigure::Server< camera1394stereo::Camera1394StereoConfig > srv_
static const uint32_t RECONFIGURE_CLOSE
static const uint32_t RECONFIGURE_RUNNING
boost::shared_ptr< image_transport::ImageTransport > it_
volatile bool reconfiguring_