gazebo_ros_triggered_camera.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 
19 
20 #include <float.h>
21 #include <string>
22 
23 #include <gazebo/sensors/Sensor.hh>
24 #include <gazebo/sensors/CameraSensor.hh>
25 #include <gazebo/sensors/SensorTypes.hh>
26 
27 #ifdef ENABLE_PROFILER
28 #include <ignition/common/Profiler.hh>
29 #endif
30 
31 namespace gazebo
32 {
33 
34 // Register this plugin with the simulator
35 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosTriggeredCamera)
36 
37 // Constructor
40 {
41 }
42 
44 // Destructor
46 {
47  ROS_DEBUG_STREAM_NAMED("camera","Unloaded");
48 }
49 
50 void GazeboRosTriggeredCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr _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  CameraPlugin::Load(_parent, _sdf);
61  // copying from CameraPlugin into GazeboRosTriggeredCameraUtils
62  this->parentSensor_ = this->parentSensor;
63  this->width_ = this->width;
64  this->height_ = this->height;
65  this->depth_ = this->depth;
66  this->format_ = this->format;
67  this->camera_ = this->camera;
68 
69  GazeboRosCameraUtils::Load(_parent, _sdf);
70 
71  this->SetCameraEnabled(false);
72  this->preRenderConnection_ =
73  event::Events::ConnectPreRender(
74  std::bind(&GazeboRosTriggeredCamera::PreRender, this));
75 }
76 
77 void GazeboRosTriggeredCamera::Load(sensors::SensorPtr _parent,
78  sdf::ElementPtr _sdf,
79  const std::string &_camera_name_suffix,
80  double _hack_baseline)
81 {
82  GazeboRosCameraUtils::Load(_parent, _sdf, _camera_name_suffix, _hack_baseline);
83 
84  this->SetCameraEnabled(false);
85  this->preRenderConnection_ =
86  event::Events::ConnectPreRender(
87  std::bind(&GazeboRosTriggeredCamera::PreRender, this));
88 }
89 
91 // Update the controller
92 void GazeboRosTriggeredCamera::OnNewFrame(const unsigned char *_image,
93  unsigned int _width, unsigned int _height, unsigned int _depth,
94  const std::string &_format)
95 {
96 #ifdef ENABLE_PROFILER
97  IGN_PROFILE("GazeboRosTriggeredCamera::OnNewFrame");
98 #endif
99  this->sensor_update_time_ = this->parentSensor_->LastMeasurementTime();
100 
101  if ((*this->image_connect_count_) > 0)
102  {
103 #ifdef ENABLE_PROFILER
104  IGN_PROFILE_BEGIN("PutCameraData");
105 #endif
106  this->PutCameraData(_image);
107 #ifdef ENABLE_PROFILER
108  IGN_PROFILE_END();
109  IGN_PROFILE_BEGIN("PublishCameraInfo");
110 #endif
111  this->PublishCameraInfo();
112 #ifdef ENABLE_PROFILER
113  IGN_PROFILE_END();
114 #endif
115  }
116 #ifdef ENABLE_PROFILER
117  IGN_PROFILE_BEGIN("SetCameraEnabled");
118 #endif
119  this->SetCameraEnabled(false);
120 #ifdef ENABLE_PROFILER
121  IGN_PROFILE_END();
122 #endif
123  std::lock_guard<std::mutex> lock(this->mutex);
124  this->triggered = std::max(this->triggered-1, 0);
125 }
126 
128 {
129  std::lock_guard<std::mutex> lock(this->mutex);
130  if (!this->parentSensor_)
131  return;
132  this->triggered++;
133 }
134 
136 {
137  return true;
138 }
139 
141 {
142  std::lock_guard<std::mutex> lock(this->mutex);
143  if (this->triggered > 0)
144  {
145  this->SetCameraEnabled(true);
146  }
147 }
148 
150 {
151  this->parentSensor_->SetActive(_enabled);
152  this->parentSensor_->SetUpdateRate(_enabled ? 0.0 : DBL_MIN);
153 }
154 
155 }
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::GazeboRosCameraUtils::parentSensor_
sensors::SensorPtr parentSensor_
Definition: gazebo_ros_camera_utils.h:193
gazebo
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(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::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::GazeboRosTriggeredCamera::CanTriggerCamera
virtual bool CanTriggerCamera()
Definition: gazebo_ros_triggered_camera.cpp:135
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::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::GazeboRosTriggeredCamera::mutex
std::mutex mutex
Definition: gazebo_ros_triggered_camera.h:71
gazebo::GazeboRosCameraUtils::sensor_update_time_
common::Time sensor_update_time_
Definition: gazebo_ros_camera_utils.h:201
gazebo::GazeboRosTriggeredCamera::PreRender
void PreRender()
Definition: gazebo_ros_triggered_camera.cpp:140
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_triggered_camera.h
gazebo::GazeboRosTriggeredCamera::triggered
int triggered
Definition: gazebo_ros_triggered_camera.h:69
gazebo::GazeboRosTriggeredCamera
Definition: gazebo_ros_triggered_camera.h:32
gazebo::GazeboRosCameraUtils::format_
std::string format_
Definition: gazebo_ros_camera_utils.h:191
gazebo::GazeboRosTriggeredCamera::~GazeboRosTriggeredCamera
~GazeboRosTriggeredCamera()
Destructor.
Definition: gazebo_ros_triggered_camera.cpp:45
gazebo::GazeboRosTriggeredCamera::SetCameraEnabled
void SetCameraEnabled(const bool _enabled)
Definition: gazebo_ros_triggered_camera.cpp:149
gazebo::GazeboRosTriggeredCamera::preRenderConnection_
event::ConnectionPtr preRenderConnection_
Definition: gazebo_ros_triggered_camera.h:63
gazebo::GazeboRosCameraUtils::camera_
rendering::CameraPtr camera_
Definition: gazebo_ros_camera_utils.h:194
gazebo::GazeboRosTriggeredCamera::TriggerCamera
virtual void TriggerCamera()
Definition: gazebo_ros_triggered_camera.cpp:127


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