gazebo_ros_video.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  * Desc: Video plugin for displaying ROS image topics on Ogre textures
20  * Author: Piyush Khandelwal
21  * Date: 26 July 2013
22  */
23 
24 #include <boost/lexical_cast.hpp>
26 #ifdef ENABLE_PROFILER
27 #include <ignition/common/Profiler.hh>
28 #endif
29 
30 namespace gazebo
31 {
32 
34  const std::string &name, rendering::VisualPtr parent,
35  int height, int width) :
36  rendering::Visual(name, parent), height_(height), width_(width)
37  {
38 
39  texture_ = Ogre::TextureManager::getSingleton().createManual(
40  name + "__VideoTexture__",
41  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
42  Ogre::TEX_TYPE_2D,
43  width_, height_,
44  0,
45  Ogre::PF_BYTE_BGRA,
46  Ogre::TU_DYNAMIC_WRITE_ONLY_DISCARDABLE);
47 
48  Ogre::MaterialPtr material =
49  Ogre::MaterialManager::getSingleton().create(
50  name + "__VideoMaterial__", "General");
51  material->getTechnique(0)->getPass(0)->createTextureUnitState(
52  name + "__VideoTexture__");
53  material->setReceiveShadows(false);
54 
55  double factor = 1.0;
56 
57  Ogre::ManualObject mo(name + "__VideoObject__");
58  mo.begin(name + "__VideoMaterial__",
59  Ogre::RenderOperation::OT_TRIANGLE_LIST);
60 
61  mo.position(-factor / 2, factor / 2, 0.51);
62  mo.textureCoord(0, 0);
63 
64  mo.position(factor / 2, factor / 2, 0.51);
65  mo.textureCoord(1, 0);
66 
67  mo.position(factor / 2, -factor / 2, 0.51);
68  mo.textureCoord(1, 1);
69 
70  mo.position(-factor / 2, -factor / 2, 0.51);
71  mo.textureCoord(0, 1);
72 
73  mo.triangle(0, 3, 2);
74  mo.triangle(2, 1, 0);
75  mo.end();
76 
77  mo.convertToMesh(name + "__VideoMesh__");
78 
79  Ogre::MovableObject *obj = (Ogre::MovableObject*)
80  GetSceneNode()->getCreator()->createEntity(
81  name + "__VideoEntity__",
82  name + "__VideoMesh__");
83  obj->setCastShadows(false);
84  AttachObject(obj);
85  }
86 
88 
89  void VideoVisual::render(const cv::Mat& image)
90  {
91 
92  // Fix image size if necessary
93  const cv::Mat* image_ptr = &image;
94  cv::Mat converted_image;
95  if (image_ptr->rows != height_ || image_ptr->cols != width_)
96  {
97  cv::resize(*image_ptr, converted_image, cv::Size(width_, height_));
98  image_ptr = &converted_image;
99  }
100 
101  // Get the pixel buffer
102  Ogre::HardwarePixelBufferSharedPtr pixelBuffer =
103  texture_->getBuffer();
104 
105  // Lock the pixel buffer and get a pixel box
106  pixelBuffer->lock(Ogre::HardwareBuffer::HBL_DISCARD);
107  const Ogre::PixelBox& pixelBox = pixelBuffer->getCurrentLock();
108  uint8_t* pDest = static_cast<uint8_t*>(pixelBox.data);
109 
110  memcpy(pDest, image_ptr->data, height_ * width_ * 4);
111 
112  // Unlock the pixel buffer
113  pixelBuffer->unlock();
114  }
115 
116  // Constructor
118 
119  // Destructor
121  update_connection_.reset();
122 
123  // Custom Callback Queue
124  queue_.clear();
125  queue_.disable();
126  rosnode_->shutdown();
127  callback_queue_thread_.join();
128 
129  delete rosnode_;
130  }
131 
132  // Load the controller
134  rendering::VisualPtr parent, sdf::ElementPtr sdf)
135  {
136 
137  model_ = parent;
138  sdf::ElementPtr p_sdf;
139  if (sdf->HasElement("sdf"))
140  {
141  p_sdf = sdf->GetElement("sdf");
142  }
143  else
144  {
145  p_sdf = sdf;
146  }
147 
148  robot_namespace_ = "";
149  if (!p_sdf->HasElement("robotNamespace"))
150  {
151  ROS_WARN_NAMED("video", "GazeboRosVideo plugin missing <robotNamespace>, "
152  "defaults to \"%s\".", robot_namespace_.c_str());
153  }
154  else
155  {
157  p_sdf->GetElement("robotNamespace")->Get<std::string>();
158  }
159 
160  topic_name_ = "image_raw";
161  if (!p_sdf->HasElement("topicName"))
162  {
163  ROS_WARN_NAMED("video", "GazeboRosVideo Plugin (ns = %s) missing <topicName>, "
164  "defaults to \"%s\".", robot_namespace_.c_str(), topic_name_.c_str());
165  }
166  else
167  {
168  topic_name_ = p_sdf->GetElement("topicName")->Get<std::string>();
169  }
170 
171  int height = 240;
172  if (!p_sdf->HasElement("height")) {
173  ROS_WARN_NAMED("video", "GazeboRosVideo Plugin (ns = %s) missing <height>, "
174  "defaults to %i.", robot_namespace_.c_str(), height);
175  }
176  else
177  {
178  height = p_sdf->GetElement("height")->Get<int>();
179  }
180 
181  int width = 320;
182  if (!p_sdf->HasElement("width")) {
183  ROS_WARN_NAMED("video", "GazeboRosVideo Plugin (ns = %s) missing <width>, "
184  "defaults to %i", robot_namespace_.c_str(), width);
185  }
186  else
187  {
188  width = p_sdf->GetElement("width")->Get<int>();
189  }
190 
191  std::string name = robot_namespace_ + "_visual";
192  video_visual_.reset(
193  new VideoVisual(name, parent, height, width));
194 
195  // Initialize the ROS node for the gazebo client if necessary
196  if (!ros::isInitialized())
197  {
198  int argc = 0;
199  char** argv = NULL;
200  ros::init(argc, argv, "gazebo_client",
202  }
203  std::string gazebo_source =
204  (ros::this_node::getName() == "/gazebo_client") ? "gzclient" : "gzserver";
206 
207  // Subscribe to the image topic
209  ros::SubscribeOptions::create<sensor_msgs::Image>(topic_name_, 1,
210  boost::bind(&GazeboRosVideo::processImage, this, _1),
211  ros::VoidPtr(), &queue_);
213 
214  new_image_available_ = false;
215 
217  boost::thread(boost::bind(&GazeboRosVideo::QueueThread, this));
218 
220  event::Events::ConnectPreRender(
221  boost::bind(&GazeboRosVideo::UpdateChild, this));
222 
223  ROS_INFO_NAMED("video", "GazeboRosVideo (%s, ns = %s) has started",
224  gazebo_source.c_str(), robot_namespace_.c_str());
225  }
226 
227  // Update the controller
229  {
230 #ifdef ENABLE_PROFILER
231  IGN_PROFILE("GazeboRosVideo::UpdateChild");
232 #endif
233  boost::mutex::scoped_lock scoped_lock(m_image_);
235  {
236 #ifdef ENABLE_PROFILER
237  IGN_PROFILE_BEGIN("render");
238 #endif
239  video_visual_->render(image_->image);
240 #ifdef ENABLE_PROFILER
241  IGN_PROFILE_END();
242 #endif
243  }
244  new_image_available_ = false;
245  }
246 
247  void GazeboRosVideo::processImage(const sensor_msgs::ImageConstPtr &msg)
248  {
249  // Get a reference to the image from the image message pointer
250  boost::mutex::scoped_lock scoped_lock(m_image_);
251  // We get image with alpha channel as it allows memcpy onto ogre texture
252  image_ = cv_bridge::toCvCopy(msg, "bgra8");
253  new_image_available_ = true;
254  }
255 
257  {
258  static const double timeout = 0.01;
259  while (rosnode_->ok())
260  {
262  }
263  }
264 
266 }
gazebo::VideoVisual::~VideoVisual
virtual ~VideoVisual()
Definition: gazebo_ros_video.cpp:87
msg
msg
gazebo::GazeboRosVideo::video_visual_
boost::shared_ptr< VideoVisual > video_visual_
Definition: gazebo_ros_video.h:78
gazebo::GazeboRosVideo::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_video.h:93
boost::shared_ptr< void >
gazebo
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
gazebo::GazeboRosVideo::camera_subscriber_
ros::Subscriber camera_subscriber_
Definition: gazebo_ros_video.h:88
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosVideo::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_video.h:76
gazebo::GazeboRosVideo
Definition: gazebo_ros_video.h:59
gazebo::GazeboRosVideo::topic_name_
std::string topic_name_
Definition: gazebo_ros_video.h:90
gazebo::VideoVisual::height_
int height_
Definition: gazebo_ros_video.h:55
gazebo::GazeboRosVideo::QueueThread
void QueueThread()
Definition: gazebo_ros_video.cpp:256
gazebo::GazeboRosVideo::GazeboRosVideo
GazeboRosVideo()
Definition: gazebo_ros_video.cpp:117
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
gazebo_ros_video.h
gazebo::GazeboRosVideo::image_
cv_bridge::CvImagePtr image_
Definition: gazebo_ros_video.h:80
gazebo::GazeboRosVideo::robot_namespace_
std::string robot_namespace_
Definition: gazebo_ros_video.h:89
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::VideoVisual::render
void render(const cv::Mat &image)
Definition: gazebo_ros_video.cpp:89
gazebo::VideoVisual
Definition: gazebo_ros_video.h:45
gazebo::GazeboRosVideo::model_
rendering::VisualPtr model_
Definition: gazebo_ros_video.h:74
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
gazebo::GazeboRosVideo::processImage
void processImage(const sensor_msgs::ImageConstPtr &msg)
Definition: gazebo_ros_video.cpp:247
gazebo::GazeboRosVideo::new_image_available_
bool new_image_available_
Definition: gazebo_ros_video.h:82
gazebo::GazeboRosVideo::~GazeboRosVideo
virtual ~GazeboRosVideo()
Definition: gazebo_ros_video.cpp:120
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
ros::NodeHandle::ok
bool ok() const
ros::SubscribeOptions
gazebo::GazeboRosVideo::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_video.h:92
gazebo::GazeboRosVideo::Load
void Load(rendering::VisualPtr parent, sdf::ElementPtr sdf)
Definition: gazebo_ros_video.cpp:133
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosVideo::m_image_
boost::mutex m_image_
Definition: gazebo_ros_video.h:81
ros::WallDuration
ros::NodeHandle::shutdown
void shutdown()
gazebo::GZ_REGISTER_VISUAL_PLUGIN
GZ_REGISTER_VISUAL_PLUGIN(GazeboRosVideo)
gazebo::VideoVisual::texture_
Ogre::TexturePtr texture_
Definition: gazebo_ros_video.h:54
gazebo::GazeboRosVideo::UpdateChild
virtual void UpdateChild()
Definition: gazebo_ros_video.cpp:228
gazebo::VideoVisual::VideoVisual
VideoVisual(const std::string &name, rendering::VisualPtr parent, int height, int width)
Definition: gazebo_ros_video.cpp:33
ros::init_options::NoSigintHandler
NoSigintHandler
ros::CallbackQueue::callAvailable
void callAvailable()
gazebo::GazeboRosVideo::rosnode_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition: gazebo_ros_video.h:85
ros::CallbackQueue::disable
void disable()
gazebo::VideoVisual::width_
int width_
Definition: gazebo_ros_video.h:56
ros::NodeHandle


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