gazebo_ros_force.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: GazeboRosForce plugin for manipulating objects in Gazebo
20  Author: John Hsu
21  Date: 24 Sept 2008
22  */
23 
24 #include <algorithm>
25 #include <assert.h>
26 
28 #ifdef ENABLE_PROFILER
29 #include <ignition/common/Profiler.hh>
30 #endif
31 
32 namespace gazebo
33 {
34 GZ_REGISTER_MODEL_PLUGIN(GazeboRosForce);
35 
37 // Constructor
39 {
40  this->wrench_msg_.force.x = 0;
41  this->wrench_msg_.force.y = 0;
42  this->wrench_msg_.force.z = 0;
43  this->wrench_msg_.torque.x = 0;
44  this->wrench_msg_.torque.y = 0;
45  this->wrench_msg_.torque.z = 0;
46 }
47 
49 // Destructor
51 {
52  this->update_connection_.reset();
53 
54  // Custom Callback Queue
55  this->queue_.clear();
56  this->queue_.disable();
57  this->rosnode_->shutdown();
58  this->callback_queue_thread_.join();
59 
60  delete this->rosnode_;
61 }
62 
64 // Load the controller
65 void GazeboRosForce::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
66 {
67  // Get the world name.
68  this->world_ = _model->GetWorld();
69 
70  // load parameters
71  this->robot_namespace_ = "";
72  if (_sdf->HasElement("robotNamespace"))
73  this->robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
74 
75  if (!_sdf->HasElement("bodyName"))
76  {
77  ROS_FATAL_NAMED("force", "force plugin missing <bodyName>, cannot proceed");
78  return;
79  }
80  else
81  this->link_name_ = _sdf->GetElement("bodyName")->Get<std::string>();
82 
83  this->link_ = _model->GetLink(this->link_name_);
84  if (!this->link_)
85  {
86  ROS_FATAL_NAMED("force", "gazebo_ros_force plugin error: link named: %s does not exist\n",this->link_name_.c_str());
87  return;
88  }
89 
90  if (!_sdf->HasElement("topicName"))
91  {
92  ROS_FATAL_NAMED("force", "force plugin missing <topicName>, cannot proceed");
93  return;
94  }
95  else
96  this->topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
97 
98 
99  // Make sure the ROS node for Gazebo has already been initialized
100  if (!ros::isInitialized())
101  {
102  ROS_FATAL_STREAM_NAMED("force", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
103  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
104  return;
105  }
106 
107  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
108 
109  // Custom Callback Queue
110  ros::SubscribeOptions so = ros::SubscribeOptions::create<geometry_msgs::Wrench>(
111  this->topic_name_,1,
112  boost::bind( &GazeboRosForce::UpdateObjectForce,this,_1),
113  ros::VoidPtr(), &this->queue_);
114  this->sub_ = this->rosnode_->subscribe(so);
115 
116  // Custom Callback Queue
117  this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosForce::QueueThread,this ) );
118 
119  // New Mechanism for Updating every World Cycle
120  // Listen to the update event. This event is broadcast every
121  // simulation iteration.
122  this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
123  boost::bind(&GazeboRosForce::UpdateChild, this));
124 }
125 
127 // Update the controller
128 void GazeboRosForce::UpdateObjectForce(const geometry_msgs::Wrench::ConstPtr& _msg)
129 {
130  this->wrench_msg_.force.x = _msg->force.x;
131  this->wrench_msg_.force.y = _msg->force.y;
132  this->wrench_msg_.force.z = _msg->force.z;
133  this->wrench_msg_.torque.x = _msg->torque.x;
134  this->wrench_msg_.torque.y = _msg->torque.y;
135  this->wrench_msg_.torque.z = _msg->torque.z;
136 }
137 
139 // Update the controller
141 {
142 #ifdef ENABLE_PROFILER
143  IGN_PROFILE("GazeboRosForce::OnNewFrame");
144  IGN_PROFILE_BEGIN("fill ROS message");
145 #endif
146  this->lock_.lock();
147  ignition::math::Vector3d force(this->wrench_msg_.force.x,this->wrench_msg_.force.y,this->wrench_msg_.force.z);
148  ignition::math::Vector3d torque(this->wrench_msg_.torque.x,this->wrench_msg_.torque.y,this->wrench_msg_.torque.z);
149  this->link_->AddForce(force);
150  this->link_->AddTorque(torque);
151  this->lock_.unlock();
152 #ifdef ENABLE_PROFILER
153  IGN_PROFILE_END();
154 #endif
155 }
156 
157 // Custom Callback Queue
159 // custom callback queue thread
161 {
162  static const double timeout = 0.01;
163 
164  while (this->rosnode_->ok())
165  {
166  this->queue_.callAvailable(ros::WallDuration(timeout));
167  }
168 }
169 
170 }
gazebo::GazeboRosForce::rosnode_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition: gazebo_ros_force.h:99
gazebo::GazeboRosForce::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_force.h:111
gazebo::GazeboRosForce::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_force.h:121
boost::shared_ptr< void >
gazebo
gazebo::GazeboRosForce::lock_
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
Definition: gazebo_ros_force.h:103
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosForce::topic_name_
std::string topic_name_
ROS Wrench topic name inputs.
Definition: gazebo_ros_force.h:106
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
gazebo::GazeboRosForce::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_force.h:114
gazebo::GazeboRosForce::Load
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Definition: gazebo_ros_force.cpp:65
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
gazebo::GazeboRosForce::callback_queue_thread_
boost::thread callback_queue_thread_
Thead object for the running callback Thread.
Definition: gazebo_ros_force.h:116
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosForce::wrench_msg_
geometry_msgs::Wrench wrench_msg_
Container for the wrench force that this plugin exerts on the body.
Definition: gazebo_ros_force.h:118
gazebo::GazeboRosForce::UpdateChild
virtual void UpdateChild()
Definition: gazebo_ros_force.cpp:140
gazebo::GazeboRosForce::sub_
ros::Subscriber sub_
Definition: gazebo_ros_force.h:100
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())
ros::NodeHandle::ok
bool ok() const
ros::SubscribeOptions
gazebo_ros_force.h
gazebo::GazeboRosForce::UpdateObjectForce
void UpdateObjectForce(const geometry_msgs::Wrench::ConstPtr &_msg)
call back when a Wrench message is published
Definition: gazebo_ros_force.cpp:128
gazebo::GazeboRosForce::~GazeboRosForce
virtual ~GazeboRosForce()
Destructor.
Definition: gazebo_ros_force.cpp:50
ros::WallDuration
assert.h
gazebo::GazeboRosForce::link_name_
std::string link_name_
The Link this plugin is attached to, and will exert forces on.
Definition: gazebo_ros_force.h:108
ros::NodeHandle::shutdown
void shutdown()
ros::CallbackQueue::callAvailable
void callAvailable()
gazebo::GazeboRosForce::GazeboRosForce
GazeboRosForce()
Constructor.
Definition: gazebo_ros_force.cpp:38
ros::CallbackQueue::disable
void disable()
gazebo::GazeboRosForce::QueueThread
void QueueThread()
The custom callback queue thread function.
Definition: gazebo_ros_force.cpp:160
gazebo::GazeboRosForce::link_
physics::LinkPtr link_
A pointer to the Link, where force is applied.
Definition: gazebo_ros_force.h:96
ros::NodeHandle
gazebo::GazeboRosForce::world_
physics::WorldPtr world_
A pointer to the gazebo world.
Definition: gazebo_ros_force.h:93


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