23 #include "../tools/alvisiondefinitions.h"
24 #include "../tools/from_any_value.hpp"
35 #include <opencv2/imgproc/imgproc.hpp>
40 #include <boost/foreach.hpp>
41 #define for_each BOOST_FOREACH
48 namespace camera_info_definitions
53 static const sensor_msgs::CameraInfo cam_info_msg;
57 const sensor_msgs::CameraInfo&
getCameraInfo(
int camera_source,
int resolution )
103 ROS_WARN(
"VGA resolution is not supported for the depth camera, use QVGA or lower");
141 ROS_WARN(
"VGA resolution is not supported for the depth camera, use QVGA or lower");
176 std::cout <<
"no camera information found for camera_source " << camera_source <<
" and res: " << resolution << std::endl;
183 const std::string& name,
184 const float& frequency,
185 const qi::SessionPtr& session,
186 const int& camera_source,
187 const int& resolution,
189 p_video_(
session->service(
"ALVideoDevice").value()),
190 camera_source_(camera_source),
191 resolution_(resolution),
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) )
198 switch (camera_source) {
234 std::cout <<
"Unsubscribe camera handle " <<
handle_ << std::endl;
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;
273 qi::AnyValue image_anyvalue =
p_video_.call<qi::AnyValue>(
"getImageRemote",
handle_);
278 catch(std::runtime_error& e)
280 std::cout <<
"Cannot retrieve image" << std::endl;
285 cv::Mat cv_img(image.height, image.width,
cv_mat_type_, image.buffer);