gazebo_ros_f3d.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: Force Feed Back Ground Truth
20  Author: Sachin Chitta and John Hsu
21  Date: 1 June 2008
22  */
23 
25 #ifdef ENABLE_PROFILER
26 #include <ignition/common/Profiler.hh>
27 #endif
28 #include <tf/tf.h>
29 
30 namespace gazebo
31 {
32 GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D);
33 
35 // Constructor
37 {
38  this->f3d_connect_count_ = 0;
39 }
40 
42 // Destructor
44 {
45  this->update_connection_.reset();
46  // Custom Callback Queue
47  this->queue_.clear();
48  this->queue_.disable();
49  this->rosnode_->shutdown();
50  this->callback_queue_thread_.join();
51  delete this->rosnode_;
52 }
53 
55 // Load the controller
56 void GazeboRosF3D::Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
57 {
58  // Get the world name.
59  this->world_ = _parent->GetWorld();
60 
61  // load parameters
62  this->robot_namespace_ = "";
63  if (_sdf->HasElement("robotNamespace"))
64  this->robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
65 
66  if (!_sdf->HasElement("bodyName"))
67  {
68  ROS_FATAL_NAMED("f3d", "f3d plugin missing <bodyName>, cannot proceed");
69  return;
70  }
71  else
72  this->link_name_ = _sdf->GetElement("bodyName")->Get<std::string>();
73 
74  this->link_ = _parent->GetLink(this->link_name_);
75  if (!this->link_)
76  {
77  ROS_FATAL_NAMED("f3d", "gazebo_ros_f3d plugin error: bodyName: %s does not exist\n",this->link_name_.c_str());
78  return;
79  }
80 
81  if (!_sdf->HasElement("topicName"))
82  {
83  ROS_FATAL_NAMED("f3d", "f3d plugin missing <topicName>, cannot proceed");
84  return;
85  }
86  else
87  this->topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
88 
89  if (!_sdf->HasElement("frameName"))
90  {
91  ROS_INFO_NAMED("f3d", "f3d plugin missing <frameName>, defaults to world");
92  this->frame_name_ = "world";
93  }
94  else
95  {
96  this->frame_name_ = _sdf->GetElement("frameName")->Get<std::string>();
97  // todo: frameName not used
98  ROS_INFO_NAMED("f3d", "f3d plugin specifies <frameName> [%s], not used, default to world",this->frame_name_.c_str());
99  }
100 
101 
102  // Make sure the ROS node for Gazebo has already been initialized
103  if (!ros::isInitialized())
104  {
105  ROS_FATAL_STREAM_NAMED("f3d", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
106  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
107  return;
108  }
109 
110  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
111 
112  // resolve tf prefix
113  std::string prefix;
114  this->rosnode_->getParam(std::string("tf_prefix"), prefix);
115  this->frame_name_ = tf::resolve(prefix, this->frame_name_);
116 
117  // Custom Callback Queue
118  ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<geometry_msgs::WrenchStamped>(
119  this->topic_name_,1,
120  boost::bind( &GazeboRosF3D::F3DConnect,this),
121  boost::bind( &GazeboRosF3D::F3DDisconnect,this), ros::VoidPtr(), &this->queue_);
122  this->pub_ = this->rosnode_->advertise(ao);
123 
124  // Custom Callback Queue
125  this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosF3D::QueueThread,this ) );
126 
127  // New Mechanism for Updating every World Cycle
128  // Listen to the update event. This event is broadcast every
129  // simulation iteration.
130  this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
131  boost::bind(&GazeboRosF3D::UpdateChild, this));
132 }
133 
135 // Someone subscribes to me
137 {
138  this->f3d_connect_count_++;
139 }
140 
142 // Someone subscribes to me
144 {
145  this->f3d_connect_count_--;
146 }
147 
149 // Update the controller
151 {
152 #ifdef ENABLE_PROFILER
153  IGN_PROFILE("GazeboRosF3D::UpdateChild");
154 #endif
155  if (this->f3d_connect_count_ == 0)
156  return;
157 
158 #ifdef ENABLE_PROFILER
159  IGN_PROFILE_BEGIN("fill ROS message");
160 #endif
161  ignition::math::Vector3d torque;
162  ignition::math::Vector3d force;
163 
164  // get force and torque on body
165 #if GAZEBO_MAJOR_VERSION >= 8
166  force = this->link_->WorldForce();
167  torque = this->link_->WorldTorque();
168 #else
169  force = this->link_->GetWorldForce().Ign();
170  torque = this->link_->GetWorldTorque().Ign();
171 #endif
172 
173  this->lock_.lock();
174  // copy data into wrench message
175  this->wrench_msg_.header.frame_id = this->frame_name_;
176 #if GAZEBO_MAJOR_VERSION >= 8
177  this->wrench_msg_.header.stamp.sec = (this->world_->SimTime()).sec;
178  this->wrench_msg_.header.stamp.nsec = (this->world_->SimTime()).nsec;
179 #else
180  this->wrench_msg_.header.stamp.sec = (this->world_->GetSimTime()).sec;
181  this->wrench_msg_.header.stamp.nsec = (this->world_->GetSimTime()).nsec;
182 #endif
183 
184  this->wrench_msg_.wrench.force.x = force.X();
185  this->wrench_msg_.wrench.force.y = force.Y();
186  this->wrench_msg_.wrench.force.z = force.Z();
187  this->wrench_msg_.wrench.torque.x = torque.X();
188  this->wrench_msg_.wrench.torque.y = torque.Y();
189  this->wrench_msg_.wrench.torque.z = torque.Z();
190 #ifdef ENABLE_PROFILER
191  IGN_PROFILE_END();
192  IGN_PROFILE_BEGIN("publish");
193 #endif
194  this->pub_.publish(this->wrench_msg_);
195 #ifdef ENABLE_PROFILER
196  IGN_PROFILE_END();
197 #endif
198  this->lock_.unlock();
199 }
200 
201 // Custom Callback Queue
203 // custom callback queue thread
205 {
206  static const double timeout = 0.01;
207 
208  while (this->rosnode_->ok())
209  {
210  this->queue_.callAvailable(ros::WallDuration(timeout));
211  }
212 }
213 
214 }
gazebo::GazeboRosF3D::F3DDisconnect
void F3DDisconnect()
Definition: gazebo_ros_f3d.cpp:143
gazebo::GazeboRosF3D::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_f3d.h:84
boost::shared_ptr< void >
gazebo
gazebo::GazeboRosF3D::rosnode_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition: gazebo_ros_f3d.h:67
gazebo::GazeboRosF3D::link_name_
std::string link_name_
store bodyname
Definition: gazebo_ros_f3d.h:74
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosF3D::lock_
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
Definition: gazebo_ros_f3d.h:87
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
gazebo::GazeboRosF3D::pub_
ros::Publisher pub_
Definition: gazebo_ros_f3d.h:68
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::AdvertiseOptions
gazebo::GazeboRosF3D::wrench_msg_
geometry_msgs::WrenchStamped wrench_msg_
ROS WrenchStamped message.
Definition: gazebo_ros_f3d.h:71
gazebo::GazeboRosF3D::world_
physics::WorldPtr world_
Definition: gazebo_ros_f3d.h:60
gazebo::GazeboRosF3D::~GazeboRosF3D
virtual ~GazeboRosF3D()
Destructor.
Definition: gazebo_ros_f3d.cpp:43
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
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::GazeboRosF3D::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_f3d.h:97
tf.h
ros::NodeHandle::ok
bool ok() const
gazebo::GazeboRosF3D::topic_name_
std::string topic_name_
ROS WrenchStamped topic name.
Definition: gazebo_ros_f3d.h:77
gazebo::GazeboRosF3D::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
Definition: gazebo_ros_f3d.cpp:56
gazebo_ros_f3d.h
gazebo::GazeboRosF3D::f3d_connect_count_
int f3d_connect_count_
: keep track of number of connections
Definition: gazebo_ros_f3d.h:90
gazebo::GazeboRosF3D::frame_name_
std::string frame_name_
ROS frame transform name to use in the image message header. This should be simply map since the retu...
Definition: gazebo_ros_f3d.h:81
gazebo::GazeboRosF3D::UpdateChild
virtual void UpdateChild()
Update the controller.
Definition: gazebo_ros_f3d.cpp:150
gazebo::GazeboRosF3D::link_
physics::LinkPtr link_
A pointer to the Gazebo Body.
Definition: gazebo_ros_f3d.h:63
ros::WallDuration
gazebo::GazeboRosF3D::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_f3d.h:100
gazebo::GazeboRosF3D::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_f3d.h:95
ros::NodeHandle::shutdown
void shutdown()
ros::CallbackQueue::callAvailable
void callAvailable()
ros::CallbackQueue::disable
void disable()
gazebo::GazeboRosF3D::QueueThread
void QueueThread()
Definition: gazebo_ros_f3d.cpp:204
ros::NodeHandle
gazebo::GazeboRosF3D::F3DConnect
void F3DConnect()
Definition: gazebo_ros_f3d.cpp:136
gazebo::GazeboRosF3D::GazeboRosF3D
GazeboRosF3D()
Constructor.
Definition: gazebo_ros_f3d.cpp:36


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