$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_pub_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 #include <boost/bind.hpp> 00040 00041 using namespace gazebo; 00042 00043 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_pub_world_state", GazeboRosPubWorldState); 00044 00046 // Constructor 00047 GazeboRosPubWorldState::GazeboRosPubWorldState(Entity *parent) 00048 : Controller(parent) 00049 { 00050 this->parent_model_ = dynamic_cast<Model*>(this->parent); 00051 00052 if (!this->parent_model_) 00053 gzthrow("GazeboMechanismControl controller requires a Model as its parent"); 00054 00055 Param::Begin(&this->parameters); 00056 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0); 00057 this->topicNameP = new ParamT<std::string>("topicName", "", 1); 00058 this->frameNameP = new ParamT<std::string>("frameName", "base_link", 0); 00059 Param::End(); 00060 00061 this->worldStateConnectCount = 0; 00062 } 00063 00065 // Destructor 00066 GazeboRosPubWorldState::~GazeboRosPubWorldState() 00067 { 00068 delete this->robotNamespaceP; 00069 delete this->topicNameP; 00070 delete this->frameNameP; 00071 delete this->rosnode_; 00072 } 00073 00075 // Load the controller 00076 void GazeboRosPubWorldState::LoadChild(XMLConfigNode *node) 00077 { 00078 this->robotNamespaceP->Load(node); 00079 this->robotNamespace = this->robotNamespaceP->GetValue(); 00080 00081 if (!ros::isInitialized()) 00082 { 00083 int argc = 0; 00084 char** argv = NULL; 00085 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00086 } 00087 00088 this->rosnode_ = new ros::NodeHandle(this->robotNamespace); 00089 00090 this->topicNameP->Load(node); 00091 this->topicName = this->topicNameP->GetValue(); 00092 this->frameNameP->Load(node); 00093 this->frameName = this->frameNameP->GetValue(); 00094 00095 // Custom Callback Queue 00096 ros::AdvertiseOptions ao = ros::AdvertiseOptions::create<gazebo_msgs::WorldState>( 00097 this->topicName,1, 00098 boost::bind( &GazeboRosPubWorldState::WorldStateConnect,this), 00099 boost::bind( &GazeboRosPubWorldState::WorldStateDisconnect,this), ros::VoidPtr(), &this->queue_); 00100 this->pub_ = this->rosnode_->advertise(ao); 00101 00102 } 00103 00105 // Someone subscribes to me 00106 void GazeboRosPubWorldState::WorldStateConnect() 00107 { 00108 this->worldStateConnectCount++; 00109 } 00110 00112 // Someone subscribes to me 00113 void GazeboRosPubWorldState::WorldStateDisconnect() 00114 { 00115 this->worldStateConnectCount--; 00116 } 00117 00119 // Initialize the controller 00120 void GazeboRosPubWorldState::InitChild() 00121 { 00122 // Custom Callback Queue 00123 this->callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosPubWorldState::QueueThread,this ) ); 00124 } 00125 00127 // Update the controller 00128 void GazeboRosPubWorldState::UpdateChild() 00129 { 00130 /***************************************************************/ 00131 /* */ 00132 /* this is called at every update simulation step */ 00133 /* */ 00134 /***************************************************************/ 00135 if (this->worldStateConnectCount == 0) 00136 return; 00137 00138 /***************************************************************/ 00139 /* */ 00140 /* publish */ 00141 /* */ 00142 /***************************************************************/ 00143 Time cur_time = Simulator::Instance()->GetSimTime(); 00144 00146 std::vector<gazebo::Model*> models; 00147 std::vector<gazebo::Model*>::iterator miter; 00148 00150 std::map<std::string,gazebo::Body*> all_bodies; 00151 all_bodies.clear(); 00152 00153 models = gazebo::World::Instance()->GetModels(); 00154 00155 // aggregate all bodies into a single vector 00156 for (miter = models.begin(); miter != models.end(); miter++) 00157 { 00158 const std::vector<gazebo::Entity*> entities = (*miter)->GetChildren(); 00159 // Iterate through all bodies 00160 std::vector<Entity*>::const_iterator eiter; 00161 for (eiter=entities.begin(); eiter!=entities.end(); eiter++) 00162 { 00163 gazebo::Body* body = dynamic_cast<gazebo::Body*>(*eiter); 00164 if (body) 00165 all_bodies.insert(make_pair(body->GetName(),body)); 00166 } 00167 } 00168 //ROS_ERROR("debug: %d",all_bodies.size()); 00169 00170 // construct world state message 00171 if (!all_bodies.empty()) 00172 { 00173 this->lock.lock(); 00174 00175 // compose worldStateMsg 00176 this->worldStateMsg.header.frame_id = this->frameName; 00177 this->worldStateMsg.header.stamp.fromSec(cur_time.Double()); 00178 00179 // Iterate through all_bodies 00180 std::map<std::string, Body*>::iterator biter; 00181 for (biter=all_bodies.begin(); biter!=all_bodies.end(); biter++) 00182 { 00183 //ROS_ERROR("body name: %s",(biter->second)->GetName().c_str()); 00184 // get name 00185 this->worldStateMsg.name.push_back(std::string(biter->second->GetName())); 00186 00187 // set pose 00188 // get pose from simulator 00189 Pose3d pose; 00190 Quatern rot; 00191 Vector3 pos; 00192 // Get Pose/Orientation ///@todo: verify correctness 00193 pose = (biter->second)->GetWorldPose(); 00194 00195 // apply xyz offsets and get position and rotation components 00196 pos = pose.pos; // (add if there's offset) + this->xyzOffsets; 00197 rot = pose.rot; 00198 // apply rpy offsets 00199 /* add if there's offsets 00200 Quatern qOffsets; 00201 qOffsets.SetFromEuler(this->rpyOffsets); 00202 rot = qOffsets*rot; 00203 rot.Normalize(); 00204 */ 00205 geometry_msgs::Pose geom_pose; 00206 geom_pose.position.x = pos.x; 00207 geom_pose.position.y = pos.y; 00208 geom_pose.position.z = pos.z; 00209 geom_pose.orientation.x = rot.x; 00210 geom_pose.orientation.y = rot.y; 00211 geom_pose.orientation.z = rot.z; 00212 geom_pose.orientation.w = rot.u; 00213 this->worldStateMsg.pose.push_back(geom_pose); 00214 00215 // set velocities 00216 // get Rates 00217 Vector3 vpos = (biter->second)->GetWorldLinearVel(); // get velocity in gazebo frame 00218 Vector3 veul = (biter->second)->GetWorldAngularVel(); // get velocity in gazebo frame 00219 00220 // pass linear rates 00221 geometry_msgs::Twist geom_twist; 00222 geom_twist.linear.x = vpos.x; 00223 geom_twist.linear.y = vpos.y; 00224 geom_twist.linear.z = vpos.z; 00225 // pass euler angular rates 00226 geom_twist.angular.x = veul.x; 00227 geom_twist.angular.y = veul.y; 00228 geom_twist.angular.z = veul.z; 00229 this->worldStateMsg.twist.push_back(geom_twist); 00230 00231 // get forces 00232 Vector3 force = (biter->second)->GetWorldForce(); // get velocity in gazebo frame 00233 Vector3 torque = (biter->second)->GetWorldTorque(); // get velocity in gazebo frame 00234 geometry_msgs::Wrench geom_wrench; 00235 geom_wrench.force.x = force.x; 00236 geom_wrench.force.y = force.y; 00237 geom_wrench.force.z = force.z; 00238 geom_wrench.torque.x = torque.x; 00239 geom_wrench.torque.y = torque.y; 00240 geom_wrench.torque.z = torque.z; 00241 this->worldStateMsg.wrench.push_back(geom_wrench); 00242 00243 } 00244 this->pub_.publish(this->worldStateMsg); 00245 this->lock.unlock(); 00246 00247 } 00248 } 00249 00251 // Finalize the controller 00252 void GazeboRosPubWorldState::FiniChild() 00253 { 00254 // Custom Callback Queue 00255 this->queue_.clear(); 00256 this->queue_.disable(); 00257 this->rosnode_->shutdown(); 00258 this->callback_queue_thread_.join(); 00259 } 00260 00261 00262 // Custom Callback Queue 00264 // custom callback queue thread 00265 void GazeboRosPubWorldState::QueueThread() 00266 { 00267 static const double timeout = 0.01; 00268 00269 while (this->rosnode_->ok()) 00270 { 00271 this->queue_.callAvailable(ros::WallDuration(timeout)); 00272 } 00273 } 00274 00275