$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 * Desc: Empty gazebo plugin 00023 * Author: John Hsu 00024 * Date: 24 July 2009 00025 * SVN info: $Id$ 00026 */ 00027 00028 00029 #include <algorithm> 00030 #include <assert.h> 00031 00032 #include <gazebo_plugins/gazebo_ros_step_world_state.h> 00033 00034 #include <gazebo/Global.hh> 00035 #include <gazebo/XMLConfig.hh> 00036 #include <gazebo/gazebo.h> 00037 #include <gazebo/GazeboError.hh> 00038 #include <gazebo/ControllerFactory.hh> 00039 00040 #include <boost/thread.hpp> 00041 #include <boost/bind.hpp> 00042 00043 using namespace gazebo; 00044 00045 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_step_world_state", GazeboRosStepWorldState); 00046 00048 // Constructor 00049 GazeboRosStepWorldState::GazeboRosStepWorldState(Entity *parent) 00050 : Controller(parent) 00051 { 00052 this->parent_model_ = dynamic_cast<Model*>(this->parent); 00053 00054 if (!this->parent_model_) 00055 gzthrow("GazeboMechanismControl controller requires a Model as its parent"); 00056 00057 Param::Begin(&this->parameters); 00058 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0); 00059 this->topicNameP = new ParamT<std::string>("topicName", "", 1); 00060 this->frameNameP = new ParamT<std::string>("frameName", "base_link", 0); 00061 Param::End(); 00062 00063 this->all_bodies.clear(); 00064 this->models.clear(); 00065 } 00066 00068 // Destructor 00069 GazeboRosStepWorldState::~GazeboRosStepWorldState() 00070 { 00071 delete this->robotNamespaceP; 00072 delete this->topicNameP; 00073 delete this->frameNameP; 00074 delete this->rosnode_; 00075 } 00076 00078 // Load the controller 00079 void GazeboRosStepWorldState::LoadChild(XMLConfigNode *node) 00080 { 00081 this->robotNamespaceP->Load(node); 00082 this->robotNamespace = this->robotNamespaceP->GetValue(); 00083 00084 if (!ros::isInitialized()) 00085 { 00086 int argc = 0; 00087 char** argv = NULL; 00088 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00089 } 00090 this->rosnode_ = new ros::NodeHandle(this->robotNamespace); 00091 00092 this->topicNameP->Load(node); 00093 this->topicName = this->topicNameP->GetValue(); 00094 this->frameNameP->Load(node); 00095 this->frameName = this->frameNameP->GetValue(); 00096 00097 // Custom Callback Queue 00098 ros::SubscribeOptions so = ros::SubscribeOptions::create<gazebo_msgs::WorldState>( 00099 this->topicName,1, 00100 boost::bind( &GazeboRosStepWorldState::WorldStateCallback,this,_1), 00101 ros::VoidPtr(), &this->queue_); 00102 this->sub_ = this->rosnode_->subscribe(so); 00103 00104 } 00105 00107 // Someone subscribes to me 00108 void GazeboRosStepWorldState::WorldStateCallback(const gazebo_msgs::WorldStateConstPtr& worldStateMsg) 00109 { 00110 ROS_DEBUG("received state message"); 00111 00112 // get information from message 00113 // ignore frame_id for now, everything inertial. this->worldStateMsg->header.frame_id 00114 gazebo::Simulator::Instance()->SetSimTime(worldStateMsg->header.stamp.toSec()); 00115 00116 int object_count = worldStateMsg->name.size(); 00117 00118 for (int count = 0; count < object_count; count++) 00119 { 00120 boost::recursive_mutex::scoped_lock lock(*gazebo::Simulator::Instance()->GetMRMutex()); 00121 std::map<std::string,gazebo::Body*>::iterator body = this->all_bodies.find(worldStateMsg->name[count]); 00122 if (body == this->all_bodies.end()) 00123 { 00124 //ROS_ERROR("body %s is not in this world!",worldStateMsg->name[count].c_str()); 00125 } 00126 else 00127 { 00128 //ROS_ERROR("setting pose for body %s.",worldStateMsg->name[count].c_str()); 00129 Vector3 pos; 00130 Quatern rot; 00131 pos.x = worldStateMsg->pose[count].position.x; 00132 pos.y = worldStateMsg->pose[count].position.y; 00133 pos.z = worldStateMsg->pose[count].position.z; 00134 rot.x = worldStateMsg->pose[count].orientation.x; 00135 rot.y = worldStateMsg->pose[count].orientation.y; 00136 rot.z = worldStateMsg->pose[count].orientation.z; 00137 rot.u = worldStateMsg->pose[count].orientation.w; 00138 body->second->SetWorldPose(Pose3d(pos,rot)); 00139 } 00140 } 00141 00142 } 00143 00145 // Initialize the controller 00146 void GazeboRosStepWorldState::InitChild() 00147 { 00148 // Custom Callback Queue 00149 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosStepWorldState::QueueThread,this ) ); 00150 } 00151 00153 // Update the controller 00154 void GazeboRosStepWorldState::UpdateChild() 00155 { 00156 00157 /********************************************************************/ 00158 /* */ 00159 /* build list of all bodies in the world (across models) */ 00160 /* */ 00161 /* need a faster way to hook up each body with incoming states */ 00162 /* */ 00163 /********************************************************************/ 00164 00165 // FIXME: this test simply checks the number of models for now, better 00166 // to setup a flag to indicate whether models in the world have changed 00167 if (this->models.size() != gazebo::World::Instance()->GetModels().size()) 00168 { 00169 this->models = gazebo::World::Instance()->GetModels(); 00170 00171 // aggregate all bodies into a single vector 00172 for (std::vector<gazebo::Model*>::iterator miter = this->models.begin(); miter != this->models.end(); miter++) 00173 { 00174 // list of all bodies in the current model 00175 const std::vector<gazebo::Entity*> entities = (*miter)->GetChildren(); 00176 // Iterate through all bodies 00177 std::vector<Entity*>::const_iterator eiter; 00178 for (eiter=entities.begin(); eiter!=entities.end(); eiter++) 00179 { 00180 gazebo::Body* body = dynamic_cast<gazebo::Body*>(*eiter); 00181 if (body) 00182 this->all_bodies.insert(make_pair(body->GetName(),body)); 00183 } 00184 } 00185 } 00186 //ROS_ERROR("debug: %d",this->all_bodies.size()); 00187 00188 } 00189 00191 // Finalize the controller 00192 void GazeboRosStepWorldState::FiniChild() 00193 { 00194 // Custom Callback Queue 00195 this->queue_.clear(); 00196 this->queue_.disable(); 00197 this->rosnode_->shutdown(); 00198 this->callback_queue_thread_.join(); 00199 } 00200 00201 // Custom Callback Queue 00203 // custom callback queue thread 00204 void GazeboRosStepWorldState::QueueThread() 00205 { 00206 static const double timeout = 0.01; 00207 00208 while (this->rosnode_->ok()) 00209 { 00210 this->queue_.callAvailable(ros::WallDuration(timeout)); 00211 } 00212 } 00213 00214