CameraNode.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <ros/ros.h>
00029 #include <sensor_msgs/Image.h>
00030 #include <sensor_msgs/image_encodings.h>
00031 #include <cv_bridge/cv_bridge.h>
00032 #include <std_msgs/Empty.h>
00033 #include <image_transport/image_transport.h>
00034 #include <std_srvs/Empty.h>
00035 
00036 #include <rtabmap/core/Camera.h>
00037 #include <rtabmap/core/CameraThread.h>
00038 #include <rtabmap/core/CameraEvent.h>
00039 
00040 #include <rtabmap/utilite/ULogger.h>
00041 #include <rtabmap/utilite/UEventsHandler.h>
00042 #include <rtabmap/utilite/UEventsManager.h>
00043 #include <rtabmap/utilite/UDirectory.h>
00044 #include <rtabmap/utilite/UFile.h>
00045 
00046 #include <dynamic_reconfigure/server.h>
00047 #include <rtabmap_ros/CameraConfig.h>
00048 
00049 class CameraWrapper : public UEventsHandler
00050 {
00051 public:
00052         // Usb device like a Webcam
00053         CameraWrapper(int usbDevice = 0,
00054                               float imageRate = 0,
00055                                   unsigned int imageWidth = 0,
00056                                   unsigned int imageHeight = 0) :
00057                 cameraThread_(0),
00058                 frameId_("camera")
00059         {
00060                 ros::NodeHandle nh;
00061                 ros::NodeHandle pnh("~");
00062                 pnh.param("frame_id", frameId_, frameId_);
00063                 image_transport::ImageTransport it(nh);
00064                 rosPublisher_ = it.advertise("image", 1);
00065                 startSrv_ = nh.advertiseService("start_camera", &CameraWrapper::startSrv, this);
00066                 stopSrv_ = nh.advertiseService("stop_camera", &CameraWrapper::stopSrv, this);
00067                 UEventsManager::addHandler(this);
00068         }
00069 
00070         virtual ~CameraWrapper()
00071         {
00072                 if(cameraThread_)
00073                 {
00074                         cameraThread_->join(true);
00075                         delete cameraThread_;
00076                 }
00077         }
00078 
00079         bool init()
00080         {
00081                 if(cameraThread_)
00082                 {
00083                         return cameraThread_->init();
00084                 }
00085                 return false;
00086         }
00087 
00088         void start()
00089         {
00090                 if(cameraThread_)
00091                 {
00092                         return cameraThread_->start();
00093                 }
00094         }
00095 
00096         bool startSrv(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00097         {
00098                 ROS_INFO("Camera started...");
00099                 if(cameraThread_)
00100                 {
00101                         cameraThread_->start();
00102                 }
00103                 return true;
00104         }
00105 
00106         bool stopSrv(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00107         {
00108                 ROS_INFO("Camera stopped...");
00109                 if(cameraThread_)
00110                 {
00111                         cameraThread_->kill();
00112                 }
00113                 return true;
00114         }
00115 
00116         void setParameters(int deviceId, double frameRate, int width, int height, const std::string & path, bool pause)
00117         {
00118                 ROS_INFO("Parameters changed: deviceId=%d, path=%s frameRate=%f w/h=%d/%d pause=%s",
00119                                 deviceId, path.c_str(), frameRate, width, height, pause?"true":"false");
00120                 if(cameraThread_)
00121                 {
00122                         rtabmap::CameraVideo * videoCam = dynamic_cast<rtabmap::CameraVideo *>(camera_);
00123                         rtabmap::CameraImages * imagesCam = dynamic_cast<rtabmap::CameraImages *>(camera_);
00124 
00125                         if(imagesCam)
00126                         {
00127                                 // images
00128                                 if(!path.empty() && UDirectory::getDir(path+"/").compare(UDirectory::getDir(imagesCam->getPath())) == 0)
00129                                 {
00130                                         imagesCam->setImageRate(frameRate);
00131                                         imagesCam->setImageSize(width, height);
00132                                         if(pause && !cameraThread_->isPaused())
00133                                         {
00134                                                 cameraThread_->join(true);
00135                                         }
00136                                         else if(!pause && cameraThread_->isPaused())
00137                                         {
00138                                                 cameraThread_->start();
00139                                         }
00140                                 }
00141                                 else
00142                                 {
00143                                         delete cameraThread_;
00144                                         cameraThread_ = 0;
00145                                 }
00146                         }
00147                         else if(videoCam)
00148                         {
00149                                 if(!path.empty() && path.compare(videoCam->getFilePath()) == 0)
00150                                 {
00151                                         // video
00152                                         videoCam->setImageRate(frameRate);
00153                                         videoCam->setImageSize(width, height);
00154                                         if(pause && !cameraThread_->isPaused())
00155                                         {
00156                                                 cameraThread_->join(true);
00157                                         }
00158                                         else if(!pause && cameraThread_->isPaused())
00159                                         {
00160                                                 cameraThread_->start();
00161                                         }
00162                                 }
00163                                 else if(path.empty() &&
00164                                                 videoCam->getFilePath().empty() &&
00165                                                 videoCam->getUsbDevice() == deviceId)
00166                                 {
00167                                         // usb device
00168                                         unsigned int w;
00169                                         unsigned int h;
00170                                         videoCam->getImageSize(w, h);
00171                                         if((int)w == width && (int)h == height)
00172                                         {
00173                                                 videoCam->setImageRate(frameRate);
00174                                                 if(pause && !cameraThread_->isPaused())
00175                                                 {
00176                                                         cameraThread_->join(true);
00177                                                 }
00178                                                 else if(!pause && cameraThread_->isPaused())
00179                                                 {
00180                                                         cameraThread_->start();
00181                                                 }
00182                                         }
00183                                         else
00184                                         {
00185                                                 delete cameraThread_;
00186                                                 cameraThread_ = 0;
00187                                         }
00188                                 }
00189                                 else
00190                                 {
00191                                         delete cameraThread_;
00192                                         cameraThread_ = 0;
00193                                 }
00194                         }
00195                         else
00196                         {
00197                                 ROS_ERROR("Wrong camera type ?!?");
00198                                 delete cameraThread_;
00199                                 cameraThread_ = 0;
00200                         }
00201                 }
00202 
00203                 if(!cameraThread_)
00204                 {
00205                         if(!path.empty() && UDirectory::exists(path))
00206                         {
00207                                 //images
00208                                 camera_ = new rtabmap::CameraImages(path, 1, false, frameRate, width, height);
00209                         }
00210                         else if(!path.empty() && UFile::exists(path))
00211                         {
00212                                 //video
00213                                 camera_ = new rtabmap::CameraVideo(path, frameRate, width, height);
00214                         }
00215                         else
00216                         {
00217                                 if(!path.empty() && !UDirectory::exists(path) && !UFile::exists(path))
00218                                 {
00219                                         ROS_ERROR("Path \"%s\" does not exist (or you don't have the permissions to read)... falling back to usb device...", path.c_str());
00220                                 }
00221                                 //usb device
00222                                 camera_ = new rtabmap::CameraVideo(deviceId, frameRate, width, height);
00223                         }
00224                         cameraThread_ = new rtabmap::CameraThread(camera_);
00225                         init();
00226                         if(!pause)
00227                         {
00228                                 start();
00229                         }
00230                 }
00231         }
00232 
00233 protected:
00234         virtual void handleEvent(UEvent * event)
00235         {
00236                 if(event->getClassName().compare("CameraEvent") == 0)
00237                 {
00238                         rtabmap::CameraEvent * e = (rtabmap::CameraEvent*)event;
00239                         const cv::Mat & image = e->data().image();
00240                         if(!image.empty() && image.depth() == CV_8U)
00241                         {
00242                                 cv_bridge::CvImage img;
00243                                 if(image.channels() == 1)
00244                                 {
00245                                         img.encoding = sensor_msgs::image_encodings::MONO8;
00246                                 }
00247                                 else
00248                                 {
00249                                         img.encoding = sensor_msgs::image_encodings::BGR8;
00250                                 }
00251                                 img.image = image;
00252                                 sensor_msgs::ImagePtr rosMsg = img.toImageMsg();
00253                                 rosMsg->header.frame_id = frameId_;
00254                                 rosMsg->header.stamp = ros::Time::now();
00255                                 rosPublisher_.publish(rosMsg);
00256                         }
00257                 }
00258         }
00259 
00260 private:
00261         image_transport::Publisher rosPublisher_;
00262         rtabmap::CameraThread * cameraThread_;
00263         rtabmap::Camera * camera_;
00264         ros::ServiceServer startSrv_;
00265         ros::ServiceServer stopSrv_;
00266         std::string frameId_;
00267 };
00268 
00269 CameraWrapper * camera = 0;
00270 void callback(rtabmap_ros::CameraConfig &config, uint32_t level)
00271 {
00272         if(camera)
00273         {
00274                 camera->setParameters(config.device_id, config.frame_rate, config.width, config.height, config.video_or_images_path, config.pause);
00275         }
00276 }
00277 
00278 int main(int argc, char** argv)
00279 {
00280         ULogger::setType(ULogger::kTypeConsole);
00281         //ULogger::setLevel(ULogger::kDebug);
00282         ULogger::setEventLevel(ULogger::kWarning);
00283 
00284         ros::init(argc, argv, "camera");
00285 
00286         ros::NodeHandle nh("~");
00287 
00288         camera = new CameraWrapper(); // webcam device 0
00289 
00290         dynamic_reconfigure::Server<rtabmap_ros::CameraConfig> server;
00291         dynamic_reconfigure::Server<rtabmap_ros::CameraConfig>::CallbackType f;
00292         f = boost::bind(&callback, _1, _2);
00293         server.setCallback(f);
00294 
00295         ros::spin();
00296 
00297         //cleanup
00298         if(camera)
00299         {
00300                 delete camera;
00301         }
00302 
00303         return 0;
00304 }


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:24