SetJointTrajectory.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-simulator_gazebo/doc_stacks/2014-01-05_11-32-34.493080/simulator_gazebo/gazebo_msgs/srv/SetJointTrajectory.srv */
00002 #ifndef GAZEBO_MSGS_SERVICE_SETJOINTTRAJECTORY_H
00003 #define GAZEBO_MSGS_SERVICE_SETJOINTTRAJECTORY_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012 
00013 #include "ros/macros.h"
00014 
00015 #include "ros/assert.h"
00016 
00017 #include "ros/service_traits.h"
00018 
00019 #include "trajectory_msgs/JointTrajectory.h"
00020 #include "geometry_msgs/Pose.h"
00021 
00022 
00023 
00024 namespace gazebo_msgs
00025 {
00026 template <class ContainerAllocator>
00027 struct SetJointTrajectoryRequest_ {
00028   typedef SetJointTrajectoryRequest_<ContainerAllocator> Type;
00029 
00030   SetJointTrajectoryRequest_()
00031   : model_name()
00032   , joint_trajectory()
00033   , model_pose()
00034   , set_model_pose(false)
00035   , disable_physics_updates(false)
00036   {
00037   }
00038 
00039   SetJointTrajectoryRequest_(const ContainerAllocator& _alloc)
00040   : model_name(_alloc)
00041   , joint_trajectory(_alloc)
00042   , model_pose(_alloc)
00043   , set_model_pose(false)
00044   , disable_physics_updates(false)
00045   {
00046   }
00047 
00048   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _model_name_type;
00049   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  model_name;
00050 
00051   typedef  ::trajectory_msgs::JointTrajectory_<ContainerAllocator>  _joint_trajectory_type;
00052    ::trajectory_msgs::JointTrajectory_<ContainerAllocator>  joint_trajectory;
00053 
00054   typedef  ::geometry_msgs::Pose_<ContainerAllocator>  _model_pose_type;
00055    ::geometry_msgs::Pose_<ContainerAllocator>  model_pose;
00056 
00057   typedef uint8_t _set_model_pose_type;
00058   uint8_t set_model_pose;
00059 
00060   typedef uint8_t _disable_physics_updates_type;
00061   uint8_t disable_physics_updates;
00062 
00063 
00064   typedef boost::shared_ptr< ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> > Ptr;
00065   typedef boost::shared_ptr< ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator>  const> ConstPtr;
00066   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00067 }; // struct SetJointTrajectoryRequest
00068 typedef  ::gazebo_msgs::SetJointTrajectoryRequest_<std::allocator<void> > SetJointTrajectoryRequest;
00069 
00070 typedef boost::shared_ptr< ::gazebo_msgs::SetJointTrajectoryRequest> SetJointTrajectoryRequestPtr;
00071 typedef boost::shared_ptr< ::gazebo_msgs::SetJointTrajectoryRequest const> SetJointTrajectoryRequestConstPtr;
00072 
00073 
00074 template <class ContainerAllocator>
00075 struct SetJointTrajectoryResponse_ {
00076   typedef SetJointTrajectoryResponse_<ContainerAllocator> Type;
00077 
00078   SetJointTrajectoryResponse_()
00079   : success(false)
00080   , status_message()
00081   {
00082   }
00083 
00084   SetJointTrajectoryResponse_(const ContainerAllocator& _alloc)
00085   : success(false)
00086   , status_message(_alloc)
00087   {
00088   }
00089 
00090   typedef uint8_t _success_type;
00091   uint8_t success;
00092 
00093   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _status_message_type;
00094   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  status_message;
00095 
00096 
00097   typedef boost::shared_ptr< ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> > Ptr;
00098   typedef boost::shared_ptr< ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator>  const> ConstPtr;
00099   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00100 }; // struct SetJointTrajectoryResponse
00101 typedef  ::gazebo_msgs::SetJointTrajectoryResponse_<std::allocator<void> > SetJointTrajectoryResponse;
00102 
00103 typedef boost::shared_ptr< ::gazebo_msgs::SetJointTrajectoryResponse> SetJointTrajectoryResponsePtr;
00104 typedef boost::shared_ptr< ::gazebo_msgs::SetJointTrajectoryResponse const> SetJointTrajectoryResponseConstPtr;
00105 
00106 struct SetJointTrajectory
00107 {
00108 
00109 typedef SetJointTrajectoryRequest Request;
00110 typedef SetJointTrajectoryResponse Response;
00111 Request request;
00112 Response response;
00113 
00114 typedef Request RequestType;
00115 typedef Response ResponseType;
00116 }; // struct SetJointTrajectory
00117 } // namespace gazebo_msgs
00118 
00119 namespace ros
00120 {
00121 namespace message_traits
00122 {
00123 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> > : public TrueType {};
00124 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator>  const> : public TrueType {};
00125 template<class ContainerAllocator>
00126 struct MD5Sum< ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> > {
00127   static const char* value() 
00128   {
00129     return "ee62e7b21a06be8681d3e4442a6c9b3d";
00130   }
00131 
00132   static const char* value(const  ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 
00133   static const uint64_t static_value1 = 0xee62e7b21a06be86ULL;
00134   static const uint64_t static_value2 = 0x81d3e4442a6c9b3dULL;
00135 };
00136 
00137 template<class ContainerAllocator>
00138 struct DataType< ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> > {
00139   static const char* value() 
00140   {
00141     return "gazebo_msgs/SetJointTrajectoryRequest";
00142   }
00143 
00144   static const char* value(const  ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 
00145 };
00146 
00147 template<class ContainerAllocator>
00148 struct Definition< ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> > {
00149   static const char* value() 
00150   {
00151     return "string model_name\n\
00152 trajectory_msgs/JointTrajectory joint_trajectory\n\
00153 geometry_msgs/Pose model_pose\n\
00154 bool set_model_pose\n\
00155 bool disable_physics_updates\n\
00156 \n\
00157 ================================================================================\n\
00158 MSG: trajectory_msgs/JointTrajectory\n\
00159 Header header\n\
00160 string[] joint_names\n\
00161 JointTrajectoryPoint[] points\n\
00162 ================================================================================\n\
00163 MSG: std_msgs/Header\n\
00164 # Standard metadata for higher-level stamped data types.\n\
00165 # This is generally used to communicate timestamped data \n\
00166 # in a particular coordinate frame.\n\
00167 # \n\
00168 # sequence ID: consecutively increasing ID \n\
00169 uint32 seq\n\
00170 #Two-integer timestamp that is expressed as:\n\
00171 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00172 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00173 # time-handling sugar is provided by the client library\n\
00174 time stamp\n\
00175 #Frame this data is associated with\n\
00176 # 0: no frame\n\
00177 # 1: global frame\n\
00178 string frame_id\n\
00179 \n\
00180 ================================================================================\n\
00181 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00182 float64[] positions\n\
00183 float64[] velocities\n\
00184 float64[] accelerations\n\
00185 duration time_from_start\n\
00186 ================================================================================\n\
00187 MSG: geometry_msgs/Pose\n\
00188 # A representation of pose in free space, composed of postion and orientation. \n\
00189 Point position\n\
00190 Quaternion orientation\n\
00191 \n\
00192 ================================================================================\n\
00193 MSG: geometry_msgs/Point\n\
00194 # This contains the position of a point in free space\n\
00195 float64 x\n\
00196 float64 y\n\
00197 float64 z\n\
00198 \n\
00199 ================================================================================\n\
00200 MSG: geometry_msgs/Quaternion\n\
00201 # This represents an orientation in free space in quaternion form.\n\
00202 \n\
00203 float64 x\n\
00204 float64 y\n\
00205 float64 z\n\
00206 float64 w\n\
00207 \n\
00208 ";
00209   }
00210 
00211   static const char* value(const  ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 
00212 };
00213 
00214 } // namespace message_traits
00215 } // namespace ros
00216 
00217 
00218 namespace ros
00219 {
00220 namespace message_traits
00221 {
00222 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> > : public TrueType {};
00223 template<class ContainerAllocator> struct IsMessage< ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator>  const> : public TrueType {};
00224 template<class ContainerAllocator>
00225 struct MD5Sum< ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> > {
00226   static const char* value() 
00227   {
00228     return "2ec6f3eff0161f4257b808b12bc830c2";
00229   }
00230 
00231   static const char* value(const  ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 
00232   static const uint64_t static_value1 = 0x2ec6f3eff0161f42ULL;
00233   static const uint64_t static_value2 = 0x57b808b12bc830c2ULL;
00234 };
00235 
00236 template<class ContainerAllocator>
00237 struct DataType< ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> > {
00238   static const char* value() 
00239   {
00240     return "gazebo_msgs/SetJointTrajectoryResponse";
00241   }
00242 
00243   static const char* value(const  ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 
00244 };
00245 
00246 template<class ContainerAllocator>
00247 struct Definition< ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> > {
00248   static const char* value() 
00249   {
00250     return "bool success\n\
00251 string status_message\n\
00252 \n\
00253 \n\
00254 ";
00255   }
00256 
00257   static const char* value(const  ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 
00258 };
00259 
00260 } // namespace message_traits
00261 } // namespace ros
00262 
00263 namespace ros
00264 {
00265 namespace serialization
00266 {
00267 
00268 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> >
00269 {
00270   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00271   {
00272     stream.next(m.model_name);
00273     stream.next(m.joint_trajectory);
00274     stream.next(m.model_pose);
00275     stream.next(m.set_model_pose);
00276     stream.next(m.disable_physics_updates);
00277   }
00278 
00279   ROS_DECLARE_ALLINONE_SERIALIZER;
00280 }; // struct SetJointTrajectoryRequest_
00281 } // namespace serialization
00282 } // namespace ros
00283 
00284 
00285 namespace ros
00286 {
00287 namespace serialization
00288 {
00289 
00290 template<class ContainerAllocator> struct Serializer< ::gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> >
00291 {
00292   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00293   {
00294     stream.next(m.success);
00295     stream.next(m.status_message);
00296   }
00297 
00298   ROS_DECLARE_ALLINONE_SERIALIZER;
00299 }; // struct SetJointTrajectoryResponse_
00300 } // namespace serialization
00301 } // namespace ros
00302 
00303 namespace ros
00304 {
00305 namespace service_traits
00306 {
00307 template<>
00308 struct MD5Sum<gazebo_msgs::SetJointTrajectory> {
00309   static const char* value() 
00310   {
00311     return "d28d88ffcdff46910abd0b17d50e07a9";
00312   }
00313 
00314   static const char* value(const gazebo_msgs::SetJointTrajectory&) { return value(); } 
00315 };
00316 
00317 template<>
00318 struct DataType<gazebo_msgs::SetJointTrajectory> {
00319   static const char* value() 
00320   {
00321     return "gazebo_msgs/SetJointTrajectory";
00322   }
00323 
00324   static const char* value(const gazebo_msgs::SetJointTrajectory&) { return value(); } 
00325 };
00326 
00327 template<class ContainerAllocator>
00328 struct MD5Sum<gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> > {
00329   static const char* value() 
00330   {
00331     return "d28d88ffcdff46910abd0b17d50e07a9";
00332   }
00333 
00334   static const char* value(const gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 
00335 };
00336 
00337 template<class ContainerAllocator>
00338 struct DataType<gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> > {
00339   static const char* value() 
00340   {
00341     return "gazebo_msgs/SetJointTrajectory";
00342   }
00343 
00344   static const char* value(const gazebo_msgs::SetJointTrajectoryRequest_<ContainerAllocator> &) { return value(); } 
00345 };
00346 
00347 template<class ContainerAllocator>
00348 struct MD5Sum<gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> > {
00349   static const char* value() 
00350   {
00351     return "d28d88ffcdff46910abd0b17d50e07a9";
00352   }
00353 
00354   static const char* value(const gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 
00355 };
00356 
00357 template<class ContainerAllocator>
00358 struct DataType<gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> > {
00359   static const char* value() 
00360   {
00361     return "gazebo_msgs/SetJointTrajectory";
00362   }
00363 
00364   static const char* value(const gazebo_msgs::SetJointTrajectoryResponse_<ContainerAllocator> &) { return value(); } 
00365 };
00366 
00367 } // namespace service_traits
00368 } // namespace ros
00369 
00370 #endif // GAZEBO_MSGS_SERVICE_SETJOINTTRAJECTORY_H
00371 


gazebo_msgs
Author(s): John Hsu
autogenerated on Sun Jan 5 2014 11:34:32