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 <gazebo_plugins/gazebo_ros_force.h>
00028
00029 namespace gazebo
00030 {
00031 GZ_REGISTER_MODEL_PLUGIN(GazeboRosForce);
00032
00034
00035 GazeboRosForce::GazeboRosForce()
00036 {
00037 this->wrench_msg_.force.x = 0;
00038 this->wrench_msg_.force.y = 0;
00039 this->wrench_msg_.force.z = 0;
00040 this->wrench_msg_.torque.x = 0;
00041 this->wrench_msg_.torque.y = 0;
00042 this->wrench_msg_.torque.z = 0;
00043 }
00044
00046
00047 GazeboRosForce::~GazeboRosForce()
00048 {
00049 event::Events::DisconnectWorldUpdateBegin(this->update_connection_);
00050
00051
00052 this->queue_.clear();
00053 this->queue_.disable();
00054 this->rosnode_->shutdown();
00055 this->callback_queue_thread_.join();
00056
00057 delete this->rosnode_;
00058 }
00059
00061
00062 void GazeboRosForce::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
00063 {
00064
00065 this->world_ = _model->GetWorld();
00066
00067
00068 this->robot_namespace_ = "";
00069 if (_sdf->HasElement("robotNamespace"))
00070 this->robot_namespace_ = _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
00071
00072 if (!_sdf->HasElement("bodyName"))
00073 {
00074 ROS_FATAL("force plugin missing <bodyName>, cannot proceed");
00075 return;
00076 }
00077 else
00078 this->link_name_ = _sdf->GetElement("bodyName")->Get<std::string>();
00079
00080 this->link_ = _model->GetLink(this->link_name_);
00081 if (!this->link_)
00082 {
00083 ROS_FATAL("gazebo_ros_force plugin error: link named: %s does not exist\n",this->link_name_.c_str());
00084 return;
00085 }
00086
00087 if (!_sdf->HasElement("topicName"))
00088 {
00089 ROS_FATAL("force plugin missing <topicName>, cannot proceed");
00090 return;
00091 }
00092 else
00093 this->topic_name_ = _sdf->GetElement("topicName")->Get<std::string>();
00094
00095
00096
00097 if (!ros::isInitialized())
00098 {
00099 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00100 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00101 return;
00102 }
00103
00104 this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00105
00106
00107 ros::SubscribeOptions so = ros::SubscribeOptions::create<geometry_msgs::Wrench>(
00108 this->topic_name_,1,
00109 boost::bind( &GazeboRosForce::UpdateObjectForce,this,_1),
00110 ros::VoidPtr(), &this->queue_);
00111 this->sub_ = this->rosnode_->subscribe(so);
00112
00113
00114 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosForce::QueueThread,this ) );
00115
00116
00117
00118
00119 this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
00120 boost::bind(&GazeboRosForce::UpdateChild, this));
00121 }
00122
00124
00125 void GazeboRosForce::UpdateObjectForce(const geometry_msgs::Wrench::ConstPtr& _msg)
00126 {
00127 this->wrench_msg_.force.x = _msg->force.x;
00128 this->wrench_msg_.force.y = _msg->force.y;
00129 this->wrench_msg_.force.z = _msg->force.z;
00130 this->wrench_msg_.torque.x = _msg->torque.x;
00131 this->wrench_msg_.torque.y = _msg->torque.y;
00132 this->wrench_msg_.torque.z = _msg->torque.z;
00133 }
00134
00136
00137 void GazeboRosForce::UpdateChild()
00138 {
00139 this->lock_.lock();
00140 math::Vector3 force(this->wrench_msg_.force.x,this->wrench_msg_.force.y,this->wrench_msg_.force.z);
00141 math::Vector3 torque(this->wrench_msg_.torque.x,this->wrench_msg_.torque.y,this->wrench_msg_.torque.z);
00142 this->link_->AddForce(force);
00143 this->link_->AddTorque(torque);
00144 this->lock_.unlock();
00145 }
00146
00147
00149
00150 void GazeboRosForce::QueueThread()
00151 {
00152 static const double timeout = 0.01;
00153
00154 while (this->rosnode_->ok())
00155 {
00156 this->queue_.callAvailable(ros::WallDuration(timeout));
00157 }
00158 }
00159
00160 }