pxmlw6n2f/Gazebo_Distributed_MPI/plugins/CameraPlugin.cc

92 lines
2.8 KiB
C++
Raw Normal View History

2019-04-18 10:27:54 +08:00
/*
* Copyright (C) 2012 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifdef _WIN32
// Ensure that Winsock2.h is included before Windows.h, which can get
// pulled in by anybody (e.g., Boost).
#include <Winsock2.h>
#endif
#include "gazebo/sensors/DepthCameraSensor.hh"
#include "plugins/CameraPlugin.hh"
using namespace gazebo;
GZ_REGISTER_SENSOR_PLUGIN(CameraPlugin)
/////////////////////////////////////////////////
CameraPlugin::CameraPlugin()
: SensorPlugin(), width(0), height(0), depth(0)
{
}
/////////////////////////////////////////////////
CameraPlugin::~CameraPlugin()
{
this->newFrameConnection.reset();
this->parentSensor.reset();
this->camera.reset();
}
/////////////////////////////////////////////////
void CameraPlugin::Load(sensors::SensorPtr _sensor, sdf::ElementPtr /*_sdf*/)
{
if (!_sensor)
gzerr << "Invalid sensor pointer.\n";
this->parentSensor =
std::dynamic_pointer_cast<sensors::CameraSensor>(_sensor);
if (!this->parentSensor)
{
gzerr << "CameraPlugin requires a CameraSensor.\n";
if (std::dynamic_pointer_cast<sensors::DepthCameraSensor>(_sensor))
gzmsg << "It is a depth camera sensor\n";
}
this->camera = this->parentSensor->Camera();
if (!this->parentSensor)
{
gzerr << "CameraPlugin not attached to a camera sensor\n";
return;
}
this->width = this->camera->ImageWidth();
this->height = this->camera->ImageHeight();
this->depth = this->camera->ImageDepth();
this->format = this->camera->ImageFormat();
this->newFrameConnection = this->camera->ConnectNewImageFrame(
std::bind(&CameraPlugin::OnNewFrame, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
std::placeholders::_4, std::placeholders::_5));
this->parentSensor->SetActive(true);
}
/////////////////////////////////////////////////
void CameraPlugin::OnNewFrame(const unsigned char * /*_image*/,
unsigned int /*_width*/,
unsigned int /*_height*/,
unsigned int /*_depth*/,
const std::string &/*_format*/)
{
/*rendering::Camera::SaveFrame(_image, this->width,
this->height, this->depth, this->format,
"/tmp/camera/me.jpg");
*/
}