gazebo_ros_triggered_multicamera.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include <string>
19 
20 #include <gazebo/sensors/Sensor.hh>
21 #include <gazebo/sensors/MultiCameraSensor.hh>
22 #include <gazebo/sensors/SensorTypes.hh>
23 
25 
26 #ifdef ENABLE_PROFILER
27 #include <ignition/common/Profiler.hh>
28 #endif
29 
30 namespace gazebo
31 {
32 // Register this plugin with the simulator
33 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosTriggeredMultiCamera)
34 
35 // Constructor
38 {
39 }
40 
42 // Destructor
44 {
45 }
46 
47 void GazeboRosTriggeredMultiCamera::Load(sensors::SensorPtr _parent,
48  sdf::ElementPtr _sdf)
49 {
50  MultiCameraPlugin::Load(_parent, _sdf);
51 
52  // Make sure the ROS node for Gazebo has already been initialized
53  if (!ros::isInitialized())
54  {
55  ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
56  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
57  return;
58  }
59 
60  // initialize shared_ptr members
61  this->image_connect_count_ = boost::shared_ptr<int>(new int(0));
63  this->was_active_ = boost::shared_ptr<bool>(new bool(false));
64 
65  // copying from CameraPlugin into GazeboRosCameraUtils
66  for (unsigned i = 0; i < this->camera.size(); ++i)
67  {
69  cam->parentSensor_ = this->parentSensor;
70  cam->width_ = this->width[i];
71  cam->height_ = this->height[i];
72  cam->depth_ = this->depth[i];
73  cam->format_ = this->format[i];
74  cam->camera_ = this->camera[i];
75  // Set up a shared connection counter
78  cam->was_active_ = this->was_active_;
79  if (this->camera[i]->Name().find("left") != std::string::npos)
80  {
81  // FIXME: hardcoded, left hack_baseline_ 0
82  cam->Load(_parent, _sdf, "/left", 0.0);
83  }
84  else if (this->camera[i]->Name().find("right") != std::string::npos)
85  {
86  double hackBaseline = 0.0;
87  if (_sdf->HasElement("hackBaseline"))
88  hackBaseline = _sdf->Get<double>("hackBaseline");
89  cam->Load(_parent, _sdf, "/right", hackBaseline);
90  }
91  this->triggered_cameras.push_back(cam);
92  }
93 }
94 
96 // Update the controller
97 void GazeboRosTriggeredMultiCamera::OnNewFrameLeft(const unsigned char *_image,
98  unsigned int _width, unsigned int _height, unsigned int _depth,
99  const std::string &_format)
100 {
101 #ifdef ENABLE_PROFILER
102  IGN_PROFILE("GazeboRosTriggeredMultiCamera::OnNewFrameLeft");
103 #endif
105 #ifdef ENABLE_PROFILER
106  IGN_PROFILE_BEGIN("OnNewFrame");
107 #endif
108  cam->OnNewFrame(_image, _width, _height, _depth, _format);
109 #ifdef ENABLE_PROFILER
110  IGN_PROFILE_END();
111 #endif
112 }
113 
115 // Update the controller
116 void GazeboRosTriggeredMultiCamera::OnNewFrameRight(const unsigned char *_image,
117  unsigned int _width, unsigned int _height, unsigned int _depth,
118  const std::string &_format)
119 {
120 #ifdef ENABLE_PROFILER
121  IGN_PROFILE("GazeboRosTriggeredMultiCamera::OnNewFrameRight");
122 #endif
124 #ifdef ENABLE_PROFILER
125  IGN_PROFILE_BEGIN("OnNewFrame");
126 #endif
127  cam->OnNewFrame(_image, _width, _height, _depth, _format);
128 #ifdef ENABLE_PROFILER
129  IGN_PROFILE_END();
130 #endif
131 }
132 }
gazebo::MultiCameraPlugin::Load
virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
Definition: MultiCameraPlugin.cpp:38
gazebo::GazeboRosTriggeredCamera::OnNewFrame
virtual void OnNewFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
Definition: gazebo_ros_triggered_camera.cpp:92
gazebo::GazeboRosTriggeredMultiCamera
Definition: gazebo_ros_triggered_multicamera.h:30
boost::shared_ptr< int >
gazebo::GazeboRosCameraUtils::parentSensor_
sensors::SensorPtr parentSensor_
Definition: gazebo_ros_camera_utils.h:193
gazebo
gazebo::GazeboRosTriggeredMultiCamera::was_active_
boost::shared_ptr< bool > was_active_
Definition: gazebo_ros_triggered_multicamera.h:59
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
gazebo::MultiCameraPlugin::width
std::vector< unsigned int > width
Definition: MultiCameraPlugin.h:48
gazebo::MultiCameraPlugin::depth
std::vector< unsigned int > depth
Definition: MultiCameraPlugin.h:48
gazebo::GazeboRosTriggeredMultiCamera::OnNewFrameRight
virtual void OnNewFrameRight(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Definition: gazebo_ros_triggered_multicamera.cpp:116
gazebo::GazeboRosCameraUtils::width_
unsigned int width_
Definition: gazebo_ros_camera_utils.h:190
gazebo::GazeboRosTriggeredCamera::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_triggered_camera.cpp:50
gazebo::MultiCameraPlugin::parentSensor
sensors::MultiCameraSensorPtr parentSensor
Definition: MultiCameraPlugin.h:46
gazebo::GazeboRosTriggeredMultiCamera::OnNewFrameLeft
virtual void OnNewFrameLeft(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller FIXME: switch to function vectors.
Definition: gazebo_ros_triggered_multicamera.cpp:97
gazebo::GazeboRosCameraUtils::image_connect_count_lock_
boost::shared_ptr< boost::mutex > image_connect_count_lock_
A mutex to lock access to image_connect_count_.
Definition: gazebo_ros_camera_utils.h:94
gazebo::GazeboRosCameraUtils::height_
unsigned int height_
Definition: gazebo_ros_camera_utils.h:190
gazebo::MultiCameraPlugin::camera
std::vector< rendering::CameraPtr > camera
Definition: MultiCameraPlugin.h:51
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosCameraUtils::image_connect_count_
boost::shared_ptr< int > image_connect_count_
Keep track of number of image connections.
Definition: gazebo_ros_camera_utils.h:92
gazebo_ros_triggered_multicamera.h
gazebo::GazeboRosCameraUtils::depth_
unsigned int depth_
Definition: gazebo_ros_camera_utils.h:190
gazebo::GazeboRosTriggeredMultiCamera::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_triggered_multicamera.cpp:47
gazebo::GazeboRosTriggeredMultiCamera::~GazeboRosTriggeredMultiCamera
~GazeboRosTriggeredMultiCamera()
Destructor.
Definition: gazebo_ros_triggered_multicamera.cpp:43
gazebo::GazeboRosCameraUtils::was_active_
boost::shared_ptr< bool > was_active_
Keep track when we activate this camera through ros subscription, was it already active?...
Definition: gazebo_ros_camera_utils.h:101
gazebo::GazeboRosTriggeredCamera
Definition: gazebo_ros_triggered_camera.h:32
gazebo::MultiCameraPlugin::format
std::vector< std::string > format
Definition: MultiCameraPlugin.h:49
gazebo::GazeboRosTriggeredMultiCamera::triggered_cameras
std::vector< GazeboRosTriggeredCamera * > triggered_cameras
Definition: gazebo_ros_triggered_multicamera.h:43
gazebo::GazeboRosCameraUtils::format_
std::string format_
Definition: gazebo_ros_camera_utils.h:191
gazebo::MultiCameraPlugin::height
std::vector< unsigned int > height
Definition: MultiCameraPlugin.h:48
gazebo::GazeboRosCameraUtils::camera_
rendering::CameraPtr camera_
Definition: gazebo_ros_camera_utils.h:194
gazebo::GazeboRosTriggeredMultiCamera::image_connect_count_
boost::shared_ptr< int > image_connect_count_
Definition: gazebo_ros_triggered_multicamera.h:57
gazebo::GazeboRosTriggeredMultiCamera::image_connect_count_lock_
boost::shared_ptr< boost::mutex > image_connect_count_lock_
Definition: gazebo_ros_triggered_multicamera.h:58


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28