Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #include <algorithm>
00025 #include <assert.h>
00026
00027 #include <std_msgs/Bool.h>
00028 #include <gazebo_plugins/gazebo_ros_vacuum_gripper.h>
00029
00030
00031 namespace gazebo
00032 {
00033 GZ_REGISTER_MODEL_PLUGIN(GazeboRosVacuumGripper);
00034
00036
00037 GazeboRosVacuumGripper::GazeboRosVacuumGripper()
00038 {
00039 connect_count_ = 0;
00040 status_ = false;
00041 }
00042
00044
00045 GazeboRosVacuumGripper::~GazeboRosVacuumGripper()
00046 {
00047 event::Events::DisconnectWorldUpdateBegin(update_connection_);
00048
00049
00050 queue_.clear();
00051 queue_.disable();
00052 rosnode_->shutdown();
00053 callback_queue_thread_.join();
00054
00055 delete rosnode_;
00056 }
00057
00059
00060 void GazeboRosVacuumGripper::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
00061 {
00062 ROS_INFO("Loading gazebo_ros_vacuum_gripper");
00063
00064
00065 parent_ = _model;
00066
00067
00068 world_ = _model->GetWorld();
00069
00070
00071 robot_namespace_ = "";
00072 if (_sdf->HasElement("robotNamespace"))
00073 robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
00074
00075 if (!_sdf->HasElement("bodyName"))
00076 {
00077 ROS_FATAL("vacuum_gripper plugin missing <bodyName>, cannot proceed");
00078 return;
00079 }
00080 else
00081 link_name_ = _sdf->GetElement("bodyName")->Get<std::string>();
00082
00083 link_ = _model->GetLink(link_name_);
00084 if (!link_)
00085 {
00086 std::string found;
00087 physics::Link_V links = _model->GetLinks();
00088 for (size_t i = 0; i < links.size(); i++) {
00089 found += std::string(" ") + links[i]->GetName();
00090 }
00091 ROS_FATAL("gazebo_ros_vacuum_gripper plugin error: link named: %s does not exist", link_name_.c_str());
00092 ROS_FATAL("gazebo_ros_vacuum_gripper plugin error: You should check it exists and is not connected with fixed joint");
00093 ROS_FATAL("gazebo_ros_vacuum_gripper plugin error: Found links are: %s", found.c_str());
00094 return;
00095 }
00096
00097 if (!_sdf->HasElement("topicName"))
00098 {
00099 ROS_FATAL("vacuum_gripper plugin missing <serviceName>, cannot proceed");
00100 return;
00101 }
00102 else
00103 topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
00104
00105
00106 if (!ros::isInitialized())
00107 {
00108 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00109 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00110 return;
00111 }
00112
00113 rosnode_ = new ros::NodeHandle(robot_namespace_);
00114
00115
00116 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<std_msgs::Bool>(
00117 topic_name_, 1,
00118 boost::bind(&GazeboRosVacuumGripper::Connect, this),
00119 boost::bind(&GazeboRosVacuumGripper::Disconnect, this),
00120 ros::VoidPtr(), &queue_);
00121 pub_ = rosnode_->advertise(ao);
00122
00123
00124 ros::AdvertiseServiceOptions aso1 =
00125 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00126 "on", boost::bind(&GazeboRosVacuumGripper::OnServiceCallback,
00127 this, _1, _2), ros::VoidPtr(), &queue_);
00128 srv1_ = rosnode_->advertiseService(aso1);
00129 ros::AdvertiseServiceOptions aso2 =
00130 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
00131 "off", boost::bind(&GazeboRosVacuumGripper::OffServiceCallback,
00132 this, _1, _2), ros::VoidPtr(), &queue_);
00133 srv2_ = rosnode_->advertiseService(aso2);
00134
00135
00136 callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosVacuumGripper::QueueThread,this ) );
00137
00138
00139
00140
00141 update_connection_ = event::Events::ConnectWorldUpdateBegin(
00142 boost::bind(&GazeboRosVacuumGripper::UpdateChild, this));
00143
00144 ROS_INFO("Loaded gazebo_ros_vacuum_gripper");
00145 }
00146
00147 bool GazeboRosVacuumGripper::OnServiceCallback(std_srvs::Empty::Request &req,
00148 std_srvs::Empty::Response &res)
00149 {
00150 if (status_) {
00151 ROS_WARN("gazebo_ros_vacuum_gripper: already status is 'on'");
00152 } else {
00153 status_ = true;
00154 ROS_INFO("gazebo_ros_vacuum_gripper: status: off -> on");
00155 }
00156 return true;
00157 }
00158 bool GazeboRosVacuumGripper::OffServiceCallback(std_srvs::Empty::Request &req,
00159 std_srvs::Empty::Response &res)
00160 {
00161 if (status_) {
00162 status_ = false;
00163 ROS_INFO("gazebo_ros_vacuum_gripper: status: on -> off");
00164 } else {
00165 ROS_WARN("gazebo_ros_vacuum_gripper: already status is 'off'");
00166 }
00167 return true;
00168 }
00169
00171
00172 void GazeboRosVacuumGripper::UpdateChild()
00173 {
00174 std_msgs::Bool grasping_msg;
00175 grasping_msg.data = false;
00176 if (!status_) {
00177 pub_.publish(grasping_msg);
00178 return;
00179 }
00180
00181 lock_.lock();
00182 math::Pose parent_pose = link_->GetWorldPose();
00183 physics::Model_V models = world_->GetModels();
00184 for (size_t i = 0; i < models.size(); i++) {
00185 if (models[i]->GetName() == link_->GetName() ||
00186 models[i]->GetName() == parent_->GetName())
00187 {
00188 continue;
00189 }
00190 physics::Link_V links = models[i]->GetLinks();
00191 for (size_t j = 0; j < links.size(); j++) {
00192 math::Pose link_pose = links[j]->GetWorldPose();
00193 math::Pose diff = parent_pose - link_pose;
00194 double norm = diff.pos.GetLength();
00195 if (norm < 0.05) {
00196 links[j]->SetLinearAccel(link_->GetWorldLinearAccel());
00197 links[j]->SetAngularAccel(link_->GetWorldAngularAccel());
00198 links[j]->SetLinearVel(link_->GetWorldLinearVel());
00199 links[j]->SetAngularVel(link_->GetWorldAngularVel());
00200 double norm_force = 1 / norm;
00201 if (norm < 0.01) {
00202
00203
00204 link_pose.Set(parent_pose.pos, link_pose.rot);
00205 links[j]->SetWorldPose(link_pose);
00206 }
00207 if (norm_force > 20) {
00208 norm_force = 20;
00209 }
00210 math::Vector3 force = norm_force * diff.pos.Normalize();
00211 links[j]->AddForce(force);
00212 grasping_msg.data = true;
00213 }
00214 }
00215 }
00216 pub_.publish(grasping_msg);
00217 lock_.unlock();
00218 }
00219
00220
00222
00223 void GazeboRosVacuumGripper::QueueThread()
00224 {
00225 static const double timeout = 0.01;
00226
00227 while (rosnode_->ok())
00228 {
00229 queue_.callAvailable(ros::WallDuration(timeout));
00230 }
00231 }
00232
00234
00235 void GazeboRosVacuumGripper::Connect()
00236 {
00237 this->connect_count_++;
00238 }
00239
00241
00242 void GazeboRosVacuumGripper::Disconnect()
00243 {
00244 this->connect_count_--;
00245 }
00246
00247 }