MultiCameraPlugin.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2013 Open Source Robotics Foundation
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 #include <gazebo/sensors/DepthCameraSensor.hh>
00018 #include <gazebo/sensors/CameraSensor.hh>
00019 #include <gazebo_plugins/MultiCameraPlugin.h>
00020 
00021 using namespace gazebo;
00022 GZ_REGISTER_SENSOR_PLUGIN(MultiCameraPlugin)
00023 
00024 
00025 MultiCameraPlugin::MultiCameraPlugin() : SensorPlugin()
00026 {
00027 }
00028 
00030 MultiCameraPlugin::~MultiCameraPlugin()
00031 {
00032   this->parentSensor.reset();
00033   this->camera.clear();
00034 }
00035 
00037 void MultiCameraPlugin::Load(sensors::SensorPtr _sensor,
00038   sdf::ElementPtr /*_sdf*/)
00039 {
00040   if (!_sensor)
00041     gzerr << "Invalid sensor pointer.\n";
00042 
00043   this->parentSensor =
00044     boost::dynamic_pointer_cast<sensors::MultiCameraSensor>(_sensor);
00045 
00046   if (!this->parentSensor)
00047   {
00048     gzerr << "MultiCameraPlugin requires a CameraSensor.\n";
00049     if (boost::dynamic_pointer_cast<sensors::DepthCameraSensor>(_sensor))
00050       gzmsg << "It is a depth camera sensor\n";
00051     if (boost::dynamic_pointer_cast<sensors::CameraSensor>(_sensor))
00052       gzmsg << "It is a camera sensor\n";
00053   }
00054 
00055   if (!this->parentSensor)
00056   {
00057     gzerr << "MultiCameraPlugin not attached to a camera sensor\n";
00058     return;
00059   }
00060 
00061   for (unsigned int i = 0; i < this->parentSensor->GetCameraCount(); ++i)
00062   {
00063     this->camera.push_back(this->parentSensor->GetCamera(i));
00064 
00065     // save camera attributes
00066     this->width.push_back(this->camera[i]->GetImageWidth());
00067     this->height.push_back(this->camera[i]->GetImageHeight());
00068     this->depth.push_back(this->camera[i]->GetImageDepth());
00069     this->format.push_back(this->camera[i]->GetImageFormat());
00070 
00071     std::string cameraName = this->parentSensor->GetCamera(i)->GetName();
00072     // gzdbg << "camera(" << i << ") name [" << cameraName << "]\n";
00073 
00074     // FIXME: hardcoded 2 camera support only
00075     if (cameraName.find("left") != std::string::npos)
00076     {
00077       this->newFrameConnection.push_back(this->camera[i]->ConnectNewImageFrame(
00078         boost::bind(&MultiCameraPlugin::OnNewFrameLeft,
00079         this, _1, _2, _3, _4, _5)));
00080     }
00081     else if (cameraName.find("right") != std::string::npos)
00082     {
00083       this->newFrameConnection.push_back(this->camera[i]->ConnectNewImageFrame(
00084         boost::bind(&MultiCameraPlugin::OnNewFrameRight,
00085         this, _1, _2, _3, _4, _5)));
00086     }
00087   }
00088 
00089   this->parentSensor->SetActive(true);
00090 }
00091 
00093 void MultiCameraPlugin::OnNewFrameLeft(const unsigned char * /*_image*/,
00094                               unsigned int /*_width*/,
00095                               unsigned int /*_height*/,
00096                               unsigned int /*_depth*/,
00097                               const std::string &/*_format*/)
00098 {
00099   /*rendering::Camera::SaveFrame(_image, this->width,
00100     this->height, this->depth, this->format,
00101     "/tmp/camera/me.jpg");
00102     */
00103 }
00104 
00106 void MultiCameraPlugin::OnNewFrameRight(const unsigned char * /*_image*/,
00107                               unsigned int /*_width*/,
00108                               unsigned int /*_height*/,
00109                               unsigned int /*_depth*/,
00110                               const std::string &/*_format*/)
00111 {
00112   /*rendering::Camera::SaveFrame(_image, this->width,
00113     this->height, this->depth, this->format,
00114     "/tmp/camera/me.jpg");
00115     */
00116 }


gazebo_plugins
Author(s): John Hsu
autogenerated on Fri Aug 28 2015 10:47:25