gazebo_ros_vacuum_gripper.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 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: GazeboVacuumGripper plugin for manipulating objects in Gazebo
20  Author: Kentaro Wada
21  Date: 7 Dec 2015
22  */
23 
24 #include <algorithm>
25 #include <assert.h>
26 
27 #include <std_msgs/Bool.h>
29 #ifdef ENABLE_PROFILER
30 #include <ignition/common/Profiler.hh>
31 #endif
32 
33 namespace gazebo
34 {
35 GZ_REGISTER_MODEL_PLUGIN(GazeboRosVacuumGripper);
36 
38 // Constructor
40 {
41  connect_count_ = 0;
42  status_ = false;
43 }
44 
46 // Destructor
48 {
49  update_connection_.reset();
50 
51  // Custom Callback Queue
52  queue_.clear();
53  queue_.disable();
54  rosnode_->shutdown();
56 
57  delete rosnode_;
58 }
59 
61 // Load the controller
62 void GazeboRosVacuumGripper::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
63 {
64  ROS_INFO_NAMED("vacuum_gripper", "Loading gazebo_ros_vacuum_gripper");
65 
66  // Set attached model;
67  parent_ = _model;
68 
69  // Get the world name.
70  world_ = _model->GetWorld();
71 
72  // load parameters
73  robot_namespace_ = "";
74  if (_sdf->HasElement("robotNamespace"))
75  robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
76 
77  if (!_sdf->HasElement("bodyName"))
78  {
79  ROS_FATAL_NAMED("vacuum_gripper", "vacuum_gripper plugin missing <bodyName>, cannot proceed");
80  return;
81  }
82  else
83  link_name_ = _sdf->GetElement("bodyName")->Get<std::string>();
84 
85  link_ = _model->GetLink(link_name_);
86  if (!link_)
87  {
88  std::string found;
89  physics::Link_V links = _model->GetLinks();
90  for (size_t i = 0; i < links.size(); i++) {
91  found += std::string(" ") + links[i]->GetName();
92  }
93  ROS_FATAL_NAMED("vacuum_gripper", "gazebo_ros_vacuum_gripper plugin error: link named: %s does not exist", link_name_.c_str());
94  ROS_FATAL_NAMED("vacuum_gripper", "gazebo_ros_vacuum_gripper plugin error: You should check it exists and is not connected with fixed joint");
95  ROS_FATAL_NAMED("vacuum_gripper", "gazebo_ros_vacuum_gripper plugin error: Found links are: %s", found.c_str());
96  return;
97  }
98 
99  if (!_sdf->HasElement("topicName"))
100  {
101  ROS_FATAL_NAMED("vacuum_gripper", "vacuum_gripper plugin missing <serviceName>, cannot proceed");
102  return;
103  }
104  else
105  topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
106 
107  // Make sure the ROS node for Gazebo has already been initialized
108  if (!ros::isInitialized())
109  {
110  ROS_FATAL_STREAM_NAMED("vacuum_gripper", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
111  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
112  return;
113  }
114 
116 
117  // Custom Callback Queue
118  ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<std_msgs::Bool>(
119  topic_name_, 1,
120  boost::bind(&GazeboRosVacuumGripper::Connect, this),
121  boost::bind(&GazeboRosVacuumGripper::Disconnect, this),
122  ros::VoidPtr(), &queue_);
123  pub_ = rosnode_->advertise(ao);
124 
125  // Custom Callback Queue
127  ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
129  this, _1, _2), ros::VoidPtr(), &queue_);
132  ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
133  "off", boost::bind(&GazeboRosVacuumGripper::OffServiceCallback,
134  this, _1, _2), ros::VoidPtr(), &queue_);
136 
137  // Custom Callback Queue
138  callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosVacuumGripper::QueueThread,this ) );
139 
140  // New Mechanism for Updating every World Cycle
141  // Listen to the update event. This event is broadcast every
142  // simulation iteration.
143  update_connection_ = event::Events::ConnectWorldUpdateBegin(
144  boost::bind(&GazeboRosVacuumGripper::UpdateChild, this));
145 
146  ROS_INFO_NAMED("vacuum_gripper", "Loaded gazebo_ros_vacuum_gripper");
147 }
148 
149 bool GazeboRosVacuumGripper::OnServiceCallback(std_srvs::Empty::Request &req,
150  std_srvs::Empty::Response &res)
151 {
152  if (status_) {
153  ROS_WARN_NAMED("vacuum_gripper", "gazebo_ros_vacuum_gripper: already status is 'on'");
154  } else {
155  status_ = true;
156  ROS_INFO_NAMED("vacuum_gripper", "gazebo_ros_vacuum_gripper: status: off -> on");
157  }
158  return true;
159 }
160 bool GazeboRosVacuumGripper::OffServiceCallback(std_srvs::Empty::Request &req,
161  std_srvs::Empty::Response &res)
162 {
163  if (status_) {
164  status_ = false;
165  ROS_INFO_NAMED("vacuum_gripper", "gazebo_ros_vacuum_gripper: status: on -> off");
166  } else {
167  ROS_WARN_NAMED("vacuum_gripper", "gazebo_ros_vacuum_gripper: already status is 'off'");
168  }
169  return true;
170 }
171 
173 // Update the controller
175 {
176 #ifdef ENABLE_PROFILER
177  IGN_PROFILE("GazeboRosVacuumGripper::UpdateChild");
178 #endif
179  std_msgs::Bool grasping_msg;
180  grasping_msg.data = false;
181  if (!status_) {
182 #ifdef ENABLE_PROFILER
183  IGN_PROFILE_BEGIN("publish status");
184 #endif
185  pub_.publish(grasping_msg);
186 #ifdef ENABLE_PROFILER
187  IGN_PROFILE_END();
188 #endif
189  return;
190  }
191  // apply force
192  lock_.lock();
193 #ifdef ENABLE_PROFILER
194  IGN_PROFILE_BEGIN("apply force");
195 #endif
196 #if GAZEBO_MAJOR_VERSION >= 8
197  ignition::math::Pose3d parent_pose = link_->WorldPose();
198  physics::Model_V models = world_->Models();
199 #else
200  ignition::math::Pose3d parent_pose = link_->GetWorldPose().Ign();
201  physics::Model_V models = world_->GetModels();
202 #endif
203  for (size_t i = 0; i < models.size(); i++) {
204  if (models[i]->GetName() == link_->GetName() ||
205  models[i]->GetName() == parent_->GetName())
206  {
207  continue;
208  }
209  physics::Link_V links = models[i]->GetLinks();
210  for (size_t j = 0; j < links.size(); j++) {
211 #if GAZEBO_MAJOR_VERSION >= 8
212  ignition::math::Pose3d link_pose = links[j]->WorldPose();
213 #else
214  ignition::math::Pose3d link_pose = links[j]->GetWorldPose().Ign();
215 #endif
216  ignition::math::Pose3d diff = parent_pose - link_pose;
217  double norm = diff.Pos().Length();
218  if (norm < 0.05) {
219 #if GAZEBO_MAJOR_VERSION >= 8
220  links[j]->SetLinearVel(link_->WorldLinearVel());
221  links[j]->SetAngularVel(link_->WorldAngularVel());
222 #else
223  links[j]->SetLinearVel(link_->GetWorldLinearVel());
224  links[j]->SetAngularVel(link_->GetWorldAngularVel());
225 #endif
226  double norm_force = 1 / norm;
227  if (norm < 0.01) {
228  // apply friction like force
229  // TODO(unknown): should apply friction actually
230  link_pose.Set(parent_pose.Pos(), link_pose.Rot());
231  links[j]->SetWorldPose(link_pose);
232  }
233  if (norm_force > 20) {
234  norm_force = 20; // max_force
235  }
236  ignition::math::Vector3d force = norm_force * diff.Pos().Normalize();
237  links[j]->AddForce(force);
238  grasping_msg.data = true;
239  }
240  }
241  }
242 #ifdef ENABLE_PROFILER
243  IGN_PROFILE_END();
244  IGN_PROFILE_BEGIN("publish grasping_msg");
245 #endif
246  pub_.publish(grasping_msg);
247 #ifdef ENABLE_PROFILER
248  IGN_PROFILE_END();
249 #endif
250  lock_.unlock();
251 }
252 
253 // Custom Callback Queue
255 // custom callback queue thread
257 {
258  static const double timeout = 0.01;
259 
260  while (rosnode_->ok())
261  {
263  }
264 }
265 
267 // Someone subscribes to me
269 {
270  this->connect_count_++;
271 }
272 
274 // Someone subscribes to me
276 {
277  this->connect_count_--;
278 }
279 
280 } // namespace gazebo
gazebo::GazeboRosVacuumGripper::Load
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Definition: gazebo_ros_vacuum_gripper.cpp:62
gazebo::GazeboRosVacuumGripper::QueueThread
void QueueThread()
The custom callback queue thread function.
Definition: gazebo_ros_vacuum_gripper.cpp:256
boost::shared_ptr< void >
gazebo
gazebo::GazeboRosVacuumGripper::pub_
ros::Publisher pub_
Definition: gazebo_ros_vacuum_gripper.h:132
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosVacuumGripper::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_vacuum_gripper.h:143
gazebo::GazeboRosVacuumGripper::parent_
physics::ModelPtr parent_
Definition: gazebo_ros_vacuum_gripper.h:119
gazebo::GazeboRosVacuumGripper::lock_
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
Definition: gazebo_ros_vacuum_gripper.h:131
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
gazebo::GazeboRosVacuumGripper::~GazeboRosVacuumGripper
virtual ~GazeboRosVacuumGripper()
Destructor.
Definition: gazebo_ros_vacuum_gripper.cpp:47
gazebo::GazeboRosVacuumGripper::OnServiceCallback
bool OnServiceCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: gazebo_ros_vacuum_gripper.cpp:149
gazebo::GazeboRosVacuumGripper::callback_queue_thread_
boost::thread callback_queue_thread_
Thead object for the running callback Thread.
Definition: gazebo_ros_vacuum_gripper.h:148
gazebo::GazeboRosVacuumGripper::status_
bool status_
Definition: gazebo_ros_vacuum_gripper.h:117
gazebo::GazeboRosVacuumGripper::Connect
void Connect()
Definition: gazebo_ros_vacuum_gripper.cpp:268
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::GazeboRosVacuumGripper::OffServiceCallback
bool OffServiceCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: gazebo_ros_vacuum_gripper.cpp:160
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
gazebo::GazeboRosVacuumGripper::world_
physics::WorldPtr world_
A pointer to the gazebo world.
Definition: gazebo_ros_vacuum_gripper.h:122
gazebo::GazeboRosVacuumGripper::link_
physics::LinkPtr link_
A pointer to the Link, where force is applied.
Definition: gazebo_ros_vacuum_gripper.h:125
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosVacuumGripper::UpdateChild
virtual void UpdateChild()
Definition: gazebo_ros_vacuum_gripper.cpp:174
ros::AdvertiseServiceOptions
gazebo::GazeboRosVacuumGripper::link_name_
std::string link_name_
The Link this plugin is attached to, and will exert forces on.
Definition: gazebo_ros_vacuum_gripper.h:140
gazebo::GazeboRosVacuumGripper::rosnode_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition: gazebo_ros_vacuum_gripper.h:128
ros::NodeHandle::ok
bool ok() const
gazebo::GazeboRosVacuumGripper::connect_count_
int connect_count_
: keep track of number of connections
Definition: gazebo_ros_vacuum_gripper.h:154
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosVacuumGripper::srv2_
ros::ServiceServer srv2_
Definition: gazebo_ros_vacuum_gripper.h:134
gazebo::GazeboRosVacuumGripper::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_vacuum_gripper.h:146
gazebo::GazeboRosVacuumGripper::Disconnect
void Disconnect()
Definition: gazebo_ros_vacuum_gripper.cpp:275
gazebo::GazeboRosVacuumGripper::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_vacuum_gripper.h:151
ros::WallDuration
assert.h
gazebo::GazeboRosVacuumGripper::srv1_
ros::ServiceServer srv1_
Definition: gazebo_ros_vacuum_gripper.h:133
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosVacuumGripper::topic_name_
std::string topic_name_
ROS Wrench topic name inputs.
Definition: gazebo_ros_vacuum_gripper.h:137
gazebo_ros_vacuum_gripper.h
gazebo::GazeboRosVacuumGripper::GazeboRosVacuumGripper
GazeboRosVacuumGripper()
Constructor.
Definition: gazebo_ros_vacuum_gripper.cpp:39
ros::CallbackQueue::callAvailable
void callAvailable()
ros::CallbackQueue::disable
void disable()
ros::NodeHandle


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