gazebo_ros_camera.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2013 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 /*
19  @mainpage
20  Desc: GazeboRosCamera plugin for simulating cameras in Gazebo
21  Author: John Hsu
22  Date: 24 Sept 2008
23 */
24 
26 
27 #include <string>
28 
29 #include <gazebo/sensors/Sensor.hh>
30 #include <gazebo/sensors/CameraSensor.hh>
31 #include <gazebo/sensors/SensorTypes.hh>
32 
33 #ifdef ENABLE_PROFILER
34 #include <ignition/common/Profiler.hh>
35 #endif
36 
37 namespace gazebo
38 {
39 // Register this plugin with the simulator
40 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosCamera)
41 
42 // Constructor
45 {
46 }
47 
49 // Destructor
51 {
52  ROS_DEBUG_STREAM_NAMED("camera","Unloaded");
53 }
54 
55 void GazeboRosCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
56 {
57  // Make sure the ROS node for Gazebo has already been initialized
58  if (!ros::isInitialized())
59  {
60  ROS_FATAL_STREAM_NAMED("camera", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
61  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
62  return;
63  }
64 
65  CameraPlugin::Load(_parent, _sdf);
66  // copying from CameraPlugin into GazeboRosCameraUtils
67  this->parentSensor_ = this->parentSensor;
68  this->width_ = this->width;
69  this->height_ = this->height;
70  this->depth_ = this->depth;
71  this->format_ = this->format;
72  this->camera_ = this->camera;
73 
74  GazeboRosCameraUtils::Load(_parent, _sdf);
75 }
76 
78 // Update the controller
79 void GazeboRosCamera::OnNewFrame(const unsigned char *_image,
80  unsigned int _width, unsigned int _height, unsigned int _depth,
81  const std::string &_format)
82 {
83 #ifdef ENABLE_PROFILER
84  IGN_PROFILE("GazeboRosCamera::OnNewFrame");
85 #endif
86 
87 # if GAZEBO_MAJOR_VERSION >= 7
88  common::Time sensor_update_time = this->parentSensor_->LastMeasurementTime();
89 # else
90  common::Time sensor_update_time = this->parentSensor_->GetLastMeasurementTime();
91 # endif
92 
93  if (!this->parentSensor->IsActive())
94  {
95  if ((*this->image_connect_count_) > 0)
96  // do this first so there's chance for sensor to run once after activated
97  this->parentSensor->SetActive(true);
98  }
99  else
100  {
101  if ((*this->image_connect_count_) > 0)
102  {
103  if (sensor_update_time < this->last_update_time_)
104  {
105  ROS_WARN_NAMED("camera", "Negative sensor update time difference detected.");
106  this->last_update_time_ = sensor_update_time;
107  }
108 
109  // OnNewFrame is triggered at the gazebo sensor <update_rate>
110  // while there is also a plugin <updateRate> that can throttle the
111  // rate down further (but then why not reduce the sensor rate?
112  // what is the use case?).
113  // Setting the <updateRate> to zero will make this plugin
114  // update at the gazebo sensor <update_rate>, update_period_ will be
115  // zero and the conditional always will be true.
116  if (sensor_update_time - this->last_update_time_ >= this->update_period_)
117  {
118 #ifdef ENABLE_PROFILER
119  IGN_PROFILE_BEGIN("PutCameraData");
120 #endif
121  this->PutCameraData(_image, sensor_update_time);
122 #ifdef ENABLE_PROFILER
123  IGN_PROFILE_END();
124  IGN_PROFILE_BEGIN("PublishCameraInfo");
125 #endif
126  this->PublishCameraInfo(sensor_update_time);
127 #ifdef ENABLE_PROFILER
128  IGN_PROFILE_END();
129 #endif
130  this->last_update_time_ = sensor_update_time;
131  }
132  }
133  }
134 }
135 }
gazebo::GazeboRosCameraUtils::parentSensor_
sensors::SensorPtr parentSensor_
Definition: gazebo_ros_camera_utils.h:193
gazebo
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
gazebo::GazeboRosCameraUtils::PutCameraData
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
Definition: gazebo_ros_camera_utils.cpp:639
gazebo::GazeboRosCameraUtils::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_camera_utils.h:146
gazebo::GazeboRosCameraUtils::width_
unsigned int width_
Definition: gazebo_ros_camera_utils.h:190
gazebo::GazeboRosCameraUtils::height_
unsigned int height_
Definition: gazebo_ros_camera_utils.h:190
gazebo::GazeboRosCameraUtils::PublishCameraInfo
void PublishCameraInfo()
Definition: gazebo_ros_camera_utils.cpp:674
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
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::GazeboRosCameraUtils::update_period_
double update_period_
Definition: gazebo_ros_camera_utils.h:145
gazebo::GazeboRosCameraUtils::depth_
unsigned int depth_
Definition: gazebo_ros_camera_utils.h:190
gazebo::GazeboRosCameraUtils::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
Load the plugin.
Definition: gazebo_ros_camera_utils.cpp:104
gazebo_ros_camera.h
gazebo::GazeboRosCamera
Definition: gazebo_ros_camera.h:34
gazebo::GazeboRosCamera::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_camera.cpp:55
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosCameraUtils::format_
std::string format_
Definition: gazebo_ros_camera_utils.h:191
gazebo::GazeboRosCamera::~GazeboRosCamera
~GazeboRosCamera()
Destructor.
Definition: gazebo_ros_camera.cpp:50
gazebo::GazeboRosCameraUtils::camera_
rendering::CameraPtr camera_
Definition: gazebo_ros_camera_utils.h:194
gazebo::GazeboRosCamera::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_camera.cpp:79


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55