00001
00002 #ifndef ARTICULATION_MSGS_SERVICE_SETMODELPRIORSRV_H
00003 #define ARTICULATION_MSGS_SERVICE_SETMODELPRIORSRV_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 "articulation_msgs/ModelMsg.h"
00020
00021
00022
00023 namespace articulation_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct SetModelPriorSrvRequest_ {
00027 typedef SetModelPriorSrvRequest_<ContainerAllocator> Type;
00028
00029 SetModelPriorSrvRequest_()
00030 : model()
00031 {
00032 }
00033
00034 SetModelPriorSrvRequest_(const ContainerAllocator& _alloc)
00035 : model(_alloc)
00036 {
00037 }
00038
00039 typedef std::vector< ::articulation_msgs::ModelMsg_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::articulation_msgs::ModelMsg_<ContainerAllocator> >::other > _model_type;
00040 std::vector< ::articulation_msgs::ModelMsg_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::articulation_msgs::ModelMsg_<ContainerAllocator> >::other > model;
00041
00042
00043 typedef boost::shared_ptr< ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> > Ptr;
00044 typedef boost::shared_ptr< ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> const> ConstPtr;
00045 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00046 };
00047 typedef ::articulation_msgs::SetModelPriorSrvRequest_<std::allocator<void> > SetModelPriorSrvRequest;
00048
00049 typedef boost::shared_ptr< ::articulation_msgs::SetModelPriorSrvRequest> SetModelPriorSrvRequestPtr;
00050 typedef boost::shared_ptr< ::articulation_msgs::SetModelPriorSrvRequest const> SetModelPriorSrvRequestConstPtr;
00051
00052
00053 template <class ContainerAllocator>
00054 struct SetModelPriorSrvResponse_ {
00055 typedef SetModelPriorSrvResponse_<ContainerAllocator> Type;
00056
00057 SetModelPriorSrvResponse_()
00058 {
00059 }
00060
00061 SetModelPriorSrvResponse_(const ContainerAllocator& _alloc)
00062 {
00063 }
00064
00065
00066 typedef boost::shared_ptr< ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> > Ptr;
00067 typedef boost::shared_ptr< ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> const> ConstPtr;
00068 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00069 };
00070 typedef ::articulation_msgs::SetModelPriorSrvResponse_<std::allocator<void> > SetModelPriorSrvResponse;
00071
00072 typedef boost::shared_ptr< ::articulation_msgs::SetModelPriorSrvResponse> SetModelPriorSrvResponsePtr;
00073 typedef boost::shared_ptr< ::articulation_msgs::SetModelPriorSrvResponse const> SetModelPriorSrvResponseConstPtr;
00074
00075 struct SetModelPriorSrv
00076 {
00077
00078 typedef SetModelPriorSrvRequest Request;
00079 typedef SetModelPriorSrvResponse Response;
00080 Request request;
00081 Response response;
00082
00083 typedef Request RequestType;
00084 typedef Response ResponseType;
00085 };
00086 }
00087
00088 namespace ros
00089 {
00090 namespace message_traits
00091 {
00092 template<class ContainerAllocator> struct IsMessage< ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> > : public TrueType {};
00093 template<class ContainerAllocator> struct IsMessage< ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> const> : public TrueType {};
00094 template<class ContainerAllocator>
00095 struct MD5Sum< ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> > {
00096 static const char* value()
00097 {
00098 return "492b025b4d335f83e3fab65eb3211a27";
00099 }
00100
00101 static const char* value(const ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00102 static const uint64_t static_value1 = 0x492b025b4d335f83ULL;
00103 static const uint64_t static_value2 = 0xe3fab65eb3211a27ULL;
00104 };
00105
00106 template<class ContainerAllocator>
00107 struct DataType< ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> > {
00108 static const char* value()
00109 {
00110 return "articulation_msgs/SetModelPriorSrvRequest";
00111 }
00112
00113 static const char* value(const ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00114 };
00115
00116 template<class ContainerAllocator>
00117 struct Definition< ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> > {
00118 static const char* value()
00119 {
00120 return "\n\
00121 \n\
00122 \n\
00123 \n\
00124 \n\
00125 \n\
00126 articulation_msgs/ModelMsg[] model\n\
00127 \n\
00128 ================================================================================\n\
00129 MSG: articulation_msgs/ModelMsg\n\
00130 # Single kinematic model\n\
00131 #\n\
00132 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00133 # The client may additionally specify a model id, that can be used to colorize the\n\
00134 # model when visualized using the RVIZ model display.\n\
00135 # \n\
00136 # For a list of currently implemented models, see the documetation at\n\
00137 # http://www.ros.org/wiki/articulation_models\n\
00138 #\n\
00139 #\n\
00140 \n\
00141 std_msgs/Header header # frame and timestamp\n\
00142 \n\
00143 int32 id # user specified model id\n\
00144 string name # name of the model family (e.g. \"rotational\",\n\
00145 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00146 articulation_msgs/ParamMsg[] params # model parameters\n\
00147 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00148 # that is evaluated using the model\n\
00149 \n\
00150 ================================================================================\n\
00151 MSG: std_msgs/Header\n\
00152 # Standard metadata for higher-level stamped data types.\n\
00153 # This is generally used to communicate timestamped data \n\
00154 # in a particular coordinate frame.\n\
00155 # \n\
00156 # sequence ID: consecutively increasing ID \n\
00157 uint32 seq\n\
00158 #Two-integer timestamp that is expressed as:\n\
00159 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00160 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00161 # time-handling sugar is provided by the client library\n\
00162 time stamp\n\
00163 #Frame this data is associated with\n\
00164 # 0: no frame\n\
00165 # 1: global frame\n\
00166 string frame_id\n\
00167 \n\
00168 ================================================================================\n\
00169 MSG: articulation_msgs/ParamMsg\n\
00170 # Single parameter passed to or from model fitting\n\
00171 #\n\
00172 # This mechanism allows to flexibly pass parameters to \n\
00173 # model fitting (and vice versa). Note that these parameters \n\
00174 # are model-specific: A client may supply additional\n\
00175 # parameters to the model estimator, and, similarly, a estimator\n\
00176 # may add the estimated model parameters to the model message.\n\
00177 # When the model is then evaluated, for example to make predictions\n\
00178 # or to compute the likelihood, the model class can then use\n\
00179 # these parameters.\n\
00180 #\n\
00181 # A parameter has a name, a value, and a type. The type globally\n\
00182 # indicates whether it is a prior parameter (prior to model fitting),\n\
00183 # or a model parameter (found during model fitting, using a maximum-\n\
00184 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00185 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00186 # can therefore already be cached).\n\
00187 #\n\
00188 # For a list of currently used parameters, see the documentation at\n\
00189 # http://www.ros.org/wiki/articulation_models\n\
00190 #\n\
00191 \n\
00192 uint8 PRIOR=0 # indicates a prior model parameter \n\
00193 # (e.g., \"sigma_position\")\n\
00194 uint8 PARAM=1 # indicates a estimated model parameter \n\
00195 # (e.g., \"rot_radius\", the estimated radius)\n\
00196 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00197 # the current trajectory\n\
00198 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00199 # data, given the model and its parameters)\n\
00200 \n\
00201 string name # name of the parameter\n\
00202 float64 value # value of the parameter\n\
00203 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00204 \n\
00205 \n\
00206 ================================================================================\n\
00207 MSG: articulation_msgs/TrackMsg\n\
00208 # Single kinematic trajectory\n\
00209 #\n\
00210 # This message contains a kinematic trajectory. The trajectory is specified\n\
00211 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00212 # the track is valid, and whether it includes orientation. The track id\n\
00213 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00214 # freely chosen by the client. \n\
00215 #\n\
00216 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00217 # Additional information may be associated to each pose using the channels\n\
00218 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00219 #\n\
00220 # After model evaluation,\n\
00221 # also the associated configurations of the object are stored in the channels,\n\
00222 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00223 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00224 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00225 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00226 # range is sampled, and the result is stored in pose_resampled.\n\
00227 # The vector pose_flags contains additional display flags for the poses in the\n\
00228 # pose vector, for example, whether a pose is visible and/or\n\
00229 # the end of a trajectory segment. At the moment, this is only used by the\n\
00230 # prior_model_learner.\n\
00231 #\n\
00232 \n\
00233 std_msgs/Header header # frame and timestamp\n\
00234 int32 id # used-specified track id\n\
00235 \n\
00236 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00237 std_msgs/Header[] pose_headers # Timestamp and frame for each pose (and pose_projected)\n\
00238 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00239 # (after model evaluation)\n\
00240 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00241 # the valid configuration range\n\
00242 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00243 \n\
00244 uint32 POSE_VISIBLE=1\n\
00245 uint32 POSE_END_OF_SEGMENT=2\n\
00246 \n\
00247 # Each channel should have the same number of elements as pose array, \n\
00248 # and the data in each channel should correspond 1:1 with each pose\n\
00249 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00250 sensor_msgs/ChannelFloat32[] channels \n\
00251 \n\
00252 \n\
00253 \n\
00254 ================================================================================\n\
00255 MSG: geometry_msgs/Pose\n\
00256 # A representation of pose in free space, composed of postion and orientation. \n\
00257 Point position\n\
00258 Quaternion orientation\n\
00259 \n\
00260 ================================================================================\n\
00261 MSG: geometry_msgs/Point\n\
00262 # This contains the position of a point in free space\n\
00263 float64 x\n\
00264 float64 y\n\
00265 float64 z\n\
00266 \n\
00267 ================================================================================\n\
00268 MSG: geometry_msgs/Quaternion\n\
00269 # This represents an orientation in free space in quaternion form.\n\
00270 \n\
00271 float64 x\n\
00272 float64 y\n\
00273 float64 z\n\
00274 float64 w\n\
00275 \n\
00276 ================================================================================\n\
00277 MSG: sensor_msgs/ChannelFloat32\n\
00278 # This message is used by the PointCloud message to hold optional data\n\
00279 # associated with each point in the cloud. The length of the values\n\
00280 # array should be the same as the length of the points array in the\n\
00281 # PointCloud, and each value should be associated with the corresponding\n\
00282 # point.\n\
00283 \n\
00284 # Channel names in existing practice include:\n\
00285 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00286 # This is opposite to usual conventions but remains for\n\
00287 # historical reasons. The newer PointCloud2 message has no\n\
00288 # such problem.\n\
00289 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00290 # (R,G,B) values packed into the least significant 24 bits,\n\
00291 # in order.\n\
00292 # \"intensity\" - laser or pixel intensity.\n\
00293 # \"distance\"\n\
00294 \n\
00295 # The channel name should give semantics of the channel (e.g.\n\
00296 # \"intensity\" instead of \"value\").\n\
00297 string name\n\
00298 \n\
00299 # The values array should be 1-1 with the elements of the associated\n\
00300 # PointCloud.\n\
00301 float32[] values\n\
00302 \n\
00303 ";
00304 }
00305
00306 static const char* value(const ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00307 };
00308
00309 }
00310 }
00311
00312
00313 namespace ros
00314 {
00315 namespace message_traits
00316 {
00317 template<class ContainerAllocator> struct IsMessage< ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> > : public TrueType {};
00318 template<class ContainerAllocator> struct IsMessage< ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> const> : public TrueType {};
00319 template<class ContainerAllocator>
00320 struct MD5Sum< ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> > {
00321 static const char* value()
00322 {
00323 return "d41d8cd98f00b204e9800998ecf8427e";
00324 }
00325
00326 static const char* value(const ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00327 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL;
00328 static const uint64_t static_value2 = 0xe9800998ecf8427eULL;
00329 };
00330
00331 template<class ContainerAllocator>
00332 struct DataType< ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> > {
00333 static const char* value()
00334 {
00335 return "articulation_msgs/SetModelPriorSrvResponse";
00336 }
00337
00338 static const char* value(const ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00339 };
00340
00341 template<class ContainerAllocator>
00342 struct Definition< ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> > {
00343 static const char* value()
00344 {
00345 return "\n\
00346 \n\
00347 \n\
00348 ";
00349 }
00350
00351 static const char* value(const ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00352 };
00353
00354 template<class ContainerAllocator> struct IsFixedSize< ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> > : public TrueType {};
00355 }
00356 }
00357
00358 namespace ros
00359 {
00360 namespace serialization
00361 {
00362
00363 template<class ContainerAllocator> struct Serializer< ::articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> >
00364 {
00365 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00366 {
00367 stream.next(m.model);
00368 }
00369
00370 ROS_DECLARE_ALLINONE_SERIALIZER;
00371 };
00372 }
00373 }
00374
00375
00376 namespace ros
00377 {
00378 namespace serialization
00379 {
00380
00381 template<class ContainerAllocator> struct Serializer< ::articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> >
00382 {
00383 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00384 {
00385 }
00386
00387 ROS_DECLARE_ALLINONE_SERIALIZER;
00388 };
00389 }
00390 }
00391
00392 namespace ros
00393 {
00394 namespace service_traits
00395 {
00396 template<>
00397 struct MD5Sum<articulation_msgs::SetModelPriorSrv> {
00398 static const char* value()
00399 {
00400 return "492b025b4d335f83e3fab65eb3211a27";
00401 }
00402
00403 static const char* value(const articulation_msgs::SetModelPriorSrv&) { return value(); }
00404 };
00405
00406 template<>
00407 struct DataType<articulation_msgs::SetModelPriorSrv> {
00408 static const char* value()
00409 {
00410 return "articulation_msgs/SetModelPriorSrv";
00411 }
00412
00413 static const char* value(const articulation_msgs::SetModelPriorSrv&) { return value(); }
00414 };
00415
00416 template<class ContainerAllocator>
00417 struct MD5Sum<articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> > {
00418 static const char* value()
00419 {
00420 return "492b025b4d335f83e3fab65eb3211a27";
00421 }
00422
00423 static const char* value(const articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00424 };
00425
00426 template<class ContainerAllocator>
00427 struct DataType<articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> > {
00428 static const char* value()
00429 {
00430 return "articulation_msgs/SetModelPriorSrv";
00431 }
00432
00433 static const char* value(const articulation_msgs::SetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00434 };
00435
00436 template<class ContainerAllocator>
00437 struct MD5Sum<articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> > {
00438 static const char* value()
00439 {
00440 return "492b025b4d335f83e3fab65eb3211a27";
00441 }
00442
00443 static const char* value(const articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00444 };
00445
00446 template<class ContainerAllocator>
00447 struct DataType<articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> > {
00448 static const char* value()
00449 {
00450 return "articulation_msgs/SetModelPriorSrv";
00451 }
00452
00453 static const char* value(const articulation_msgs::SetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00454 };
00455
00456 }
00457 }
00458
00459 #endif // ARTICULATION_MSGS_SERVICE_SETMODELPRIORSRV_H
00460