$search
00001 /* 00002 * Gazebo - Outdoor Multi-Robot Simulator 00003 * Copyright (C) 2003 00004 * Nate Koenig & Andrew Howard 00005 * 00006 * This program is free software; you can redistribute it and/or modify 00007 * it under the terms of the GNU General Public License as published by 00008 * the Free Software Foundation; either version 2 of the License, or 00009 * (at your option) any later version. 00010 * 00011 * This program is distributed in the hope that it will be useful, 00012 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 * GNU General Public License for more details. 00015 * 00016 * You should have received a copy of the GNU General Public License 00017 * along with this program; if not, write to the Free Software 00018 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00019 * 00020 */ 00021 /* 00022 @mainpage 00023 Desc: GazeboRosForce plugin for manipulating objects in Gazebo 00024 Author: John Hsu 00025 Date: 24 Sept 2008 00026 SVN info: $Id$ 00027 @htmlinclude manifest.html 00028 @b GazeboRosForce plugin reads ROS geometry_msgs/Wrench messages 00029 */ 00030 00031 #include <algorithm> 00032 #include <assert.h> 00033 00034 #include <gazebo_plugins/gazebo_ros_force.h> 00035 00036 #include <gazebo/Sensor.hh> 00037 #include <gazebo/Global.hh> 00038 #include <gazebo/XMLConfig.hh> 00039 #include <gazebo/Simulator.hh> 00040 #include <gazebo/gazebo.h> 00041 #include <gazebo/World.hh> 00042 #include <gazebo/PhysicsEngine.hh> 00043 #include <gazebo/GazeboError.hh> 00044 #include <gazebo/ControllerFactory.hh> 00045 00046 using namespace gazebo; 00047 00048 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_force", GazeboRosForce); 00049 00051 // Constructor 00052 GazeboRosForce::GazeboRosForce(Entity *parent) 00053 : Controller(parent) 00054 { 00055 this->myParent = dynamic_cast<Model*>(this->parent); 00056 00057 if (!this->myParent) 00058 gzthrow("GazeboRosForce controller requires an Model as its parent"); 00059 00060 Param::Begin(&this->parameters); 00061 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0); 00062 this->topicNameP = new ParamT<std::string>("topicName","", 1); 00063 this->bodyNameP = new ParamT<std::string>("bodyName","link", 1); 00064 Param::End(); 00065 00066 if (!ros::isInitialized()) 00067 { 00068 int argc = 0; 00069 char** argv = NULL; 00070 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00071 } 00072 00073 this->rosnode_ = new ros::NodeHandle(); 00074 00075 this->wrench.force.x = 0; 00076 this->wrench.force.y = 0; 00077 this->wrench.force.z = 0; 00078 this->wrench.torque.x = 0; 00079 this->wrench.torque.y = 0; 00080 this->wrench.torque.z = 0; 00081 } 00082 00084 // Destructor 00085 GazeboRosForce::~GazeboRosForce() 00086 { 00087 delete this->robotNamespaceP; 00088 delete this->rosnode_; 00089 00090 delete this->topicNameP; 00091 delete this->bodyNameP; 00092 00093 } 00094 00096 // Load the controller 00097 void GazeboRosForce::LoadChild(XMLConfigNode *node) 00098 { 00099 this->robotNamespaceP->Load(node); 00100 this->robotNamespace = this->robotNamespaceP->GetValue(); 00101 00102 int argc = 0; 00103 char** argv = NULL; 00104 ros::init(argc,argv,"gazebo"); 00105 this->rosnode_ = new ros::NodeHandle(this->robotNamespace); 00106 00107 this->topicNameP->Load(node); 00108 this->bodyNameP->Load(node); 00109 00110 this->topicName = this->topicNameP->GetValue(); 00111 this->bodyName = this->bodyNameP->GetValue(); 00112 00113 00114 // assert that the body by bodyName exists 00115 if (dynamic_cast<Body*>(this->myParent->GetBody(bodyName)) == NULL) 00116 ROS_FATAL("gazebo_ros_force plugin error: bodyName: %s does not exist\n",bodyName.c_str()); 00117 00118 this->myBody = dynamic_cast<Body*>(this->myParent->GetBody(bodyName)); 00119 00120 // check update rate against world physics update rate 00121 // should be equal or higher to guarantee the wrench applied is not "diluted" 00122 if (this->updatePeriod > 0 && 00123 //(gazebo::World::Instance()->GetPhysicsEngine()->GetUpdateRate() > 1.0/this->updatePeriod.Double())) 00124 (gazebo::World::Instance()->GetPhysicsEngine()->GetUpdateRate() > 1.0/this->updatePeriod)) 00125 ROS_ERROR("gazebo_ros_force controller update rate is less than physics update rate, wrench applied will be diluted (applied intermittently)"); 00126 00127 // Custom Callback Queue 00128 ros::SubscribeOptions so = ros::SubscribeOptions::create<geometry_msgs::Wrench>( 00129 this->topicName,1, 00130 boost::bind( &GazeboRosForce::UpdateObjectForce,this,_1), 00131 ros::VoidPtr(), &this->queue_); 00132 this->sub_ = this->rosnode_->subscribe(so); 00133 } 00134 00136 // Initialize the controller 00137 void GazeboRosForce::InitChild() 00138 { 00139 // Custom Callback Queue 00140 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosForce::QueueThread,this ) ); 00141 } 00142 00144 // Update the controller 00145 void GazeboRosForce::UpdateObjectForce(const geometry_msgs::Wrench::ConstPtr& wrenchMsg) 00146 { 00147 this->wrench.force.x = wrenchMsg->force.x; 00148 this->wrench.force.y = wrenchMsg->force.y; 00149 this->wrench.force.z = wrenchMsg->force.z; 00150 this->wrench.torque.x = wrenchMsg->torque.x; 00151 this->wrench.torque.y = wrenchMsg->torque.y; 00152 this->wrench.torque.z = wrenchMsg->torque.z; 00153 } 00154 00156 // Update the controller 00157 void GazeboRosForce::UpdateChild() 00158 { 00159 00160 this->lock.lock(); 00161 Vector3 force(this->wrench.force.x,this->wrench.force.y,this->wrench.force.z); 00162 Vector3 torque(this->wrench.torque.x,this->wrench.torque.y,this->wrench.torque.z); 00163 this->myBody->SetForce(force); 00164 this->myBody->SetTorque(torque); 00165 this->lock.unlock(); 00166 00167 } 00168 00170 // Finalize the controller 00171 void GazeboRosForce::FiniChild() 00172 { 00173 // Custom Callback Queue 00174 this->queue_.clear(); 00175 this->queue_.disable(); 00176 this->rosnode_->shutdown(); 00177 this->callback_queue_thread_.join(); 00178 } 00179 00180 // Custom Callback Queue 00182 // custom callback queue thread 00183 void GazeboRosForce::QueueThread() 00184 { 00185 static const double timeout = 0.01; 00186 00187 while (this->rosnode_->ok()) 00188 { 00189 this->queue_.callAvailable(ros::WallDuration(timeout)); 00190 } 00191 } 00192