gazebo_ros_joint_trajectory.h
Go to the documentation of this file.
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: 3D position interface.
00023  * Author: Sachin Chitta and John Hsu
00024  * Date: 10 June 2008
00025  * SVN: $Id$
00026  */
00027 #ifndef GAZEBO_ROS_JOINT_TRAJECTORY_PLUGIN_HH
00028 #define GAZEBO_ROS_JOINT_TRAJECTORY_PLUGIN_HH
00029 
00030 #include <ros/ros.h>
00031 #include <ros/callback_queue.h>
00032 #include <ros/advertise_options.h>
00033 #include <ros/subscribe_options.h>
00034 #include <trajectory_msgs/JointTrajectory.h>
00035 #include <geometry_msgs/Pose.h>
00036 
00037 #include <gazebo_msgs/SetJointTrajectory.h>
00038 
00039 #include "physics/physics.hh"
00040 #include "transport/TransportTypes.hh"
00041 #include "common/Time.hh"
00042 #include "common/Plugin.hh"
00043 #include "common/Events.hh"
00044 
00045 #include <boost/thread.hpp>
00046 #include "boost/thread/mutex.hpp"
00047 
00048 namespace gazebo
00049 {
00050 
00051    class GazeboRosJointTrajectory : public WorldPlugin
00052    {
00054       public: GazeboRosJointTrajectory();
00055 
00057       public: virtual ~GazeboRosJointTrajectory();
00058 
00060       public: void Load( physics::WorldPtr _world, sdf::ElementPtr _sdf );
00061 
00063       private: void SetTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr& trajectory);
00064       private: bool SetTrajectory(const gazebo_msgs::SetJointTrajectory::Request& req,
00065                                   const gazebo_msgs::SetJointTrajectory::Response& res);
00066       private: void UpdateStates();
00067 
00068       private: physics::WorldPtr world_;
00069       private: physics::ModelPtr model_;
00070 
00072       private: physics::LinkPtr reference_link_;
00073       private: std::string reference_link_name_;
00075       //private: std::string tf_frame_name_;
00076 
00078       private: ros::NodeHandle* rosnode_;
00079       private: ros::Subscriber sub_;
00080       private: ros::ServiceServer srv_;
00081       private: bool has_trajectory_;
00082 
00084       private: trajectory_msgs::JointTrajectory trajectory_msg_;
00085       private: bool set_model_pose_;
00086       private: geometry_msgs::Pose model_pose_;
00087 
00089       private: std::string topic_name_;
00090       private: std::string service_name_;
00091 
00093       private: boost::mutex update_mutex;
00094 
00096       private: common::Time last_time_;
00097 
00098       // trajectory time control
00099       private: common::Time trajectory_start;
00100       private: unsigned int trajectory_index;
00101 
00102       // rate control
00103       private: double update_rate_;
00104       private: bool disable_physics_updates_;
00105       private: bool physics_engine_enabled_;
00106 
00108       private: std::string robot_namespace_;
00109 
00110       private: ros::CallbackQueue queue_;
00111       private: void QueueThread();
00112       private: boost::thread callback_queue_thread_;
00113       
00114       // Pointer to the update event connection
00115       private: event::ConnectionPtr update_connection_;
00116 
00117       private: trajectory_msgs::JointTrajectory joint_trajectory_;
00118 
00119       void FixLink(physics::LinkPtr link);
00120       void UnfixLink();
00121       private: physics::JointPtr joint_;
00122    };
00123 
00125 
00126 
00127 
00128 }
00129 
00130 #endif


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Mon Oct 6 2014 12:15:44