27 #include <std_msgs/Bool.h>
29 #ifdef ENABLE_PROFILER
30 #include <ignition/common/Profiler.hh>
64 ROS_INFO_NAMED(
"vacuum_gripper",
"Loading gazebo_ros_vacuum_gripper");
70 world_ = _model->GetWorld();
74 if (_sdf->HasElement(
"robotNamespace"))
75 robot_namespace_ = _sdf->GetElement(
"robotNamespace")->Get<std::string>() +
"/";
77 if (!_sdf->HasElement(
"bodyName"))
79 ROS_FATAL_NAMED(
"vacuum_gripper",
"vacuum_gripper plugin missing <bodyName>, cannot proceed");
83 link_name_ = _sdf->GetElement(
"bodyName")->Get<std::string>();
89 physics::Link_V links = _model->GetLinks();
90 for (
size_t i = 0; i < links.size(); i++) {
91 found += std::string(
" ") + links[i]->GetName();
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());
99 if (!_sdf->HasElement(
"topicName"))
101 ROS_FATAL_NAMED(
"vacuum_gripper",
"vacuum_gripper plugin missing <serviceName>, cannot proceed");
105 topic_name_ = _sdf->GetElement(
"topicName")->Get<std::string>();
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)");
127 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
132 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
146 ROS_INFO_NAMED(
"vacuum_gripper",
"Loaded gazebo_ros_vacuum_gripper");
150 std_srvs::Empty::Response &res)
153 ROS_WARN_NAMED(
"vacuum_gripper",
"gazebo_ros_vacuum_gripper: already status is 'on'");
156 ROS_INFO_NAMED(
"vacuum_gripper",
"gazebo_ros_vacuum_gripper: status: off -> on");
161 std_srvs::Empty::Response &res)
165 ROS_INFO_NAMED(
"vacuum_gripper",
"gazebo_ros_vacuum_gripper: status: on -> off");
167 ROS_WARN_NAMED(
"vacuum_gripper",
"gazebo_ros_vacuum_gripper: already status is 'off'");
176 #ifdef ENABLE_PROFILER
177 IGN_PROFILE(
"GazeboRosVacuumGripper::UpdateChild");
179 std_msgs::Bool grasping_msg;
180 grasping_msg.data =
false;
182 #ifdef ENABLE_PROFILER
183 IGN_PROFILE_BEGIN(
"publish status");
186 #ifdef ENABLE_PROFILER
193 #ifdef ENABLE_PROFILER
194 IGN_PROFILE_BEGIN(
"apply force");
196 #if GAZEBO_MAJOR_VERSION >= 8
197 ignition::math::Pose3d parent_pose =
link_->WorldPose();
198 physics::Model_V models =
world_->Models();
200 ignition::math::Pose3d parent_pose =
link_->GetWorldPose().Ign();
201 physics::Model_V models =
world_->GetModels();
203 for (
size_t i = 0; i < models.size(); i++) {
204 if (models[i]->GetName() ==
link_->GetName() ||
205 models[i]->GetName() ==
parent_->GetName())
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();
214 ignition::math::Pose3d link_pose = links[j]->GetWorldPose().Ign();
216 ignition::math::Pose3d diff = parent_pose - link_pose;
217 double norm = diff.Pos().Length();
219 #if GAZEBO_MAJOR_VERSION >= 8
220 links[j]->SetLinearVel(
link_->WorldLinearVel());
221 links[j]->SetAngularVel(
link_->WorldAngularVel());
223 links[j]->SetLinearVel(
link_->GetWorldLinearVel());
224 links[j]->SetAngularVel(
link_->GetWorldAngularVel());
226 double norm_force = 1 / norm;
230 link_pose.Set(parent_pose.Pos(), link_pose.Rot());
231 links[j]->SetWorldPose(link_pose);
233 if (norm_force > 20) {
236 ignition::math::Vector3d force = norm_force * diff.Pos().Normalize();
237 links[j]->AddForce(force);
238 grasping_msg.data =
true;
242 #ifdef ENABLE_PROFILER
244 IGN_PROFILE_BEGIN(
"publish grasping_msg");
247 #ifdef ENABLE_PROFILER
258 static const double timeout = 0.01;