$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: Actuator array controller for a Pr2 robot. 00023 * Author: Sachin Chitta and John Hsu 00024 * Date: 1 June 2008 00025 * SVN info: $Id$ 00026 */ 00027 00028 00029 #include <algorithm> 00030 #include <assert.h> 00031 00032 #include <gazebo_plugins/gazebo_ros_time.h> 00033 00034 #include <gazebo/Global.hh> 00035 #include <gazebo/XMLConfig.hh> 00036 #include <gazebo/Simulator.hh> 00037 #include <gazebo/gazebo.h> 00038 #include <gazebo/GazeboError.hh> 00039 #include <gazebo/ControllerFactory.hh> 00040 00041 #include <boost/thread.hpp> 00042 #include <boost/bind.hpp> 00043 00044 using namespace gazebo; 00045 00046 GZ_REGISTER_DYNAMIC_CONTROLLER("gazebo_ros_time", GazeboRosTime); 00047 00049 // Constructor 00050 GazeboRosTime::GazeboRosTime(Entity *parent) 00051 : Controller(parent) 00052 { 00053 Param::Begin(&this->parameters); 00054 this->robotNamespaceP = new ParamT<std::string>("robotNamespace", "/", 0); 00055 Param::End(); 00056 } 00057 00059 // Destructor 00060 GazeboRosTime::~GazeboRosTime() 00061 { 00062 delete this->rosnode_; 00063 delete this->robotNamespaceP; 00064 } 00065 00067 // Load the controller 00068 void GazeboRosTime::LoadChild(XMLConfigNode *node) 00069 { 00070 this->robotNamespaceP->Load(node); 00071 this->robotNamespace = this->robotNamespaceP->GetValue(); 00072 if (!ros::isInitialized()) 00073 { 00074 int argc = 0; 00075 char** argv = NULL; 00076 ros::init(argc,argv,"gazebo",ros::init_options::NoSigintHandler|ros::init_options::AnonymousName); 00077 } 00078 00079 this->rosnode_ = new ros::NodeHandle(this->robotNamespace); 00080 00081 // for rostime 00082 this->pub_ = this->rosnode_->advertise<rosgraph_msgs::Clock>("clock",10); 00083 00084 // broadcasting sim time, so set parameter, this should really be in the launch script param tag, so it's set before nodes start 00085 this->rosnode_->setParam("/use_sim_time", true); 00086 } 00087 00089 // Initialize the controller 00090 void GazeboRosTime::InitChild() 00091 { 00092 } 00093 00095 // Update the controller 00096 void GazeboRosTime::UpdateChild() 00097 { 00098 // pass time to robot 00099 Time currentTime = Simulator::Instance()->GetSimTime(); 00100 //std::cout << "sim time: " << currentTime << std::endl; 00101 00102 /***************************************************************/ 00103 /* */ 00104 /* publish time to ros */ 00105 /* */ 00106 /***************************************************************/ 00107 this->lock.lock(); 00108 timeMsg.clock.fromSec(currentTime.Double()); 00109 this->pub_.publish(timeMsg); 00110 this->lock.unlock(); 00111 } 00112 00114 // Finalize the controller 00115 void GazeboRosTime::FiniChild() 00116 { 00117 } 00118 00119 00120