gazebo_ros_api_plugin.h
Go to the documentation of this file.
00001 #ifndef __GAZEBO_ROS_API_PLUGIN_HH__
00002 #define __GAZEBO_ROS_API_PLUGIN_HH__
00003 
00004 /*
00005  *  Gazebo - Outdoor Multi-Robot Simulator
00006  *  Copyright (C) 2003
00007  *     Nate Koenig & Andrew Howard
00008  *
00009  *  This program is free software; you can redistribute it and/or modify
00010  *  it under the terms of the GNU General Public License as published by
00011  *  the Free Software Foundation; either version 2 of the License, or
00012  *  (at your option) any later version.
00013  *
00014  *  This program is distributed in the hope that it will be useful,
00015  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00016  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00017  *  GNU General Public License for more details.
00018  *
00019  *  You should have received a copy of the GNU General Public License
00020  *  along with this program; if not, write to the Free Software
00021  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00022  *
00023  */
00024 
00025 /* Desc: External interfaces for Gazebo
00026  * Author: John Hsu adapted original gazebo main.cc by Nate Koenig
00027  * Date: 25 Apr 2010
00028  * SVN: $Id: main.cc 8598 2010-03-22 21:59:24Z hsujohnhsu $
00029  */
00030 
00031 #include <stdio.h>
00032 #include <stdlib.h>
00033 #include <signal.h>
00034 #include <errno.h>
00035 #include <iostream>
00036 
00037 // urdf utilities
00038 #include <tinyxml.h>
00039 
00040 #include "Server.hh"
00041 #include "physics/Physics.hh"
00042 #include "physics/PhysicsEngine.hh"
00043 #include "physics/PhysicsTypes.hh"
00044 #include "physics/Entity.hh"
00045 #include "physics/Collision.hh"
00046 #include "physics/Inertial.hh"
00047 #include "physics/Base.hh"
00048 #include "physics/Link.hh"
00049 #include "physics/Model.hh"
00050 #include "physics/Joint.hh"
00051 #include "common/CommonTypes.hh"
00052 #include "common/Exception.hh"
00053 #include "common/SystemPaths.hh"
00054 #include "common/Plugin.hh"
00055 #include "transport/Node.hh"
00056 //#include "msgs/MessageTypes.hh" // implicitly included from CommonTypes.hh
00057 
00058 // ros
00059 #include <ros/ros.h>
00060 #include <ros/callback_queue.h>
00061 #include <ros/subscribe_options.h>
00062 #include <ros/package.h>
00063 #include <rosgraph_msgs/Clock.h>
00064 
00065 // Services
00066 #include "std_srvs/Empty.h"
00067 
00068 #include "gazebo_msgs/JointRequest.h"
00069 #include "gazebo_msgs/BodyRequest.h"
00070 
00071 #include "gazebo_msgs/SpawnModel.h"
00072 #include "gazebo_msgs/DeleteModel.h"
00073 
00074 #include "gazebo_msgs/ApplyBodyWrench.h"
00075 
00076 #include "gazebo_msgs/SetPhysicsProperties.h"
00077 #include "gazebo_msgs/GetPhysicsProperties.h"
00078 
00079 #include "gazebo_msgs/SetJointProperties.h"
00080 
00081 #include "gazebo_msgs/GetWorldProperties.h"
00082 
00083 #include "gazebo_msgs/GetModelProperties.h"
00084 #include "gazebo_msgs/GetModelState.h"
00085 #include "gazebo_msgs/SetModelState.h"
00086 
00087 #include "gazebo_msgs/GetJointProperties.h"
00088 #include "gazebo_msgs/ApplyJointEffort.h"
00089 
00090 #include "gazebo_msgs/GetLinkProperties.h"
00091 #include "gazebo_msgs/SetLinkProperties.h"
00092 #include "gazebo_msgs/SetLinkState.h"
00093 #include "gazebo_msgs/GetLinkState.h"
00094 
00095 // Topics
00096 #include "gazebo_msgs/ModelState.h"
00097 #include "gazebo_msgs/LinkState.h"
00098 #include "gazebo_msgs/ModelStates.h"
00099 #include "gazebo_msgs/LinkStates.h"
00100 
00101 #include "geometry_msgs/Vector3.h"
00102 #include "geometry_msgs/Wrench.h"
00103 #include "geometry_msgs/Pose.h"
00104 #include "geometry_msgs/Twist.h"
00105 
00106 // For model pose transform to set custom joint angles
00107 #include <ros/ros.h>
00108 #include <urdf/model.h>
00109 #include "LinearMath/btTransform.h"
00110 #include "LinearMath/btVector3.h"
00111 #include <gazebo_msgs/SetModelConfiguration.h>
00112 #include <boost/shared_ptr.hpp>
00113 
00114 // For physics dynamics reconfigure
00115 #include <dynamic_reconfigure/server.h>
00116 #include <gazebo/PhysicsConfig.h>
00117 #include "gazebo_msgs/SetPhysicsProperties.h"
00118 #include "gazebo_msgs/GetPhysicsProperties.h"
00119 
00120 #include <boost/algorithm/string.hpp>
00121 
00122 //#include <tf/transform_broadcaster.h>
00123 
00124 namespace gazebo
00125 {
00126 
00127 class GazeboRosApiPlugin : public SystemPlugin
00128 {
00129   public:
00130     GazeboRosApiPlugin();
00131     ~GazeboRosApiPlugin();
00132 
00133     void Load(int argc, char** argv);
00134 
00136     void gazeboQueueThread();
00137 
00139     void AdvertiseServices();
00140 
00141     void onLinkStatesConnect();
00142     void onModelStatesConnect();
00143     void onLinkStatesDisconnect();
00144     void onModelStatesDisconnect();
00145 
00146     bool spawnURDFModel(gazebo_msgs::SpawnModel::Request &req,gazebo_msgs::SpawnModel::Response &res);
00147     bool spawnGazeboModel(gazebo_msgs::SpawnModel::Request &req,gazebo_msgs::SpawnModel::Response &res);
00148 
00151     bool deleteModel(gazebo_msgs::DeleteModel::Request &req,gazebo_msgs::DeleteModel::Response &res);
00152 
00155     bool getModelState(gazebo_msgs::GetModelState::Request &req,gazebo_msgs::GetModelState::Response &res);
00156 
00159     bool getModelProperties(gazebo_msgs::GetModelProperties::Request &req,gazebo_msgs::GetModelProperties::Response &res);
00160 
00163     bool getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req,gazebo_msgs::GetWorldProperties::Response &res);
00164 
00167     bool getJointProperties(gazebo_msgs::GetJointProperties::Request &req,gazebo_msgs::GetJointProperties::Response &res);
00168 
00171     bool getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req,gazebo_msgs::GetLinkProperties::Response &res);
00172 
00175     bool getLinkState(gazebo_msgs::GetLinkState::Request &req,gazebo_msgs::GetLinkState::Response &res);
00176 
00179     bool setLinkProperties(gazebo_msgs::SetLinkProperties::Request &req,gazebo_msgs::SetLinkProperties::Response &res);
00180 
00183     bool setPhysicsProperties(gazebo_msgs::SetPhysicsProperties::Request &req,gazebo_msgs::SetPhysicsProperties::Response &res);
00184 
00187     bool getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req,gazebo_msgs::GetPhysicsProperties::Response &res);
00188 
00191     bool setJointProperties(gazebo_msgs::SetJointProperties::Request &req,gazebo_msgs::SetJointProperties::Response &res);
00192 
00195     bool setModelState(gazebo_msgs::SetModelState::Request &req,gazebo_msgs::SetModelState::Response &res);
00196 
00199     void updateModelState(const gazebo_msgs::ModelState::ConstPtr& model_state);
00200 
00203     bool applyJointEffort(gazebo_msgs::ApplyJointEffort::Request &req,gazebo_msgs::ApplyJointEffort::Response &res);
00204 
00207     bool resetSimulation(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
00208 
00211     bool resetWorld(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
00212 
00215     bool pausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
00216 
00219     bool unpausePhysics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res);
00220 
00223     bool clearJointForces(gazebo_msgs::JointRequest::Request &req,gazebo_msgs::JointRequest::Response &res);
00224     bool clearJointForces(std::string joint_name);
00225 
00228     bool clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req,gazebo_msgs::BodyRequest::Response &res);
00229     bool clearBodyWrenches(std::string body_name);
00230 
00233     bool setModelConfiguration(gazebo_msgs::SetModelConfiguration::Request &req,gazebo_msgs::SetModelConfiguration::Response &res);
00234 
00237     bool setLinkState(gazebo_msgs::SetLinkState::Request &req,gazebo_msgs::SetLinkState::Response &res);
00238 
00241     void updateLinkState(const gazebo_msgs::LinkState::ConstPtr& link_state);
00242 
00245     bool applyBodyWrench(gazebo_msgs::ApplyBodyWrench::Request &req,gazebo_msgs::ApplyBodyWrench::Response &res);
00246 
00247     void spin();
00248 
00249   private:
00250     // helper function for applyBodyWrench
00251     void transformWrench(gazebo::math::Vector3 &target_force, gazebo::math::Vector3 &target_torque,
00252                          gazebo::math::Vector3 reference_force, gazebo::math::Vector3 reference_torque,
00253                          gazebo::math::Pose target_to_reference );
00254     gazebo::transport::NodePtr gazebonode_;
00255     gazebo::transport::SubscriberPtr stat_sub_;
00256     gazebo::transport::PublisherPtr factory_pub_;
00257     gazebo::transport::PublisherPtr request_pub_;
00258     gazebo::transport::SubscriberPtr response_sub_;
00259 
00260     ros::NodeHandle* rosnode_;
00261     ros::CallbackQueue gazebo_queue_;
00262     boost::thread* gazebo_callback_queue_thread_;
00263 
00264     gazebo::physics::WorldPtr world;
00265     gazebo::event::ConnectionPtr wrench_update_event_;
00266     gazebo::event::ConnectionPtr force_update_event_;
00267     gazebo::event::ConnectionPtr time_update_event_;
00268     gazebo::event::ConnectionPtr pub_link_states_event_;
00269     gazebo::event::ConnectionPtr pub_model_states_event_;
00270     gazebo::event::ConnectionPtr load_gazebo_ros_api_plugin_event_;
00271 
00272     ros::ServiceServer spawn_urdf_gazebo_service_;
00273     ros::ServiceServer spawn_urdf_model_service_;
00274     ros::ServiceServer delete_model_service_;
00275     ros::ServiceServer get_model_state_service_;
00276     ros::ServiceServer get_model_properties_service_;
00277     ros::ServiceServer get_world_properties_service_;
00278     ros::ServiceServer get_joint_properties_service_;
00279     ros::ServiceServer get_link_properties_service_;
00280     ros::ServiceServer get_link_state_service_;
00281     ros::ServiceServer set_link_properties_service_;
00282     ros::ServiceServer set_physics_properties_service_;
00283     ros::ServiceServer get_physics_properties_service_;
00284     ros::ServiceServer apply_body_wrench_service_;
00285     ros::ServiceServer set_joint_properties_service_;
00286     ros::ServiceServer set_model_state_service_;
00287     ros::ServiceServer apply_joint_effort_service_;
00288     ros::ServiceServer set_model_configuration_service_;
00289     ros::ServiceServer set_link_state_service_;
00290     ros::ServiceServer reset_simulation_service_;
00291     ros::ServiceServer reset_world_service_;
00292     ros::ServiceServer pause_physics_service_;
00293     ros::ServiceServer unpause_physics_service_;
00294     ros::ServiceServer clear_joint_forces_service_;
00295     ros::ServiceServer clear_body_wrenches_service_;
00296     ros::Subscriber    set_link_state_topic_;
00297     ros::Subscriber    set_model_state_topic_;
00298     ros::Publisher     pub_link_states_;
00299     ros::Publisher     pub_model_states_;
00300     int                pub_link_states_connection_count_;
00301     int                pub_model_states_connection_count_;
00302 
00303     // for internal gazebo xml use
00304     std::string xmlPrefix_;
00305     std::string xmlSuffix_;
00306 
00307     // physics dynamic reconfigure
00308     boost::thread* ros_spin_thread_;
00309     boost::thread* physics_reconfigure_thread_;
00310     bool physics_reconfigure_initialized_;
00311     ros::ServiceClient physics_reconfigure_set_client_;
00312     ros::ServiceClient physics_reconfigure_get_client_;
00313     void PhysicsReconfigureCallback(gazebo::PhysicsConfig &config, uint32_t level);
00314     void PhysicsReconfigureNode();
00315 
00316     void OnResponse(ConstResponsePtr &_response);
00317 
00318     ros::Publisher     pub_clock_;
00319 
00321     private: boost::mutex lock_;
00322 
00324     void SetupTransform(btTransform &transform, urdf::Pose pose);
00325     void SetupTransform(btTransform &transform, geometry_msgs::Pose pose);
00326 
00328     bool IsURDF(std::string model_xml);
00329     bool IsGazeboModelXML(std::string model_xml);
00330     bool IsSDF(std::string model_xml);
00331     void LoadGazeboRosApiPlugin(std::string _worldName);
00332     bool world_created_;
00333 
00334     class WrenchBodyJob
00335     {
00336       public:
00337         gazebo::physics::LinkPtr body;
00338         gazebo::math::Vector3 force;
00339         gazebo::math::Vector3 torque;
00340         ros::Time start_time;
00341         ros::Duration duration;
00342     };
00343 
00344     class ForceJointJob
00345     {
00346       public:
00347         gazebo::physics::JointPtr joint;
00348         double force; // should this be a array?
00349         ros::Time start_time;
00350         ros::Duration duration;
00351     };
00352 
00353     std::vector<GazeboRosApiPlugin::WrenchBodyJob*> wrench_body_jobs;
00354     std::vector<GazeboRosApiPlugin::ForceJointJob*> force_joint_jobs;
00355 
00358     void wrenchBodySchedulerSlot();
00359 
00362     void forceJointSchedulerSlot();
00363 
00366     void publishSimTime(const boost::shared_ptr<gazebo::msgs::WorldStatistics const> &msg);
00367     void publishSimTime();
00368 
00371     void publishLinkStates();
00372 
00375     void publishModelStates();
00376 };
00377 }
00378 #endif


gazebo
Author(s): Nate Koenig, Andrew Howard, with contributions from many others. See web page for a full credits llist.
autogenerated on Sun Jan 5 2014 11:34:52