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 
00031 /*
00032 * CV includes
00033 */
00034 #include <opencv2/imgproc/imgproc.hpp>
00035 
00036 /*
00037 * BOOST includes
00038 */
00039 #include <boost/foreach.hpp>
00040 #define for_each BOOST_FOREACH
00041 
00042 namespace naoqi
00043 {
00044 namespace converter
00045 {
00046 
00047 namespace camera_info_definitions
00048 {
00049 
00050 const sensor_msgs::CameraInfo& getEmptyInfo()
00051 {
00052   static const sensor_msgs::CameraInfo cam_info_msg;
00053   return cam_info_msg;
00054 }
00055 
00056 const sensor_msgs::CameraInfo& getCameraInfo( int camera_source, int resolution )
00057 {
00061   if ( camera_source == AL::kTopCamera)
00062   {
00063     if ( resolution == AL::kVGA )
00064     {
00065       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoTOPVGA();
00066       return cam_info_msg;
00067     }
00068     else if( resolution == AL::kQVGA )
00069     {
00070       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoTOPQVGA();
00071       return cam_info_msg;
00072     }
00073     else if( resolution == AL::kQQVGA )
00074     {
00075       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoTOPQQVGA();
00076       return cam_info_msg;
00077     }
00078   }
00079   else if ( camera_source == AL::kBottomCamera )
00080   {
00081     if ( resolution == AL::kVGA )
00082     {
00083       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoBOTTOMVGA();
00084       return cam_info_msg;
00085     }
00086     else if( resolution == AL::kQVGA )
00087     {
00088       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoBOTTOMQVGA();
00089       return cam_info_msg;
00090     }
00091     else if( resolution == AL::kQQVGA )
00092     {
00093       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoBOTTOMQQVGA();
00094       return cam_info_msg;
00095     }
00096   }
00097   else if ( camera_source == AL::kDepthCamera )
00098   {
00099     if ( resolution == AL::kVGA )
00100     {
00101       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHVGA();
00102       return cam_info_msg;
00103     }
00104     else if( resolution == AL::kQVGA )
00105     {
00106       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQVGA();
00107       return cam_info_msg;
00108     }
00109     else if( resolution == AL::kQQVGA )
00110     {
00111       static const sensor_msgs::CameraInfo cam_info_msg = createCameraInfoDEPTHQQVGA();
00112       return cam_info_msg;
00113     }
00114   }
00115   else{
00116     std::cout << "no camera information found for camera_source " << camera_source << " and res: " << resolution << std::endl;
00117     return getEmptyInfo();
00118   }
00119 }
00120 
00121 } // camera_info_definitions
00122 
00123 CameraConverter::CameraConverter( const std::string& name, const float& frequency, const qi::SessionPtr& session, const int& camera_source, const int& resolution )
00124   : BaseConverter( name, frequency, session ),
00125     p_video_( session->service("ALVideoDevice") ),
00126     camera_source_(camera_source),
00127     resolution_(resolution),
00128     // change in case of depth camera
00129     colorspace_( (camera_source_!=AL::kDepthCamera)?AL::kRGBColorSpace:AL::kRawDepthColorSpace ),
00130     msg_colorspace_( (camera_source_!=AL::kDepthCamera)?"rgb8":"16UC1" ),
00131     cv_mat_type_( (camera_source_!=AL::kDepthCamera)?CV_8UC3:CV_16U ),
00132     camera_info_( camera_info_definitions::getCameraInfo(camera_source, resolution) )
00133 {
00134   if ( camera_source == AL::kTopCamera )
00135   {
00136     msg_frameid_ = "CameraTop_optical_frame";
00137   }
00138   else if (camera_source == AL::kBottomCamera )
00139   {
00140     msg_frameid_ = "CameraBottom_optical_frame";
00141   }
00142   else if (camera_source_ == AL::kDepthCamera )
00143   {
00144     msg_frameid_ = "CameraDepth_optical_frame";
00145   }
00146   // Overwrite the parameters for the infrared
00147   else if (camera_source_ == AL::kInfraredCamera )
00148   {
00149     // Reset to kDepth since it's the same device handle
00150     camera_source_ = AL::kDepthCamera;
00151     msg_frameid_ = "CameraDepth_optical_frame";
00152     colorspace_ = AL::kInfraredColorSpace;
00153     msg_colorspace_ = "16UC1";
00154     cv_mat_type_ = CV_16U;
00155     camera_info_ = camera_info_definitions::getCameraInfo(camera_source_, resolution_);
00156   }
00157 }
00158 
00159 CameraConverter::~CameraConverter()
00160 {
00161   if (!handle_.empty())
00162   {
00163     std::cout << "Unsubscribe camera handle " << handle_ << std::endl;
00164     p_video_.call<qi::AnyValue>("unsubscribe", handle_);
00165     handle_.clear();
00166   }
00167 }
00168 
00169 void CameraConverter::reset()
00170 {
00171   if (!handle_.empty())
00172   {
00173     p_video_.call<qi::AnyValue>("unsubscribe", handle_);
00174     handle_.clear();
00175   }
00176 
00177   handle_ = p_video_.call<std::string>(
00178                          "subscribeCamera",
00179                           name_,
00180                           camera_source_,
00181                           resolution_,
00182                           colorspace_,
00183                           frequency_
00184                           );
00185 }
00186 
00187 void CameraConverter::registerCallback( const message_actions::MessageAction action, Callback_t cb )
00188 {
00189   callbacks_[action] = cb;
00190 }
00191 
00192 void CameraConverter::callAll( const std::vector<message_actions::MessageAction>& actions )
00193 {
00194 
00195   if (handle_.empty() )
00196   {
00197     std::cerr << name_ << "Camera Handle is empty - cannot retrieve image" << std::endl;
00198     std::cerr << name_ << "Might be a NAOqi problem. Try to restart the ALVideoDevice." << std::endl;
00199     return;
00200   }
00201 
00202   qi::AnyValue image_anyvalue = p_video_.call<qi::AnyValue>("getImageRemote", handle_);
00203   tools::NaoqiImage image;
00204   try{
00205       image = tools::fromAnyValueToNaoqiImage(image_anyvalue);
00206   }
00207   catch(std::runtime_error& e)
00208   {
00209     std::cout << "Cannot retrieve image" << std::endl;
00210     return;
00211   }
00212 
00213   // Create a cv::Mat of the right dimensions
00214   cv::Mat cv_img(image.height, image.width, cv_mat_type_, image.buffer);
00215   msg_ = cv_bridge::CvImage(std_msgs::Header(), msg_colorspace_, cv_img).toImageMsg();
00216   msg_->header.frame_id = msg_frameid_;
00217 
00218   msg_->header.stamp = ros::Time::now();
00219   //msg_->header.stamp.sec = image.timestamp_s;
00220   //msg_->header.stamp.nsec = image.timestamp_us*1000;
00221   camera_info_.header.stamp = msg_->header.stamp;
00222 
00223   for_each( const message_actions::MessageAction& action, actions )
00224   {
00225     callbacks_[action]( msg_, camera_info_ );
00226   }
00227 }
00228 
00229 } // publisher
00230 } //naoqi


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sun Sep 17 2017 02:57:14