gazebo_ros_ft_sensor.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2014 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  * Desc: Force Torque Sensor Plugin
19  * Author: Francisco Suarez-Ruiz
20  * Date: 5 June 2014
21  */
22 
24 #include <tf/tf.h>
25 #ifdef ENABLE_PROFILER
26 #include <ignition/common/Profiler.hh>
27 #endif
28 #include <ignition/math/Rand.hh>
29 
30 namespace gazebo
31 {
32 GZ_REGISTER_MODEL_PLUGIN(GazeboRosFT);
33 
35 // Constructor
37 {
38  this->ft_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 GazeboRosFT::Load( physics::ModelPtr _model, sdf::ElementPtr _sdf )
57 {
58  // Save pointers
59  this->model_ = _model;
60  this->world_ = this->model_->GetWorld();
61 
62  // load parameters
63  this->robot_namespace_ = "";
64  if (_sdf->HasElement("robotNamespace"))
65  this->robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
66 
67  if (!_sdf->HasElement("jointName"))
68  {
69  ROS_FATAL_NAMED("ft_sensor", "ft_sensor plugin missing <jointName>, cannot proceed");
70  return;
71  }
72  else
73  this->joint_name_ = _sdf->GetElement("jointName")->Get<std::string>();
74 
75  this->joint_ = this->model_->GetJoint(this->joint_name_);
76  if (!this->joint_)
77  {
78  ROS_FATAL_NAMED("ft_sensor", "gazebo_ros_ft_sensor plugin error: jointName: %s does not exist\n",this->joint_name_.c_str());
79  return;
80  }
81 
82  this->parent_link_ = this->joint_->GetParent();
83  this->child_link_ = this->joint_->GetChild();
84  this->frame_name_ = this->child_link_->GetName();
85 
86  ROS_INFO_NAMED("ft_sensor", "ft_sensor plugin reporting wrench values to the frame [%s]", this->frame_name_.c_str());
87 
88  if (!_sdf->HasElement("topicName"))
89  {
90  ROS_FATAL_NAMED("ft_sensor", "ft_sensor plugin missing <topicName>, cannot proceed");
91  return;
92  }
93  else
94  this->topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
95 
96  if (!_sdf->HasElement("gaussianNoise"))
97  {
98  ROS_INFO_NAMED("ft_sensor", "ft_sensor plugin missing <gaussianNoise>, defaults to 0.0");
99  this->gaussian_noise_ = 0.0;
100  }
101  else
102  this->gaussian_noise_ = _sdf->Get<double>("gaussianNoise");
103 
104  if (!_sdf->HasElement("updateRate"))
105  {
106  ROS_DEBUG_NAMED("ft_sensor", "ft_sensor plugin missing <updateRate>, defaults to 0.0"
107  " (as fast as possible)");
108  this->update_rate_ = 0;
109  }
110  else
111  this->update_rate_ = _sdf->GetElement("updateRate")->Get<double>();
112 
113  // Make sure the ROS node for Gazebo has already been initialized
114  if (!ros::isInitialized())
115  {
116  ROS_FATAL_STREAM_NAMED("ft_sensor", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
117  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
118  return;
119  }
120 
121  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
122 
123  // resolve tf prefix
124  std::string prefix;
125  this->rosnode_->getParam(std::string("tf_prefix"), prefix);
126  this->frame_name_ = tf::resolve(prefix, this->frame_name_);
127 
128  // Custom Callback Queue
129  ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<geometry_msgs::WrenchStamped>(
130  this->topic_name_,1,
131  boost::bind( &GazeboRosFT::FTConnect,this),
132  boost::bind( &GazeboRosFT::FTDisconnect,this), ros::VoidPtr(), &this->queue_);
133  this->pub_ = this->rosnode_->advertise(ao);
134 
135  // Custom Callback Queue
136  this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosFT::QueueThread,this ) );
137 
138  // New Mechanism for Updating every World Cycle
139  // Listen to the update event. This event is broadcast every
140  // simulation iteration.
141  this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
142  boost::bind(&GazeboRosFT::UpdateChild, this));
143 }
144 
146 // Someone subscribes to me
148 {
149  this->ft_connect_count_++;
150 }
151 
153 // Someone subscribes to me
155 {
156  this->ft_connect_count_--;
157 }
158 
160 // Update the controller
162 {
163 #ifdef ENABLE_PROFILER
164  IGN_PROFILE("GazeboRosFT::UpdateChild");
165  IGN_PROFILE_BEGIN("fill ROS message");
166 #endif
167 #if GAZEBO_MAJOR_VERSION >= 8
168  common::Time cur_time = this->world_->SimTime();
169 #else
170  common::Time cur_time = this->world_->GetSimTime();
171 #endif
172 
173  // rate control
174  if (this->update_rate_ > 0 &&
175  (cur_time-this->last_time_).Double() < (1.0/this->update_rate_))
176  return;
177 
178  if (this->ft_connect_count_ == 0)
179  return;
180 
181  physics::JointWrench wrench;
182  ignition::math::Vector3d torque;
183  ignition::math::Vector3d force;
184 
185  // FIXME: Should include options for diferent frames and measure directions
186  // E.g: https://bitbucket.org/osrf/gazebo/raw/default/gazebo/sensors/ForceTorqueSensor.hh
187  // Get force torque at the joint
188  // The wrench is reported in the CHILD <frame>
189  // The <measure_direction> is child_to_parent
190  wrench = this->joint_->GetForceTorque(0);
191 #if GAZEBO_MAJOR_VERSION >= 8
192  force = wrench.body2Force;
193  torque = wrench.body2Torque;
194 #else
195  force = wrench.body2Force.Ign();
196  torque = wrench.body2Torque.Ign();
197 #endif
198 
199 
200  this->lock_.lock();
201  // copy data into wrench message
202  this->wrench_msg_.header.frame_id = this->frame_name_;
203 #if GAZEBO_MAJOR_VERSION >= 8
204  this->wrench_msg_.header.stamp.sec = (this->world_->SimTime()).sec;
205  this->wrench_msg_.header.stamp.nsec = (this->world_->SimTime()).nsec;
206 #else
207  this->wrench_msg_.header.stamp.sec = (this->world_->GetSimTime()).sec;
208  this->wrench_msg_.header.stamp.nsec = (this->world_->GetSimTime()).nsec;
209 #endif
210 
211  this->wrench_msg_.wrench.force.x = force.X() + this->GaussianKernel(0, this->gaussian_noise_);
212  this->wrench_msg_.wrench.force.y = force.Y() + this->GaussianKernel(0, this->gaussian_noise_);
213  this->wrench_msg_.wrench.force.z = force.Z() + this->GaussianKernel(0, this->gaussian_noise_);
214  this->wrench_msg_.wrench.torque.x = torque.X() + this->GaussianKernel(0, this->gaussian_noise_);
215  this->wrench_msg_.wrench.torque.y = torque.Y() + this->GaussianKernel(0, this->gaussian_noise_);
216  this->wrench_msg_.wrench.torque.z = torque.Z() + this->GaussianKernel(0, this->gaussian_noise_);
217 #ifdef ENABLE_PROFILER
218  IGN_PROFILE_END();
219  IGN_PROFILE_BEGIN("publish");
220 #endif
221  this->pub_.publish(this->wrench_msg_);
222 #ifdef ENABLE_PROFILER
223  IGN_PROFILE_END();
224 #endif
225  this->lock_.unlock();
226 
227  // save last time stamp
228  this->last_time_ = cur_time;
229 }
230 
232 // Utility for adding noise
233 double GazeboRosFT::GaussianKernel(double mu, double sigma)
234 {
235  // using Box-Muller transform to generate two independent standard
236  // normally disbributed normal variables see wikipedia
237 
238  // normalized uniform random variable
239  double U = ignition::math::Rand::DblUniform();
240 
241  // normalized uniform random variable
242  double V = ignition::math::Rand::DblUniform();
243 
244  double X = sqrt(-2.0 * ::log(U)) * cos(2.0*M_PI * V);
245  // double Y = sqrt(-2.0 * ::log(U)) * sin(2.0*M_PI * V);
246 
247  // there are 2 indep. vars, we'll just use X
248  // scale to our mu and sigma
249  X = sigma * X + mu;
250  return X;
251 }
252 
253 // Custom Callback Queue
255 // custom callback queue thread
257 {
258  static const double timeout = 0.01;
259 
260  while (this->rosnode_->ok())
261  {
262  this->queue_.callAvailable(ros::WallDuration(timeout));
263  }
264 }
265 
266 }
gazebo::GazeboRosFT::QueueThread
void QueueThread()
Definition: gazebo_ros_ft_sensor.cpp:256
gazebo::GazeboRosFT::topic_name_
std::string topic_name_
ROS WrenchStamped topic name.
Definition: gazebo_ros_ft_sensor.h:121
gazebo::GazeboRosFT::~GazeboRosFT
virtual ~GazeboRosFT()
Destructor.
Definition: gazebo_ros_ft_sensor.cpp:43
gazebo::GazeboRosFT::model_
physics::ModelPtr model_
A pointer to the Gazebo model.
Definition: gazebo_ros_ft_sensor.h:105
gazebo::GazeboRosFT::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_ft_sensor.h:147
boost::shared_ptr< void >
gazebo
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
gazebo::GazeboRosFT::parent_link_
physics::LinkPtr parent_link_
A pointer to the Gazebo parent link.
Definition: gazebo_ros_ft_sensor.h:99
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosFT::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_ft_sensor.h:128
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
gazebo::GazeboRosFT::rosnode_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition: gazebo_ros_ft_sensor.h:111
gazebo::GazeboRosFT::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_ft_sensor.h:150
gazebo::GazeboRosFT::lock_
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
Definition: gazebo_ros_ft_sensor.h:131
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)
gazebo::GazeboRosFT::pub_
ros::Publisher pub_
Definition: gazebo_ros_ft_sensor.h:112
ros::AdvertiseOptions
gazebo::GazeboRosFT::frame_name_
std::string frame_name_
ROS frame transform name to use in the image message header. FIXME: extract link name directly?
Definition: gazebo_ros_ft_sensor.h:125
gazebo::GazeboRosFT::joint_
physics::JointPtr joint_
A pointer to the Gazebo joint.
Definition: gazebo_ros_ft_sensor.h:96
gazebo::GazeboRosFT::world_
physics::WorldPtr world_
A pointer to the Gazebo world.
Definition: gazebo_ros_ft_sensor.h:108
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
gazebo::GazeboRosFT::ft_connect_count_
int ft_connect_count_
: keep track of number of connections
Definition: gazebo_ros_ft_sensor.h:140
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
gazebo::GazeboRosFT::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
Definition: gazebo_ros_ft_sensor.cpp:56
gazebo_ros_ft_sensor.h
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosFT::joint_name_
std::string joint_name_
store bodyname
Definition: gazebo_ros_ft_sensor.h:118
gazebo::GazeboRosFT::update_rate_
double update_rate_
Definition: gazebo_ros_ft_sensor.h:137
tf.h
gazebo::GazeboRosFT::last_time_
common::Time last_time_
save last_time
Definition: gazebo_ros_ft_sensor.h:134
gazebo::GazeboRosFT::UpdateChild
virtual void UpdateChild()
Update the controller.
Definition: gazebo_ros_ft_sensor.cpp:161
gazebo::GazeboRosFT::GaussianKernel
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
Definition: gazebo_ros_ft_sensor.cpp:233
gazebo::GazeboRosFT::wrench_msg_
geometry_msgs::WrenchStamped wrench_msg_
ROS WrenchStamped message.
Definition: gazebo_ros_ft_sensor.h:115
ros::NodeHandle::ok
bool ok() const
gazebo::GazeboRosFT::GazeboRosFT
GazeboRosFT()
Constructor.
Definition: gazebo_ros_ft_sensor.cpp:36
gazebo::GazeboRosFT::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_ft_sensor.h:145
gazebo::GazeboRosFT::FTDisconnect
void FTDisconnect()
Definition: gazebo_ros_ft_sensor.cpp:154
gazebo::GazeboRosFT::child_link_
physics::LinkPtr child_link_
A pointer to the Gazebo child link.
Definition: gazebo_ros_ft_sensor.h:102
gazebo::GazeboRosFT::gaussian_noise_
double gaussian_noise_
Gaussian noise.
Definition: gazebo_ros_ft_sensor.h:90
ros::WallDuration
ros::NodeHandle::shutdown
void shutdown()
ros::CallbackQueue::callAvailable
void callAvailable()
gazebo::GazeboRosFT::FTConnect
void FTConnect()
Definition: gazebo_ros_ft_sensor.cpp:147
ros::CallbackQueue::disable
void disable()
ros::NodeHandle


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