camera.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2015 Aldebaran
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 /*
00019 * LOCAL includes
00020 */
00021 #include "camera.hpp"
00022 #include "camera_info_definitions.hpp"
00023 #include "../tools/alvisiondefinitions.h" // for kTop...
00024 #include "../tools/from_any_value.hpp"
00025 
00026 /*
00027 * ROS includes
00028 */
00029 #include <cv_bridge/cv_bridge.h>
00030 #include <ros/console.h>
00031 
00032 /*
00033 * CV includes
00034 */
00035 #include <opencv2/imgproc/imgproc.hpp>
00036 
00037 /*
00038 * BOOST includes
00039 */
00040 #include <boost/foreach.hpp>
00041 #define for_each BOOST_FOREACH
00042 
00043 namespace naoqi
00044 {
00045 namespace converter
00046 {
00047 
00048 namespace camera_info_definitions
00049 {
00050 
00051 const sensor_msgs::CameraInfo& getEmptyInfo()
00052 {
00053   static const sensor_msgs::CameraInfo cam_info_msg;
00054   return cam_info_msg;
00055 }
00056 
00057 const sensor_msgs::CameraInfo& getCameraInfo( int camera_source, int resolution )
00058 {
00062   if ( camera_source == AL::kTopCamera)
00063   {
00064     if ( resolution == AL::kVGA )
00065     {
00066       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoTOPVGA();
00067       return cam_info_msg;
00068     }
00069     else if( resolution == AL::kQVGA )
00070     {
00071       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoTOPQVGA();
00072       return cam_info_msg;
00073     }
00074     else if( resolution == AL::kQQVGA )
00075     {
00076       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoTOPQQVGA();
00077       return cam_info_msg;
00078     }
00079   }
00080   else if ( camera_source == AL::kBottomCamera )
00081   {
00082     if ( resolution == AL::kVGA )
00083     {
00084       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoBOTTOMVGA();
00085       return cam_info_msg;
00086     }
00087     else if( resolution == AL::kQVGA )
00088     {
00089       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoBOTTOMQVGA();
00090       return cam_info_msg;
00091     }
00092     else if( resolution == AL::kQQVGA )
00093     {
00094       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoBOTTOMQQVGA();
00095       return cam_info_msg;
00096     }
00097   }
00098   else if ( camera_source == AL::kDepthCamera )
00099   {
00100     if ( resolution == AL::kVGA )
00101     {
00102       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHVGA();
00103       ROS_WARN("VGA resolution is not supported for the depth camera, use QVGA or lower");
00104       return cam_info_msg;
00105     }
00106     else if( resolution == AL::kQVGA )
00107     {
00108       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQVGA();
00109       return cam_info_msg;
00110     }
00111     else if( resolution == AL::kQQVGA )
00112     {
00113       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQVGA();
00114       return cam_info_msg;
00115     }
00116     else if (resolution == AL::k720p){
00117         static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTH720P();
00118         return cam_info_msg;
00119     }
00120     else if (resolution == AL::kQ720p){
00121         static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQ720P();
00122         return cam_info_msg;
00123     }
00124     else if (resolution == AL::kQQ720p){
00125         static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQ720P();
00126         return cam_info_msg;
00127     }
00128     else if (resolution == AL::kQQQ720p){
00129         static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQQ720P();
00130         return cam_info_msg;
00131     }
00132     else if (resolution == AL::kQQQQ720p){
00133         static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQQQ720P();
00134         return cam_info_msg;
00135     }
00136   }
00137   else if (camera_source == AL::kInfraredOrStereoCamera) {
00138     if ( resolution == AL::kVGA )
00139     {
00140       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHVGA();
00141       ROS_WARN("VGA resolution is not supported for the depth camera, use QVGA or lower");
00142       return cam_info_msg;
00143     }
00144     else if( resolution == AL::kQVGA )
00145     {
00146       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQVGA();
00147       return cam_info_msg;
00148     }
00149     else if( resolution == AL::kQQVGA )
00150     {
00151       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQVGA();
00152       return cam_info_msg;
00153     }
00154     else if (resolution == AL::k720px2){
00155       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereo720PX2();
00156       return cam_info_msg;
00157     }
00158     else if (resolution == AL::kQ720px2){
00159       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereoQ720PX2();
00160       return cam_info_msg;
00161     }
00162     else if (resolution == AL::kQQ720px2){
00163       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereoQQ720PX2();
00164       return cam_info_msg;
00165     }
00166     else if (resolution == AL::kQQQ720px2){
00167       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereoQQQ720PX2();
00168       return cam_info_msg;
00169     }
00170     else if (resolution == AL::kQQQQ720px2){
00171       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoStereoQQQQ720PX2();
00172       return cam_info_msg;
00173     }
00174   }
00175   else{
00176     std::cout << "no camera information found for camera_source " << camera_source << " and res: " << resolution << std::endl;
00177     return getEmptyInfo();
00178   }
00179 }
00180 
00181 } // camera_info_definitions
00182 
00183 CameraConverter::CameraConverter(
00184   const std::string& name,
00185   const float& frequency,
00186   const qi::SessionPtr& session,
00187   const int& camera_source,
00188   const int& resolution,
00189   const bool& has_stereo) : BaseConverter( name, frequency, session ),
00190     p_video_( session->service("ALVideoDevice") ),
00191     camera_source_(camera_source),
00192     resolution_(resolution),
00193     // change in case of depth camera
00194     colorspace_( (camera_source_!=AL::kDepthCamera)?AL::kRGBColorSpace:AL::kRawDepthColorSpace ),
00195     msg_colorspace_( (camera_source_!=AL::kDepthCamera)?"rgb8":"16UC1" ),
00196     cv_mat_type_( (camera_source_!=AL::kDepthCamera)?CV_8UC3:CV_16U ),
00197     camera_info_( camera_info_definitions::getCameraInfo(camera_source, resolution) )
00198 {
00199   switch (camera_source) {
00200     case AL::kTopCamera:
00201       msg_frameid_ = "CameraTop_optical_frame";
00202       break;
00203 
00204     case AL::kBottomCamera:
00205       msg_frameid_ = "CameraBottom_optical_frame";
00206       break;
00207 
00208     case AL::kDepthCamera:
00209       msg_frameid_ = "CameraDepth_optical_frame";
00210 
00211       if (has_stereo)
00212         colorspace_ = AL::kDepthColorSpace;
00213 
00214       break;
00215 
00216     case AL::kInfraredOrStereoCamera:
00217       msg_frameid_ = "CameraDepth_optical_frame";
00218 
00219       if (!has_stereo) {
00220         camera_source_ = AL::kDepthCamera;
00221         colorspace_ = AL::kInfraredColorSpace;
00222         msg_colorspace_ = "16UC1";
00223         cv_mat_type_ = CV_16U;
00224       }
00225 
00226       camera_info_ = camera_info_definitions::getCameraInfo(camera_source_, resolution_);
00227       break;
00228   }
00229 }
00230 
00231 CameraConverter::~CameraConverter()
00232 {
00233   if (!handle_.empty())
00234   {
00235     std::cout << "Unsubscribe camera handle " << handle_ << std::endl;
00236     p_video_.call<qi::AnyValue>("unsubscribe", handle_);
00237     handle_.clear();
00238   }
00239 }
00240 
00241 void CameraConverter::reset()
00242 {
00243   if (!handle_.empty())
00244   {
00245     p_video_.call<qi::AnyValue>("unsubscribe", handle_);
00246     handle_.clear();
00247   }
00248 
00249   handle_ = p_video_.call<std::string>(
00250                          "subscribeCamera",
00251                           name_,
00252                           camera_source_,
00253                           resolution_,
00254                           colorspace_,
00255                           frequency_
00256                           );
00257 }
00258 
00259 void CameraConverter::registerCallback( const message_actions::MessageAction action, Callback_t cb )
00260 {
00261   callbacks_[action] = cb;
00262 }
00263 
00264 void CameraConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
00265 {
00266 
00267   if (handle_.empty() )
00268   {
00269     std::cerr << name_ << "Camera Handle is empty - cannot retrieve image" << std::endl;
00270     std::cerr << name_ << "Might be a NAOqi problem. Try to restart the ALVideoDevice." << std::endl;
00271     return;
00272   }
00273 
00274   qi::AnyValue image_anyvalue = p_video_.call<qi::AnyValue>("getImageRemote", handle_);
00275   tools::NaoqiImage image;
00276   try{
00277       image = tools::fromAnyValueToNaoqiImage(image_anyvalue);
00278   }
00279   catch(std::runtime_error& e)
00280   {
00281     std::cout << "Cannot retrieve image" << std::endl;
00282     return;
00283   }
00284 
00285   // Create a cv::Mat of the right dimensions
00286   cv::Mat cv_img(image.height, image.width, cv_mat_type_, image.buffer);
00287   msg_ = cv_bridge::CvImage(std_msgs::Header(), msg_colorspace_, cv_img).toImageMsg();
00288   msg_->header.frame_id = msg_frameid_;
00289 
00290   msg_->header.stamp = ros::Time::now();
00291   //msg_->header.stamp.sec = image.timestamp_s;
00292   //msg_->header.stamp.nsec = image.timestamp_us*1000;
00293   camera_info_.header.stamp = msg_->header.stamp;
00294 
00295   for_each( const message_actions::MessageAction& action, actions )
00296   {
00297     callbacks_[action]( msg_, camera_info_ );
00298   }
00299 }
00300 
00301 } // publisher
00302 } //naoqi


naoqi_driver
Author(s): Karsten Knese
autogenerated on Tue Jul 9 2019 03:21:56