$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: Force Feed Back Ground Truth 00024 Author: Sachin Chitta and John Hsu 00025 Date: 1 June 2008 00026 SVN info: $Id$ 00027 @htmlinclude manifest.html 00028 @b GazeboRosF3D plugin broadcasts forces acting on the body specified by name. 00029 */ 00030 00031 #include <gazebo_plugins/gazebo_ros_f3d.h> 00032 00033 #include <gazebo/Global.hh> 00034 #include <gazebo/XMLConfig.hh> 00035 #include <gazebo/HingeJoint.hh> 00036 #include <gazebo/SliderJoint.hh> 00037 #include <gazebo/Simulator.hh> 00038 #include <gazebo/gazebo.h> 00039 #include <gazebo/GazeboError.hh> 00040 #include <gazebo/ControllerFactory.hh> 00041 00042 using namespace gazebo; 00043 00044 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_f3d", GazeboRosF3D); 00045 00046 00048 // Constructor 00049 GazeboRosF3D::GazeboRosF3D(Entity *parent ) 00050 : Controller(parent) 00051 { 00052 this->myParent = dynamic_cast<Model*>(this->parent); 00053 00054 if (!this->myParent) 00055 gzthrow("GazeboRosF3D controller requires a Model as its parent"); 00056 00057 Param::Begin(&this->parameters); 00058 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0); 00059 this->bodyNameP = new ParamT<std::string>("bodyName", "", 0); 00060 this->topicNameP = new ParamT<std::string>("topicName", "", 1); 00061 this->frameNameP = new ParamT<std::string>("frameName", "default_f3d_frame", 0); 00062 Param::End(); 00063 00064 this->f3dConnectCount = 0; 00065 } 00066 00068 // Destructor 00069 GazeboRosF3D::~GazeboRosF3D() 00070 { 00071 delete this->robotNamespaceP; 00072 delete this->bodyNameP; 00073 delete this->topicNameP; 00074 delete this->frameNameP; 00075 delete this->rosnode_; 00076 } 00077 00079 // Load the controller 00080 void GazeboRosF3D::LoadChild(XMLConfigNode *node) 00081 { 00082 00083 this->robotNamespaceP->Load(node); 00084 this->robotNamespace = this->robotNamespaceP->GetValue(); 00085 if (!ros::isInitialized()) 00086 { 00087 int argc = 0; 00088 char** argv = NULL; 00089 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00090 } 00091 00092 this->rosnode_ = new ros::NodeHandle(this->robotNamespace); 00093 00094 this->bodyNameP->Load(node); 00095 this->bodyName = this->bodyNameP->GetValue(); 00096 this->myBody = dynamic_cast<Body*>(this->myParent->GetBody(bodyName)); 00097 if (!this->myBody) 00098 ROS_FATAL("gazebo_ros_f3d plugin error: bodyName: %s does not exist\n",bodyName.c_str()); 00099 00100 this->topicNameP->Load(node); 00101 this->topicName = this->topicNameP->GetValue(); 00102 this->frameNameP->Load(node); 00103 this->frameName = this->frameNameP->GetValue(); 00104 00105 // Custom Callback Queue 00106 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<geometry_msgs::WrenchStamped>( 00107 this->topicName,1, 00108 boost::bind( &GazeboRosF3D::F3DConnect,this), 00109 boost::bind( &GazeboRosF3D::F3DDisconnect,this), ros::VoidPtr(), &this->queue_); 00110 this->pub_ = this->rosnode_->advertise(ao); 00111 } 00112 00114 // Someone subscribes to me 00115 void GazeboRosF3D::F3DConnect() 00116 { 00117 this->f3dConnectCount++; 00118 } 00119 00121 // Someone subscribes to me 00122 void GazeboRosF3D::F3DDisconnect() 00123 { 00124 this->f3dConnectCount--; 00125 } 00126 00128 // Initialize the controller 00129 void GazeboRosF3D::InitChild() 00130 { 00131 // Custom Callback Queue 00132 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosF3D::QueueThread,this ) ); 00133 } 00134 00136 // Update the controller 00137 void GazeboRosF3D::UpdateChild() 00138 { 00139 if (this->f3dConnectCount == 0) 00140 return; 00141 00142 Vector3 torque; 00143 Vector3 force; 00144 00145 // get force on body 00146 force = this->myBody->GetWorldForce(); 00147 00148 // get torque on body 00149 torque = this->myBody->GetWorldTorque(); 00150 00151 this->lock.lock(); 00152 // copy data into wrench message 00153 this->wrenchMsg.header.frame_id = this->frameName; 00154 this->wrenchMsg.header.stamp.sec = (Simulator::Instance()->GetSimTime()).sec; 00155 this->wrenchMsg.header.stamp.nsec = (Simulator::Instance()->GetSimTime()).nsec; 00156 00157 this->wrenchMsg.wrench.force.x = force.x; 00158 this->wrenchMsg.wrench.force.y = force.y; 00159 this->wrenchMsg.wrench.force.z = force.z; 00160 this->wrenchMsg.wrench.torque.x = torque.x; 00161 this->wrenchMsg.wrench.torque.y = torque.y; 00162 this->wrenchMsg.wrench.torque.z = torque.z; 00163 00164 this->pub_.publish(this->wrenchMsg); 00165 this->lock.unlock(); 00166 00167 } 00168 00170 // Finalize the controller 00171 void GazeboRosF3D::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 GazeboRosF3D::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 }