NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
camera.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 
19 #ifndef IS_CAMERA_CAMERA_H_
20 #define IS_CAMERA_CAMERA_H_
21 
23 #include <image_transport/image_transport.h>
24 #include <nodelet/nodelet.h>
25 #include <opencv2/imgproc/imgproc.hpp>
26 #include <ff_msgs/SetBool.h>
27 #include <ff_msgs/SetExposure.h>
28 #include <ff_util/ff_nodelet.h>
29 #include <std_msgs/Int32MultiArray.h>
30 
31 #include <thread>
32 #include <atomic>
33 #include <string>
34 
35 namespace is_camera {
36 
37 // Functions used to interact with Video4Linux
38 struct buffer {
39  void *start;
40  size_t length;
41 };
42 
43 static void xioctl(int fh, int request, void *arg);
44 
45 // Class to hide V4L structures
46 struct V4LStruct;
47 
48 // Nodelet class
50  public:
51  // The size of the image message ring buffer for publishing
52  // grayscale images. 30 images = 35.2 MB of buffer space. This
53  // number is so large because it sets the lifetime for each image
54  // message sent out. Eventually we'll write over the pointer we've
55  // handed out. At 15 Hz, 30 frames means an image will stay valid
56  // for 2.0 seconds. Localization can process at 1 Hz, so it only
57  // needs an image for 1.0 second.
58  static constexpr size_t kImageMsgBuffer = 30;
59 
60  // The size of the image message ring buffer for publishing raw
61  // Bayer format images. The same comments apply about message
62  // lifetime, but in this case we're publishing at a lower rate and
63  // expecting the subscriber callback to at most de-Bayer the image
64  // before passing it on, so the buffer doesn't need to be so long.
65  static constexpr size_t kBayerImageMsgBufferLength = 5;
66 
67  static constexpr size_t kImageWidth = 1280;
68  static constexpr size_t kImageHeight = 960;
69 
70  CameraNodelet();
71  virtual ~CameraNodelet();
72  void ReadParams(void);
73 
74  protected:
75  virtual void Initialize(ros::NodeHandle* nh);
76 
77  private:
78  void PublishLoop();
79  void LoadCameraInfo();
80  void EnableBayer(bool enable);
81  void AutoExposure();
82  size_t getNumBayerSubscribers();
83  bool SetExposure(ff_msgs::SetExposure::Request &req, ff_msgs::SetExposure::Response &res);
84 
85  sensor_msgs::CameraInfo info_msg_;
86 
87  ros::NodeHandle *nh_;
88  sensor_msgs::ImagePtr img_msg_buffer_[kImageMsgBuffer];
89  sensor_msgs::ImagePtr bayer_img_msg_buffer_[kBayerImageMsgBufferLength];
90  size_t img_msg_buffer_idx_;
91  size_t bayer_img_msg_buffer_idx_;
92  std::thread thread_;
93  std::atomic<bool> thread_running_;
94  ros::Publisher pub_;
95  ros::Publisher info_pub_;
96  ros::Publisher bayer_pub_;
97  ros::Publisher pub_exposure_;
98  ros::ServiceServer srv_exposure_;
99  std::shared_ptr<V4LStruct> v4l_;
100 
102  ros::Timer config_timer_;
103  ros::Timer auto_exposure_timer_;
104  std::string camera_device_;
105  std::string camera_topic_;
106  std::string bayer_camera_topic_;
107  std::string config_name_;
108  int camera_gain_, camera_exposure_, camera_auto_exposure_;
109  bool calibration_mode_;
110 
111  // bayer_enable: Set to true to enable publishing raw Bayer image
112  // (can be converted to RGB). May incur significant I/O overhead.
113  bool bayer_enable_;
114 
115  // bayer_throttle_ratio: Set to n to publish 1 raw Bayer image for
116  // every n images grabbed. With n = 1, every image is
117  // published. Larger n reduces I/O overhead.
118  unsigned int bayer_throttle_ratio_;
119  size_t bayer_throttle_ratio_counter_;
120 
121  // Auto exposure parameters
122  bool auto_exposure_;
123  int hist_size_;
124  double desired_msv_, k_p_, k_i_, max_i_, err_p_, err_i_, tolerance_;
125 };
126 
127 } // end namespace is_camera
128 
129 #endif // IS_CAMERA_CAMERA_H_
is_camera::CameraNodelet::kImageMsgBuffer
static constexpr size_t kImageMsgBuffer
Definition: camera.h:58
is_camera::CameraNodelet::kImageWidth
static constexpr size_t kImageWidth
Definition: camera.h:67
is_camera::CameraNodelet::~CameraNodelet
virtual ~CameraNodelet()
Definition: camera.cc:179
is_camera::CameraNodelet::kImageHeight
static constexpr size_t kImageHeight
Definition: camera.h:68
ff_nodelet.h
is_camera::xioctl
static void xioctl(int fh, int request, void *arg)
is_camera::CameraNodelet
Definition: camera.h:49
is_camera::CameraNodelet::CameraNodelet
CameraNodelet()
Definition: camera.cc:165
is_camera::V4LStruct
Definition: camera.cc:56
ff_util::FreeFlyerNodelet
Definition: ff_nodelet.h:57
is_camera::CameraNodelet::kBayerImageMsgBufferLength
static constexpr size_t kBayerImageMsgBufferLength
Definition: camera.h:65
config_reader::ConfigReader
Definition: config_reader.h:48
is_camera::buffer::start
void * start
Definition: camera.h:39
config_reader.h
is_camera
Definition: camera.h:35
is_camera::buffer
Definition: camera.h:38
is_camera::CameraNodelet::ReadParams
void ReadParams(void)
Definition: camera.cc:276
is_camera::buffer::length
size_t length
Definition: camera.h:40
is_camera::CameraNodelet::Initialize
virtual void Initialize(ros::NodeHandle *nh)
Definition: camera.cc:185