gazebo_ros_joint_trajectory.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2012 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 // *************************************************************
00019 // DEPRECATED
00020 // This class has been renamed to gazebo_ros_joint_pose_trajectory
00021 // *************************************************************
00022 
00023 #ifndef GAZEBO_ROS_JOINT_TRAJECTORY_PLUGIN_HH
00024 #define GAZEBO_ROS_JOINT_TRAJECTORY_PLUGIN_HH
00025 
00026 #include <string>
00027 #include <vector>
00028 
00029 #include <boost/thread.hpp>
00030 #include <boost/thread/mutex.hpp>
00031 
00032 #include <ros/ros.h>
00033 #include <ros/callback_queue.h>
00034 #include <ros/advertise_options.h>
00035 #include <ros/subscribe_options.h>
00036 
00037 #include <trajectory_msgs/JointTrajectory.h>
00038 #include <geometry_msgs/Pose.h>
00039 
00040 #undef ENABLE_SERVICE
00041 #ifdef ENABLE_SERVICE
00042 #include <gazebo_msgs/SetJointTrajectory.h>
00043 #endif
00044 
00045 #include <gazebo/physics/physics.hh>
00046 #include <gazebo/transport/TransportTypes.hh>
00047 #include <gazebo/common/Time.hh>
00048 #include <gazebo/common/Plugin.hh>
00049 #include <gazebo/common/Events.hh>
00050 
00051 namespace gazebo
00052 {
00053   class GazeboRosJointTrajectory : public ModelPlugin // replaced with GazeboROSJointPoseTrajectory
00054   {
00056     public: GazeboRosJointTrajectory();
00057 
00059     public: virtual ~GazeboRosJointTrajectory();
00060 
00062     public: void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
00063 
00065     private: void SetTrajectory(
00066       const trajectory_msgs::JointTrajectory::ConstPtr& trajectory);
00067 #ifdef ENABLE_SERVICE
00068     private: bool SetTrajectory(
00069       const gazebo_msgs::SetJointTrajectory::Request& req,
00070       const gazebo_msgs::SetJointTrajectory::Response& res);
00071 #endif
00072     private: void UpdateStates();
00073 
00074     private: physics::WorldPtr world_;
00075     private: physics::ModelPtr model_;
00076 
00078     private: physics::LinkPtr reference_link_;
00079     private: std::string reference_link_name_;
00080 
00082     private: ros::NodeHandle* rosnode_;
00083     private: ros::Subscriber sub_;
00084     private: ros::ServiceServer srv_;
00085     private: bool has_trajectory_;
00086 
00088     private: trajectory_msgs::JointTrajectory trajectory_msg_;
00089     private: bool set_model_pose_;
00090     private: geometry_msgs::Pose model_pose_;
00091 
00093     private: std::string topic_name_;
00094     private: std::string service_name_;
00095 
00098     private: boost::mutex update_mutex;
00099 
00101     private: common::Time last_time_;
00102 
00103     // trajectory time control
00104     private: common::Time trajectory_start;
00105     private: unsigned int trajectory_index;
00106 
00107     // rate control
00108     private: double update_rate_;
00109     private: bool disable_physics_updates_;
00110     private: bool physics_engine_enabled_;
00111 
00113     private: std::string robot_namespace_;
00114 
00115     private: ros::CallbackQueue queue_;
00116     private: void QueueThread();
00117     private: boost::thread callback_queue_thread_;
00118 
00119     private: std::vector<gazebo::physics::JointPtr> joints_;
00120     private: std::vector<trajectory_msgs::JointTrajectoryPoint> points_;
00121 
00122     // Pointer to the update event connection
00123     private: event::ConnectionPtr update_connection_;
00124 
00125     private: trajectory_msgs::JointTrajectory joint_trajectory_;
00126 
00127     // deferred load in case ros is blocking
00128     private: sdf::ElementPtr sdf;
00129     private: void LoadThread();
00130     private: boost::thread deferred_load_thread_;
00131   };
00132 }
00133 #endif


gazebo_plugins
Author(s): John Hsu
autogenerated on Fri Aug 28 2015 10:47:25