gazebo_ros_projector.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: GazeboRosTextureProjector plugin that controls texture projection
20  Author: Jared Duke
21  Date: 17 Jun 2010
22  */
23 
24 #include <algorithm>
25 #include <assert.h>
26 #include <utility>
27 #include <sstream>
28 
29 #include <gazebo/rendering/RenderingIface.hh>
30 #include <gazebo/rendering/Scene.hh>
31 #include <gazebo/rendering/Visual.hh>
32 #include <gazebo/rendering/RTShaderSystem.hh>
34 
35 #ifdef ENABLE_PROFILER
36 #include <ignition/common/Profiler.hh>
37 #endif
38 
39 #include <std_msgs/String.h>
40 #include <std_msgs/Int32.h>
41 
42 #include <Ogre.h>
43 #include <OgreMath.h>
44 #include <OgreSceneNode.h>
45 #include <OgreFrustum.h>
46 #include <OgreSceneQuery.h>
47 
48 namespace gazebo
49 {
50 GZ_REGISTER_MODEL_PLUGIN(GazeboRosProjector);
51 
52 typedef std::map<std::string,Ogre::Pass*> OgrePassMap;
53 typedef OgrePassMap::iterator OgrePassMapIterator;
54 
55 
57 // Constructor
59 {
60  this->rosnode_ = NULL;
61 }
62 
63 
65 // Destructor
67 {
68  // Custom Callback Queue
69  this->queue_.clear();
70  this->queue_.disable();
71  this->rosnode_->shutdown();
72  this->callback_queue_thread_.join();
73 
74  delete this->rosnode_;
75 }
76 
78 // Load the controller
79 void GazeboRosProjector::Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
80 {
81  this->world_ = _parent->GetWorld();
82 
83  // Create a new transport node for talking to the projector
84  this->node_.reset(new transport::Node());
85  // Initialize the node with the world name
86 #if GAZEBO_MAJOR_VERSION >= 8
87  this->node_->Init(this->world_->Name());
88 #else
89  this->node_->Init(this->world_->GetName());
90 #endif
91  // Setting projector topic
92  std::string name = std::string("~/") + _parent->GetName() + "/" +
93  _sdf->Get<std::string>("projector");
94  // Create a publisher on the ~/physics topic
95  this->projector_pub_ = node_->Advertise<msgs::Projector>(name);
96 
97 
98 
99  // load parameters
100  this->robot_namespace_ = "";
101  if (_sdf->HasElement("robotNamespace"))
102  this->robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
103 
104  this->texture_topic_name_ = "";
105  if (_sdf->HasElement("textureTopicName"))
106  this->texture_topic_name_ = _sdf->GetElement("textureTopicName")->Get<std::string>();
107 
108  this->projector_topic_name_ = "";
109  if (_sdf->HasElement("projectorTopicName"))
110  this->projector_topic_name_ = _sdf->GetElement("projectorTopicName")->Get<std::string>();
111 
112  // Make sure the ROS node for Gazebo has already been initialized
113  if (!ros::isInitialized())
114  {
115  ROS_FATAL_STREAM_NAMED("projector", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
116  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
117  return;
118  }
119 
120 
121  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
122 
123 
124  // Custom Callback Queue
125  ros::SubscribeOptions so = ros::SubscribeOptions::create<std_msgs::Int32>(
126  this->projector_topic_name_,1,
127  boost::bind( &GazeboRosProjector::ToggleProjector,this,_1),
128  ros::VoidPtr(), &this->queue_);
129  this->projectorSubscriber_ = this->rosnode_->subscribe(so);
130 
131  ros::SubscribeOptions so2 = ros::SubscribeOptions::create<std_msgs::String>(
132  this->texture_topic_name_,1,
133  boost::bind( &GazeboRosProjector::LoadImage,this,_1),
134  ros::VoidPtr(), &this->queue_);
135  this->imageSubscriber_ = this->rosnode_->subscribe(so2);
136 
137 
138  // Custom Callback Queue
139  this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosProjector::QueueThread,this ) );
140 
141 }
142 
143 
145 // Load a texture into the projector
146 void GazeboRosProjector::LoadImage(const std_msgs::String::ConstPtr& imageMsg)
147 {
148 #ifdef ENABLE_PROFILER
149  IGN_PROFILE("GazeboRosProjector::LoadImage");
150  IGN_PROFILE_BEGIN("publish");
151 #endif
152  msgs::Projector msg;
153  msg.set_name("texture_projector");
154  msg.set_texture(imageMsg->data);
155  this->projector_pub_->Publish(msg);
156 #ifdef ENABLE_PROFILER
157  IGN_PROFILE_END();
158 #endif
159 }
160 
162 // Toggle the activation of the projector
163 void GazeboRosProjector::ToggleProjector(const std_msgs::Int32::ConstPtr& projectorMsg)
164 {
165 #ifdef ENABLE_PROFILER
166  IGN_PROFILE("GazeboRosProjector::ToggleProjector");
167  IGN_PROFILE_BEGIN("publish");
168 #endif
169  msgs::Projector msg;
170  msg.set_name("texture_projector");
171  msg.set_enabled(projectorMsg->data);
172  this->projector_pub_->Publish(msg);
173 #ifdef ENABLE_PROFILER
174  IGN_PROFILE_END();
175 #endif
176 }
177 
178 
180 // Custom callback queue thread
182 {
183  static const double timeout = 0.01;
184 
185  while (this->rosnode_->ok())
186  {
187  this->queue_.callAvailable(ros::WallDuration(timeout));
188  }
189 }
190 
191 }
msg
msg
boost::shared_ptr< void >
gazebo
gazebo::OgrePassMap
std::map< std::string, Ogre::Pass * > OgrePassMap
Definition: gazebo_ros_projector.cpp:52
gazebo::GazeboRosProjector::projector_topic_name_
std::string projector_topic_name_
ROS projector topic name.
Definition: gazebo_ros_projector.h:106
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosProjector::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_projector.h:114
gazebo::GazeboRosProjector::texture_topic_name_
std::string texture_topic_name_
ROS texture topic name.
Definition: gazebo_ros_projector.h:103
gazebo::GazeboRosProjector::LoadImage
void LoadImage(const std_msgs::String::ConstPtr &imageMsg)
Callback when a texture is published.
Definition: gazebo_ros_projector.cpp:146
gazebo::GazeboRosProjector::imageSubscriber_
ros::Subscriber imageSubscriber_
Definition: gazebo_ros_projector.h:99
gazebo::GazeboRosProjector::ToggleProjector
void ToggleProjector(const std_msgs::Int32::ConstPtr &projectorMsg)
Callbakc when a projector toggle is published.
Definition: gazebo_ros_projector.cpp:163
gazebo::GazeboRosProjector::node_
transport::NodePtr node_
Definition: gazebo_ros_projector.h:118
gazebo::GazeboRosProjector::projector_pub_
transport::PublisherPtr projector_pub_
Definition: gazebo_ros_projector.h:119
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo_ros_projector.h
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::GazeboRosProjector::~GazeboRosProjector
virtual ~GazeboRosProjector()
Destructor.
Definition: gazebo_ros_projector.cpp:66
gazebo::GazeboRosProjector::Load
virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
Definition: gazebo_ros_projector.cpp:79
ros::NodeHandle::ok
bool ok() const
ros::SubscribeOptions
gazebo::GazeboRosProjector::robot_namespace_
std::string robot_namespace_
For setting ROS name space.
Definition: gazebo_ros_projector.h:109
gazebo::GazeboRosProjector::projectorSubscriber_
ros::Subscriber projectorSubscriber_
Definition: gazebo_ros_projector.h:100
gazebo::GazeboRosProjector::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_projector.h:112
gazebo::OgrePassMapIterator
OgrePassMap::iterator OgrePassMapIterator
Definition: gazebo_ros_projector.cpp:53
ros::WallDuration
assert.h
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosProjector::QueueThread
void QueueThread()
Definition: gazebo_ros_projector.cpp:181
ros::CallbackQueue::callAvailable
void callAvailable()
ros::CallbackQueue::disable
void disable()
ros::NodeHandle
gazebo::GazeboRosProjector::world_
physics::WorldPtr world_
pointer to the world
Definition: gazebo_ros_projector.h:89
gazebo::GazeboRosProjector::GazeboRosProjector
GazeboRosProjector()
Constructor.
Definition: gazebo_ros_projector.cpp:58
gazebo::GazeboRosProjector::rosnode_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition: gazebo_ros_projector.h:98


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