Go to the documentation of this file.00001
00002 #ifndef HRL_HAPTIC_MANIPULATION_IN_CLUTTER_SRVS_SERVICE_LOGANDMONITORINFO_H
00003 #define HRL_HAPTIC_MANIPULATION_IN_CLUTTER_SRVS_SERVICE_LOGANDMONITORINFO_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 "geometry_msgs/Pose.h"
00020 #include "geometry_msgs/Point.h"
00021
00022
00023
00024 namespace hrl_haptic_manipulation_in_clutter_srvs
00025 {
00026 template <class ContainerAllocator>
00027 struct LogAndMonitorInfoRequest_ {
00028 typedef LogAndMonitorInfoRequest_<ContainerAllocator> Type;
00029
00030 LogAndMonitorInfoRequest_()
00031 : logging_name()
00032 , torso_pose()
00033 , local_goal()
00034 , stopping_force(0.0)
00035 , ee_motion_threshold(0.0)
00036 {
00037 }
00038
00039 LogAndMonitorInfoRequest_(const ContainerAllocator& _alloc)
00040 : logging_name(_alloc)
00041 , torso_pose(_alloc)
00042 , local_goal(_alloc)
00043 , stopping_force(0.0)
00044 , ee_motion_threshold(0.0)
00045 {
00046 }
00047
00048 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _logging_name_type;
00049 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > logging_name;
00050
00051 typedef ::geometry_msgs::Pose_<ContainerAllocator> _torso_pose_type;
00052 ::geometry_msgs::Pose_<ContainerAllocator> torso_pose;
00053
00054 typedef ::geometry_msgs::Point_<ContainerAllocator> _local_goal_type;
00055 ::geometry_msgs::Point_<ContainerAllocator> local_goal;
00056
00057 typedef double _stopping_force_type;
00058 double stopping_force;
00059
00060 typedef double _ee_motion_threshold_type;
00061 double ee_motion_threshold;
00062
00063
00064 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> > Ptr;
00065 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> const> ConstPtr;
00066 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00067 };
00068 typedef ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<std::allocator<void> > LogAndMonitorInfoRequest;
00069
00070 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest> LogAndMonitorInfoRequestPtr;
00071 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest const> LogAndMonitorInfoRequestConstPtr;
00072
00073
00074 template <class ContainerAllocator>
00075 struct LogAndMonitorInfoResponse_ {
00076 typedef LogAndMonitorInfoResponse_<ContainerAllocator> Type;
00077
00078 LogAndMonitorInfoResponse_()
00079 {
00080 }
00081
00082 LogAndMonitorInfoResponse_(const ContainerAllocator& _alloc)
00083 {
00084 }
00085
00086
00087 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> > Ptr;
00088 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> const> ConstPtr;
00089 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00090 };
00091 typedef ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<std::allocator<void> > LogAndMonitorInfoResponse;
00092
00093 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse> LogAndMonitorInfoResponsePtr;
00094 typedef boost::shared_ptr< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse const> LogAndMonitorInfoResponseConstPtr;
00095
00096 struct LogAndMonitorInfo
00097 {
00098
00099 typedef LogAndMonitorInfoRequest Request;
00100 typedef LogAndMonitorInfoResponse Response;
00101 Request request;
00102 Response response;
00103
00104 typedef Request RequestType;
00105 typedef Response ResponseType;
00106 };
00107 }
00108
00109 namespace ros
00110 {
00111 namespace message_traits
00112 {
00113 template<class ContainerAllocator> struct IsMessage< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> > : public TrueType {};
00114 template<class ContainerAllocator> struct IsMessage< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> const> : public TrueType {};
00115 template<class ContainerAllocator>
00116 struct MD5Sum< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> > {
00117 static const char* value()
00118 {
00119 return "e045f94af367795b99be0b4906cfb194";
00120 }
00121
00122 static const char* value(const ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> &) { return value(); }
00123 static const uint64_t static_value1 = 0xe045f94af367795bULL;
00124 static const uint64_t static_value2 = 0x99be0b4906cfb194ULL;
00125 };
00126
00127 template<class ContainerAllocator>
00128 struct DataType< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> > {
00129 static const char* value()
00130 {
00131 return "hrl_haptic_manipulation_in_clutter_srvs/LogAndMonitorInfoRequest";
00132 }
00133
00134 static const char* value(const ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> &) { return value(); }
00135 };
00136
00137 template<class ContainerAllocator>
00138 struct Definition< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> > {
00139 static const char* value()
00140 {
00141 return "\n\
00142 \n\
00143 \n\
00144 \n\
00145 \n\
00146 string logging_name\n\
00147 \n\
00148 \n\
00149 geometry_msgs/Pose torso_pose\n\
00150 \n\
00151 \n\
00152 \n\
00153 geometry_msgs/Point local_goal\n\
00154 \n\
00155 \n\
00156 \n\
00157 \n\
00158 \n\
00159 \n\
00160 \n\
00161 float64 stopping_force\n\
00162 \n\
00163 float64 ee_motion_threshold\n\
00164 \n\
00165 ================================================================================\n\
00166 MSG: geometry_msgs/Pose\n\
00167 # A representation of pose in free space, composed of postion and orientation. \n\
00168 Point position\n\
00169 Quaternion orientation\n\
00170 \n\
00171 ================================================================================\n\
00172 MSG: geometry_msgs/Point\n\
00173 # This contains the position of a point in free space\n\
00174 float64 x\n\
00175 float64 y\n\
00176 float64 z\n\
00177 \n\
00178 ================================================================================\n\
00179 MSG: geometry_msgs/Quaternion\n\
00180 # This represents an orientation in free space in quaternion form.\n\
00181 \n\
00182 float64 x\n\
00183 float64 y\n\
00184 float64 z\n\
00185 float64 w\n\
00186 \n\
00187 ";
00188 }
00189
00190 static const char* value(const ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> &) { return value(); }
00191 };
00192
00193 }
00194 }
00195
00196
00197 namespace ros
00198 {
00199 namespace message_traits
00200 {
00201 template<class ContainerAllocator> struct IsMessage< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> > : public TrueType {};
00202 template<class ContainerAllocator> struct IsMessage< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> const> : public TrueType {};
00203 template<class ContainerAllocator>
00204 struct MD5Sum< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> > {
00205 static const char* value()
00206 {
00207 return "d41d8cd98f00b204e9800998ecf8427e";
00208 }
00209
00210 static const char* value(const ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> &) { return value(); }
00211 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL;
00212 static const uint64_t static_value2 = 0xe9800998ecf8427eULL;
00213 };
00214
00215 template<class ContainerAllocator>
00216 struct DataType< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> > {
00217 static const char* value()
00218 {
00219 return "hrl_haptic_manipulation_in_clutter_srvs/LogAndMonitorInfoResponse";
00220 }
00221
00222 static const char* value(const ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> &) { return value(); }
00223 };
00224
00225 template<class ContainerAllocator>
00226 struct Definition< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> > {
00227 static const char* value()
00228 {
00229 return "\n\
00230 \n\
00231 \n\
00232 ";
00233 }
00234
00235 static const char* value(const ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> &) { return value(); }
00236 };
00237
00238 template<class ContainerAllocator> struct IsFixedSize< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> > : public TrueType {};
00239 }
00240 }
00241
00242 namespace ros
00243 {
00244 namespace serialization
00245 {
00246
00247 template<class ContainerAllocator> struct Serializer< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> >
00248 {
00249 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00250 {
00251 stream.next(m.logging_name);
00252 stream.next(m.torso_pose);
00253 stream.next(m.local_goal);
00254 stream.next(m.stopping_force);
00255 stream.next(m.ee_motion_threshold);
00256 }
00257
00258 ROS_DECLARE_ALLINONE_SERIALIZER;
00259 };
00260 }
00261 }
00262
00263
00264 namespace ros
00265 {
00266 namespace serialization
00267 {
00268
00269 template<class ContainerAllocator> struct Serializer< ::hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> >
00270 {
00271 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00272 {
00273 }
00274
00275 ROS_DECLARE_ALLINONE_SERIALIZER;
00276 };
00277 }
00278 }
00279
00280 namespace ros
00281 {
00282 namespace service_traits
00283 {
00284 template<>
00285 struct MD5Sum<hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfo> {
00286 static const char* value()
00287 {
00288 return "e045f94af367795b99be0b4906cfb194";
00289 }
00290
00291 static const char* value(const hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfo&) { return value(); }
00292 };
00293
00294 template<>
00295 struct DataType<hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfo> {
00296 static const char* value()
00297 {
00298 return "hrl_haptic_manipulation_in_clutter_srvs/LogAndMonitorInfo";
00299 }
00300
00301 static const char* value(const hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfo&) { return value(); }
00302 };
00303
00304 template<class ContainerAllocator>
00305 struct MD5Sum<hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> > {
00306 static const char* value()
00307 {
00308 return "e045f94af367795b99be0b4906cfb194";
00309 }
00310
00311 static const char* value(const hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> &) { return value(); }
00312 };
00313
00314 template<class ContainerAllocator>
00315 struct DataType<hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> > {
00316 static const char* value()
00317 {
00318 return "hrl_haptic_manipulation_in_clutter_srvs/LogAndMonitorInfo";
00319 }
00320
00321 static const char* value(const hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoRequest_<ContainerAllocator> &) { return value(); }
00322 };
00323
00324 template<class ContainerAllocator>
00325 struct MD5Sum<hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> > {
00326 static const char* value()
00327 {
00328 return "e045f94af367795b99be0b4906cfb194";
00329 }
00330
00331 static const char* value(const hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> &) { return value(); }
00332 };
00333
00334 template<class ContainerAllocator>
00335 struct DataType<hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> > {
00336 static const char* value()
00337 {
00338 return "hrl_haptic_manipulation_in_clutter_srvs/LogAndMonitorInfo";
00339 }
00340
00341 static const char* value(const hrl_haptic_manipulation_in_clutter_srvs::LogAndMonitorInfoResponse_<ContainerAllocator> &) { return value(); }
00342 };
00343
00344 }
00345 }
00346
00347 #endif // HRL_HAPTIC_MANIPULATION_IN_CLUTTER_SRVS_SERVICE_LOGANDMONITORINFO_H
00348