converters/camera.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 /*
19 * LOCAL includes
20 */
21 #include "camera.hpp"
23 #include "../tools/alvisiondefinitions.h" // for kTop...
24 #include "../tools/from_any_value.hpp"
25 
26 /*
27 * ROS includes
28 */
29 #include <cv_bridge/cv_bridge.h>
30 #include <ros/console.h>
31 
32 /*
33 * CV includes
34 */
35 #include <opencv2/imgproc/imgproc.hpp>
36 
37 /*
38 * BOOST includes
39 */
40 #include <boost/foreach.hpp>
41 #define for_each BOOST_FOREACH
42 
43 namespace naoqi
44 {
45 namespace converter
46 {
47 
48 namespace camera_info_definitions
49 {
50 
51 const sensor_msgs::CameraInfo& getEmptyInfo()
52 {
53  static const sensor_msgs::CameraInfo cam_info_msg;
54  return cam_info_msg;
55 }
56 
57 const sensor_msgs::CameraInfo& getCameraInfo( int camera_source, int resolution )
58 {
62  if ( camera_source == AL::kTopCamera)
63  {
64  if ( resolution == AL::kVGA )
65  {
66  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoTOPVGA();
67  return cam_info_msg;
68  }
69  else if( resolution == AL::kQVGA )
70  {
71  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoTOPQVGA();
72  return cam_info_msg;
73  }
74  else if( resolution == AL::kQQVGA )
75  {
76  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoTOPQQVGA();
77  return cam_info_msg;
78  }
79  }
80  else if ( camera_source == AL::kBottomCamera )
81  {
82  if ( resolution == AL::kVGA )
83  {
84  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoBOTTOMVGA();
85  return cam_info_msg;
86  }
87  else if( resolution == AL::kQVGA )
88  {
89  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoBOTTOMQVGA();
90  return cam_info_msg;
91  }
92  else if( resolution == AL::kQQVGA )
93  {
94  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoBOTTOMQQVGA();
95  return cam_info_msg;
96  }
97  }
98  else if ( camera_source == AL::kDepthCamera )
99  {
100  if ( resolution == AL::kVGA )
101  {
102  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHVGA();
103  ROS_WARN("VGA resolution is not supported for the depth camera, use QVGA or lower");
104  return cam_info_msg;
105  }
106  else if( resolution == AL::kQVGA )
107  {
108  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQVGA();
109  return cam_info_msg;
110  }
111  else if( resolution == AL::kQQVGA )
112  {
113  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQVGA();
114  return cam_info_msg;
115  }
116  else if (resolution == AL::k720p){
117  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTH720P();
118  return cam_info_msg;
119  }
120  else if (resolution == AL::kQ720p){
121  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQ720P();
122  return cam_info_msg;
123  }
124  else if (resolution == AL::kQQ720p){
125  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQ720P();
126  return cam_info_msg;
127  }
128  else if (resolution == AL::kQQQ720p){
129  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQQ720P();
130  return cam_info_msg;
131  }
132  else if (resolution == AL::kQQQQ720p){
133  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQQQ720P();
134  return cam_info_msg;
135  }
136  }
137  else if (camera_source == AL::kInfraredOrStereoCamera) {
138  if ( resolution == AL::kVGA )
139  {
140  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHVGA();
141  ROS_WARN("VGA resolution is not supported for the depth camera, use QVGA or lower");
142  return cam_info_msg;
143  }
144  else if( resolution == AL::kQVGA )
145  {
146  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQVGA();
147  return cam_info_msg;
148  }
149  else if( resolution == AL::kQQVGA )
150  {
151  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQVGA();
152  return cam_info_msg;
153  }
154  else if (resolution == AL::k720px2){
155  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereo720PX2();
156  return cam_info_msg;
157  }
158  else if (resolution == AL::kQ720px2){
159  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereoQ720PX2();
160  return cam_info_msg;
161  }
162  else if (resolution == AL::kQQ720px2){
163  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereoQQ720PX2();
164  return cam_info_msg;
165  }
166  else if (resolution == AL::kQQQ720px2){
167  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereoQQQ720PX2();
168  return cam_info_msg;
169  }
170  else if (resolution == AL::kQQQQ720px2){
171  static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereoQQQQ720PX2();
172  return cam_info_msg;
173  }
174  }
175  // else
176  std::cout << "no camera information found for camera_source " << camera_source << " and res: " << resolution << std::endl;
177  return getEmptyInfo();
178 }
179 
180 } // camera_info_definitions
181 
183  const std::string& name,
184  const float& frequency,
185  const qi::SessionPtr& session,
186  const int& camera_source,
187  const int& resolution,
188  const bool& has_stereo) : BaseConverter( name, frequency, session ),
189  p_video_(session->service("ALVideoDevice").value()),
190  camera_source_(camera_source),
191  resolution_(resolution),
192  // change in case of depth camera
193  colorspace_( (camera_source_!=AL::kDepthCamera)?AL::kRGBColorSpace:AL::kRawDepthColorSpace ),
194  msg_colorspace_( (camera_source_!=AL::kDepthCamera)?"rgb8":"16UC1" ),
195  cv_mat_type_( (camera_source_!=AL::kDepthCamera)?CV_8UC3:CV_16U ),
196  camera_info_( camera_info_definitions::getCameraInfo(camera_source, resolution) )
197 {
198  switch (camera_source) {
199  case AL::kTopCamera:
200  msg_frameid_ = "CameraTop_optical_frame";
201  break;
202 
203  case AL::kBottomCamera:
204  msg_frameid_ = "CameraBottom_optical_frame";
205  break;
206 
207  case AL::kDepthCamera:
208  msg_frameid_ = "CameraDepth_optical_frame";
209 
210  if (has_stereo)
212 
213  break;
214 
216  msg_frameid_ = "CameraDepth_optical_frame";
217 
218  if (!has_stereo) {
221  msg_colorspace_ = "16UC1";
222  cv_mat_type_ = CV_16U;
223  }
224 
226  break;
227  }
228 }
229 
231 {
232  if (!handle_.empty())
233  {
234  std::cout << "Unsubscribe camera handle " << handle_ << std::endl;
235  p_video_.call<qi::AnyValue>("unsubscribe", handle_);
236  handle_.clear();
237  }
238 }
239 
241 {
242  if (!handle_.empty())
243  {
244  p_video_.call<qi::AnyValue>("unsubscribe", handle_);
245  handle_.clear();
246  }
247 
248  handle_ = p_video_.call<std::string>(
249  "subscribeCamera",
250  name_,
252  resolution_,
253  colorspace_,
254  frequency_
255  );
256 }
257 
259 {
260  callbacks_[action] = cb;
261 }
262 
263 void CameraConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
264 {
265 
266  if (handle_.empty() )
267  {
268  std::cerr << name_ << "Camera Handle is empty - cannot retrieve image" << std::endl;
269  std::cerr << name_ << "Might be a NAOqi problem. Try to restart the ALVideoDevice." << std::endl;
270  return;
271  }
272 
273  qi::AnyValue image_anyvalue = p_video_.call<qi::AnyValue>("getImageRemote", handle_);
274  tools::NaoqiImage image;
275  try{
276  image = tools::fromAnyValueToNaoqiImage(image_anyvalue);
277  }
278  catch(std::runtime_error& e)
279  {
280  std::cout << "Cannot retrieve image" << std::endl;
281  return;
282  }
283 
284  // Create a cv::Mat of the right dimensions
285  cv::Mat cv_img(image.height, image.width, cv_mat_type_, image.buffer);
286  msg_ = cv_bridge::CvImage(std_msgs::Header(), msg_colorspace_, cv_img).toImageMsg();
287  msg_->header.frame_id = msg_frameid_;
288 
289  msg_->header.stamp = ros::Time::now();
290  //msg_->header.stamp.sec = image.timestamp_s;
291  //msg_->header.stamp.nsec = image.timestamp_us*1000;
292  camera_info_.header.stamp = msg_->header.stamp;
293 
294  for_each( const message_actions::MessageAction& action, actions )
295  {
296  callbacks_[action]( msg_, camera_info_ );
297  }
298 }
299 
300 } // publisher
301 } //naoqi
naoqi::converter::CameraConverter::callAll
void callAll(const std::vector< message_actions::MessageAction > &actions)
Definition: converters/camera.cpp:263
for_each
#define for_each
Definition: converters/camera.cpp:41
AL::kBottomCamera
const int kBottomCamera
Definition: alvisiondefinitions.h:37
camera_info_definitions.hpp
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
converter
AL::kQQ720p
const int kQQ720p
Definition: alvisiondefinitions.h:55
naoqi::converter::camera_info_definitions::createCameraInfoDEPTHQVGA
sensor_msgs::CameraInfo createCameraInfoDEPTHQVGA()
Definition: camera_info_definitions.hpp:187
naoqi::converter::camera_info_definitions::createCameraInfoTOPVGA
sensor_msgs::CameraInfo createCameraInfoTOPVGA()
Definition: camera_info_definitions.hpp:34
naoqi::converter::CameraConverter::camera_info_
sensor_msgs::CameraInfo camera_info_
Definition: converters/camera.hpp:75
session
session
naoqi::message_actions::MessageAction
MessageAction
Definition: message_actions.h:9
naoqi::converter::camera_info_definitions::createCameraInfoDEPTHQ720P
sensor_msgs::CameraInfo createCameraInfoDEPTHQ720P()
Definition: camera_info_definitions.hpp:287
AL::kRGBColorSpace
const int kRGBColorSpace
Definition: alvisiondefinitions.h:79
naoqi::converter::camera_info_definitions::createCameraInfoBOTTOMQQVGA
sensor_msgs::CameraInfo createCameraInfoBOTTOMQQVGA()
Definition: camera_info_definitions.hpp:142
naoqi::converter::camera_info_definitions::createCameraInfoTOPQQVGA
sensor_msgs::CameraInfo createCameraInfoTOPQQVGA()
Definition: camera_info_definitions.hpp:76
naoqi::converter::CameraConverter::colorspace_
int colorspace_
Definition: converters/camera.hpp:66
naoqi::converter::camera_info_definitions::createCameraInfoBOTTOMVGA
sensor_msgs::CameraInfo createCameraInfoBOTTOMVGA()
Definition: camera_info_definitions.hpp:100
naoqi::converter::camera_info_definitions::createCameraInfoStereoQQQQ720PX2
sensor_msgs::CameraInfo createCameraInfoStereoQQQQ720PX2()
Definition: camera_info_definitions.hpp:328
AL::kQQQ720p
const int kQQQ720p
Definition: alvisiondefinitions.h:56
naoqi::converter::camera_info_definitions::createCameraInfoDEPTH720P
sensor_msgs::CameraInfo createCameraInfoDEPTH720P()
Definition: camera_info_definitions.hpp:281
naoqi::converter::camera_info_definitions::createCameraInfoStereoQ720PX2
sensor_msgs::CameraInfo createCameraInfoStereoQ720PX2()
Definition: camera_info_definitions.hpp:313
naoqi::converter::CameraConverter::handle_
std::string handle_
Definition: converters/camera.hpp:67
naoqi::converter::CameraConverter::camera_source_
int camera_source_
Definition: converters/camera.hpp:64
AL::k720p
const int k720p
Definition: alvisiondefinitions.h:53
naoqi::converter::CameraConverter::resolution_
int resolution_
Definition: converters/camera.hpp:65
AL::kVGA
const int kVGA
Definition: alvisiondefinitions.h:48
naoqi::converter::CameraConverter::msg_
sensor_msgs::ImagePtr msg_
Definition: converters/camera.hpp:76
naoqi::converter::CameraConverter::Callback_t
boost::function< void(sensor_msgs::ImagePtr, sensor_msgs::CameraInfo)> Callback_t
Definition: converters/camera.hpp:40
naoqi
Definition: converter.hpp:29
console.h
AL::kDepthColorSpace
const int kDepthColorSpace
Definition: alvisiondefinitions.h:85
naoqi::converter::camera_info_definitions::getCameraInfo
const sensor_msgs::CameraInfo & getCameraInfo(int camera_source, int resolution)
Definition: converters/camera.cpp:57
AL::kQQQ720px2
const int kQQQ720px2
Definition: alvisiondefinitions.h:61
AL::kQ720px2
const int kQ720px2
Definition: alvisiondefinitions.h:59
naoqi::converter::CameraConverter::msg_colorspace_
std::string msg_colorspace_
Definition: converters/camera.hpp:71
naoqi::converter::CameraConverter::CameraConverter
CameraConverter(const std::string &name, const float &frequency, const qi::SessionPtr &session, const int &camera_source, const int &resolution, const bool &has_stereo=false)
Definition: converters/camera.cpp:182
AL::kQQ720px2
const int kQQ720px2
Definition: alvisiondefinitions.h:60
AL::kRawDepthColorSpace
const int kRawDepthColorSpace
Definition: alvisiondefinitions.h:90
camera.hpp
naoqi::tools::NaoqiImage
The struct describing an image retrieved by ALVideoDevice. This specification can be found here: http...
Definition: naoqi_image.hpp:30
ROS_WARN
#define ROS_WARN(...)
AL::kInfraredOrStereoCamera
const int kInfraredOrStereoCamera
Definition: alvisiondefinitions.h:39
naoqi::converter::BaseConverter< CameraConverter >::frequency_
float frequency_
Definition: converter_base.hpp:69
name
name
naoqi::converter::camera_info_definitions::createCameraInfoStereoQQ720PX2
sensor_msgs::CameraInfo createCameraInfoStereoQQ720PX2()
Definition: camera_info_definitions.hpp:318
naoqi::converter::BaseConverter
Definition: converter_base.hpp:40
naoqi::converter::CameraConverter::p_video_
qi::AnyObject p_video_
Definition: converters/camera.hpp:63
naoqi::tools::fromAnyValueToNaoqiImage
NaoqiImage fromAnyValueToNaoqiImage(qi::AnyValue &value)
Definition: from_any_value.cpp:24
AL::kQQQQ720px2
const int kQQQQ720px2
Definition: alvisiondefinitions.h:62
naoqi::converter::camera_info_definitions::createCameraInfoDEPTHQQVGA
sensor_msgs::CameraInfo createCameraInfoDEPTHQQVGA()
Definition: camera_info_definitions.hpp:207
naoqi::converter::camera_info_definitions::createCameraInfoTOPQVGA
sensor_msgs::CameraInfo createCameraInfoTOPQVGA()
Definition: camera_info_definitions.hpp:55
AL::kInfraredColorSpace
const int kInfraredColorSpace
Definition: alvisiondefinitions.h:88
naoqi::converter::CameraConverter::registerCallback
void registerCallback(const message_actions::MessageAction action, Callback_t cb)
Definition: converters/camera.cpp:258
AL
Definition: alvisiondefinitions.h:27
naoqi::converter::camera_info_definitions::getEmptyInfo
const sensor_msgs::CameraInfo & getEmptyInfo()
Definition: converters/camera.cpp:51
naoqi::converter::CameraConverter::cv_mat_type_
int cv_mat_type_
Definition: converters/camera.hpp:72
AL::kQQVGA
const int kQQVGA
Definition: alvisiondefinitions.h:46
naoqi::converter::camera_info_definitions::createCameraInfoDEPTHQQQQ720P
sensor_msgs::CameraInfo createCameraInfoDEPTHQQQQ720P()
Definition: camera_info_definitions.hpp:302
cv_bridge.h
cv_bridge::CvImage
AL::kTopCamera
const int kTopCamera
Definition: alvisiondefinitions.h:36
AL::kDepthCamera
const int kDepthCamera
Definition: alvisiondefinitions.h:38
naoqi::converter::BaseConverter< CameraConverter >::name_
std::string name_
Definition: converter_base.hpp:66
naoqi::converter::CameraConverter::~CameraConverter
~CameraConverter()
Definition: converters/camera.cpp:230
naoqi::converter::camera_info_definitions::createCameraInfoBOTTOMQVGA
sensor_msgs::CameraInfo createCameraInfoBOTTOMQVGA()
Definition: camera_info_definitions.hpp:121
naoqi::converter::camera_info_definitions::createCameraInfoStereoQQQ720PX2
sensor_msgs::CameraInfo createCameraInfoStereoQQQ720PX2()
Definition: camera_info_definitions.hpp:323
AL::kQVGA
const int kQVGA
Definition: alvisiondefinitions.h:47
AL::kQQQQ720p
const int kQQQQ720p
Definition: alvisiondefinitions.h:57
naoqi::converter::camera_info_definitions::createCameraInfoDEPTHQQQ720P
sensor_msgs::CameraInfo createCameraInfoDEPTHQQQ720P()
Definition: camera_info_definitions.hpp:297
naoqi::converter::camera_info_definitions::createCameraInfoStereo720PX2
sensor_msgs::CameraInfo createCameraInfoStereo720PX2()
Definition: camera_info_definitions.hpp:308
naoqi::converter::CameraConverter::msg_frameid_
std::string msg_frameid_
Definition: converters/camera.hpp:74
naoqi::converter::camera_info_definitions::createCameraInfoDEPTHVGA
sensor_msgs::CameraInfo createCameraInfoDEPTHVGA()
Definition: camera_info_definitions.hpp:166
naoqi::converter::camera_info_definitions::createCameraInfoDEPTHQQ720P
sensor_msgs::CameraInfo createCameraInfoDEPTHQQ720P()
Definition: camera_info_definitions.hpp:292
naoqi::converter::CameraConverter::callbacks_
std::map< message_actions::MessageAction, Callback_t > callbacks_
Definition: converters/camera.hpp:60
AL::kQ720p
const int kQ720p
Definition: alvisiondefinitions.h:54
naoqi::converter::CameraConverter::reset
void reset()
Definition: converters/camera.cpp:240
AL::k720px2
const int k720px2
Definition: alvisiondefinitions.h:58
ros::Time::now
static Time now()


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06