24 #include <boost/lexical_cast.hpp>
26 #ifdef ENABLE_PROFILER
27 #include <ignition/common/Profiler.hh>
34 const std::string &name, rendering::VisualPtr parent,
35 int height,
int width) :
36 rendering::Visual(name, parent), height_(height), width_(width)
39 texture_ = Ogre::TextureManager::getSingleton().createManual(
40 name +
"__VideoTexture__",
41 Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
46 Ogre::TU_DYNAMIC_WRITE_ONLY_DISCARDABLE);
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);
57 Ogre::ManualObject mo(name +
"__VideoObject__");
58 mo.begin(name +
"__VideoMaterial__",
59 Ogre::RenderOperation::OT_TRIANGLE_LIST);
61 mo.position(-factor / 2, factor / 2, 0.51);
62 mo.textureCoord(0, 0);
64 mo.position(factor / 2, factor / 2, 0.51);
65 mo.textureCoord(1, 0);
67 mo.position(factor / 2, -factor / 2, 0.51);
68 mo.textureCoord(1, 1);
70 mo.position(-factor / 2, -factor / 2, 0.51);
71 mo.textureCoord(0, 1);
77 mo.convertToMesh(name +
"__VideoMesh__");
79 Ogre::MovableObject *obj = (Ogre::MovableObject*)
80 GetSceneNode()->getCreator()->createEntity(
81 name +
"__VideoEntity__",
82 name +
"__VideoMesh__");
83 obj->setCastShadows(
false);
93 const cv::Mat* image_ptr = ℑ
94 cv::Mat converted_image;
97 cv::resize(*image_ptr, converted_image, cv::Size(
width_,
height_));
98 image_ptr = &converted_image;
102 Ogre::HardwarePixelBufferSharedPtr pixelBuffer =
106 pixelBuffer->lock(Ogre::HardwareBuffer::HBL_DISCARD);
107 const Ogre::PixelBox& pixelBox = pixelBuffer->getCurrentLock();
108 uint8_t* pDest =
static_cast<uint8_t*
>(pixelBox.data);
113 pixelBuffer->unlock();
134 rendering::VisualPtr parent, sdf::ElementPtr sdf)
138 sdf::ElementPtr p_sdf;
139 if (sdf->HasElement(
"sdf"))
141 p_sdf = sdf->GetElement(
"sdf");
149 if (!p_sdf->HasElement(
"robotNamespace"))
151 ROS_WARN_NAMED(
"video",
"GazeboRosVideo plugin missing <robotNamespace>, "
157 p_sdf->GetElement(
"robotNamespace")->Get<std::string>();
161 if (!p_sdf->HasElement(
"topicName"))
163 ROS_WARN_NAMED(
"video",
"GazeboRosVideo Plugin (ns = %s) missing <topicName>, "
168 topic_name_ = p_sdf->GetElement(
"topicName")->Get<std::string>();
172 if (!p_sdf->HasElement(
"height")) {
173 ROS_WARN_NAMED(
"video",
"GazeboRosVideo Plugin (ns = %s) missing <height>, "
178 height = p_sdf->GetElement(
"height")->Get<
int>();
182 if (!p_sdf->HasElement(
"width")) {
183 ROS_WARN_NAMED(
"video",
"GazeboRosVideo Plugin (ns = %s) missing <width>, "
188 width = p_sdf->GetElement(
"width")->Get<
int>();
203 std::string gazebo_source =
209 ros::SubscribeOptions::create<sensor_msgs::Image>(
topic_name_, 1,
220 event::Events::ConnectPreRender(
223 ROS_INFO_NAMED(
"video",
"GazeboRosVideo (%s, ns = %s) has started",
230 #ifdef ENABLE_PROFILER
231 IGN_PROFILE(
"GazeboRosVideo::UpdateChild");
233 boost::mutex::scoped_lock scoped_lock(
m_image_);
236 #ifdef ENABLE_PROFILER
237 IGN_PROFILE_BEGIN(
"render");
240 #ifdef ENABLE_PROFILER
250 boost::mutex::scoped_lock scoped_lock(
m_image_);
258 static const double timeout = 0.01;