00001
00002 #ifndef ARTICULATION_MSGS_SERVICE_GETMODELPRIORSRV_H
00003 #define ARTICULATION_MSGS_SERVICE_GETMODELPRIORSRV_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015
00016
00017 #include "articulation_msgs/ModelMsg.h"
00018
00019 namespace articulation_msgs
00020 {
00021 template <class ContainerAllocator>
00022 struct GetModelPriorSrvRequest_ : public ros::Message
00023 {
00024 typedef GetModelPriorSrvRequest_<ContainerAllocator> Type;
00025
00026 GetModelPriorSrvRequest_()
00027 {
00028 }
00029
00030 GetModelPriorSrvRequest_(const ContainerAllocator& _alloc)
00031 {
00032 }
00033
00034
00035 private:
00036 static const char* __s_getDataType_() { return "articulation_msgs/GetModelPriorSrvRequest"; }
00037 public:
00038 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00039
00040 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00041
00042 private:
00043 static const char* __s_getMD5Sum_() { return "d41d8cd98f00b204e9800998ecf8427e"; }
00044 public:
00045 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00046
00047 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00048
00049 private:
00050 static const char* __s_getServerMD5Sum_() { return "056375d531bc6dcbc8a3fedb4b45371f"; }
00051 public:
00052 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00053
00054 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00055
00056 private:
00057 static const char* __s_getMessageDefinition_() { return "\n\
00058 \n\
00059 \n\
00060 \n\
00061 \n\
00062 \n\
00063 \n\
00064 "; }
00065 public:
00066 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00067
00068 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00069
00070 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00071 {
00072 ros::serialization::OStream stream(write_ptr, 1000000000);
00073 return stream.getData();
00074 }
00075
00076 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00077 {
00078 ros::serialization::IStream stream(read_ptr, 1000000000);
00079 return stream.getData();
00080 }
00081
00082 ROS_DEPRECATED virtual uint32_t serializationLength() const
00083 {
00084 uint32_t size = 0;
00085 return size;
00086 }
00087
00088 typedef boost::shared_ptr< ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> > Ptr;
00089 typedef boost::shared_ptr< ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> const> ConstPtr;
00090 };
00091 typedef ::articulation_msgs::GetModelPriorSrvRequest_<std::allocator<void> > GetModelPriorSrvRequest;
00092
00093 typedef boost::shared_ptr< ::articulation_msgs::GetModelPriorSrvRequest> GetModelPriorSrvRequestPtr;
00094 typedef boost::shared_ptr< ::articulation_msgs::GetModelPriorSrvRequest const> GetModelPriorSrvRequestConstPtr;
00095
00096
00097 template <class ContainerAllocator>
00098 struct GetModelPriorSrvResponse_ : public ros::Message
00099 {
00100 typedef GetModelPriorSrvResponse_<ContainerAllocator> Type;
00101
00102 GetModelPriorSrvResponse_()
00103 : model()
00104 {
00105 }
00106
00107 GetModelPriorSrvResponse_(const ContainerAllocator& _alloc)
00108 : model(_alloc)
00109 {
00110 }
00111
00112 typedef std::vector< ::articulation_msgs::ModelMsg_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::articulation_msgs::ModelMsg_<ContainerAllocator> >::other > _model_type;
00113 std::vector< ::articulation_msgs::ModelMsg_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::articulation_msgs::ModelMsg_<ContainerAllocator> >::other > model;
00114
00115
00116 ROS_DEPRECATED uint32_t get_model_size() const { return (uint32_t)model.size(); }
00117 ROS_DEPRECATED void set_model_size(uint32_t size) { model.resize((size_t)size); }
00118 ROS_DEPRECATED void get_model_vec(std::vector< ::articulation_msgs::ModelMsg_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::articulation_msgs::ModelMsg_<ContainerAllocator> >::other > & vec) const { vec = this->model; }
00119 ROS_DEPRECATED void set_model_vec(const std::vector< ::articulation_msgs::ModelMsg_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::articulation_msgs::ModelMsg_<ContainerAllocator> >::other > & vec) { this->model = vec; }
00120 private:
00121 static const char* __s_getDataType_() { return "articulation_msgs/GetModelPriorSrvResponse"; }
00122 public:
00123 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00124
00125 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00126
00127 private:
00128 static const char* __s_getMD5Sum_() { return "056375d531bc6dcbc8a3fedb4b45371f"; }
00129 public:
00130 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00131
00132 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00133
00134 private:
00135 static const char* __s_getServerMD5Sum_() { return "056375d531bc6dcbc8a3fedb4b45371f"; }
00136 public:
00137 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00138
00139 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00140
00141 private:
00142 static const char* __s_getMessageDefinition_() { return "articulation_msgs/ModelMsg[] model\n\
00143 \n\
00144 \n\
00145 ================================================================================\n\
00146 MSG: articulation_msgs/ModelMsg\n\
00147 # Single kinematic model\n\
00148 #\n\
00149 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00150 # The client may additionally specify a model id, that can be used to colorize the\n\
00151 # model when visualized using the RVIZ model display.\n\
00152 # \n\
00153 # For a list of currently implemented models, see the documetation at\n\
00154 # http://www.ros.org/wiki/articulation_models\n\
00155 #\n\
00156 #\n\
00157 \n\
00158 Header header # frame and timestamp\n\
00159 \n\
00160 int32 id # user specified model id\n\
00161 string name # name of the model family (e.g. \"rotational\",\n\
00162 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00163 articulation_msgs/ParamMsg[] params # model parameters\n\
00164 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00165 # that is evaluated using the model\n\
00166 \n\
00167 ================================================================================\n\
00168 MSG: std_msgs/Header\n\
00169 # Standard metadata for higher-level stamped data types.\n\
00170 # This is generally used to communicate timestamped data \n\
00171 # in a particular coordinate frame.\n\
00172 # \n\
00173 # sequence ID: consecutively increasing ID \n\
00174 uint32 seq\n\
00175 #Two-integer timestamp that is expressed as:\n\
00176 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00177 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00178 # time-handling sugar is provided by the client library\n\
00179 time stamp\n\
00180 #Frame this data is associated with\n\
00181 # 0: no frame\n\
00182 # 1: global frame\n\
00183 string frame_id\n\
00184 \n\
00185 ================================================================================\n\
00186 MSG: articulation_msgs/ParamMsg\n\
00187 # Single parameter passed to or from model fitting\n\
00188 #\n\
00189 # This mechanism allows to flexibly pass parameters to \n\
00190 # model fitting (and vice versa). Note that these parameters \n\
00191 # are model-specific: A client may supply additional\n\
00192 # parameters to the model estimator, and, similarly, a estimator\n\
00193 # may add the estimated model parameters to the model message.\n\
00194 # When the model is then evaluated, for example to make predictions\n\
00195 # or to compute the likelihood, the model class can then use\n\
00196 # these parameters.\n\
00197 #\n\
00198 # A parameter has a name, a value, and a type. The type globally\n\
00199 # indicates whether it is a prior parameter (prior to model fitting),\n\
00200 # or a model parameter (found during model fitting, using a maximum-\n\
00201 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00202 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00203 # can therefore already be cached).\n\
00204 #\n\
00205 # For a list of currently used parameters, see the documentation at\n\
00206 # http://www.ros.org/wiki/articulation_models\n\
00207 #\n\
00208 \n\
00209 uint8 PRIOR=0 # indicates a prior model parameter \n\
00210 # (e.g., \"sigma_position\")\n\
00211 uint8 PARAM=1 # indicates a estimated model parameter \n\
00212 # (e.g., \"rot_radius\", the estimated radius)\n\
00213 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00214 # the current trajectory\n\
00215 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00216 # data, given the model and its parameters)\n\
00217 \n\
00218 string name # name of the parameter\n\
00219 float64 value # value of the parameter\n\
00220 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00221 \n\
00222 \n\
00223 ================================================================================\n\
00224 MSG: articulation_msgs/TrackMsg\n\
00225 # Single kinematic trajectory\n\
00226 #\n\
00227 # This message contains a kinematic trajectory. The trajectory is specified\n\
00228 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00229 # the track is valid, and whether it includes orientation. The track id\n\
00230 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00231 # freely chosen by the client. \n\
00232 #\n\
00233 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00234 # Additional information may be associated to each pose using the channels\n\
00235 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00236 #\n\
00237 # After model evaluation,\n\
00238 # also the associated configurations of the object are stored in the channels,\n\
00239 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00240 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00241 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00242 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00243 # range is sampled, and the result is stored in pose_resampled.\n\
00244 # The vector pose_flags contains additional display flags for the poses in the\n\
00245 # pose vector, for example, whether a pose is visible and/or\n\
00246 # the end of a trajectory segment. At the moment, this is only used by the\n\
00247 # prior_model_learner.\n\
00248 #\n\
00249 \n\
00250 Header header # Timestamp and frame\n\
00251 int32 id # used-specified track id\n\
00252 \n\
00253 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00254 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00255 # (after model evaluation)\n\
00256 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00257 # the valid configuration range\n\
00258 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00259 \n\
00260 uint32 POSE_VISIBLE=1\n\
00261 uint32 POSE_END_OF_SEGMENT=2\n\
00262 \n\
00263 # Each channel should have the same number of elements as pose array, \n\
00264 # and the data in each channel should correspond 1:1 with each pose\n\
00265 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00266 sensor_msgs/ChannelFloat32[] channels \n\
00267 \n\
00268 \n\
00269 \n\
00270 ================================================================================\n\
00271 MSG: geometry_msgs/Pose\n\
00272 # A representation of pose in free space, composed of postion and orientation. \n\
00273 Point position\n\
00274 Quaternion orientation\n\
00275 \n\
00276 ================================================================================\n\
00277 MSG: geometry_msgs/Point\n\
00278 # This contains the position of a point in free space\n\
00279 float64 x\n\
00280 float64 y\n\
00281 float64 z\n\
00282 \n\
00283 ================================================================================\n\
00284 MSG: geometry_msgs/Quaternion\n\
00285 # This represents an orientation in free space in quaternion form.\n\
00286 \n\
00287 float64 x\n\
00288 float64 y\n\
00289 float64 z\n\
00290 float64 w\n\
00291 \n\
00292 ================================================================================\n\
00293 MSG: sensor_msgs/ChannelFloat32\n\
00294 # This message is used by the PointCloud message to hold optional data\n\
00295 # associated with each point in the cloud. The length of the values\n\
00296 # array should be the same as the length of the points array in the\n\
00297 # PointCloud, and each value should be associated with the corresponding\n\
00298 # point.\n\
00299 \n\
00300 # Channel names in existing practice include:\n\
00301 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00302 # This is opposite to usual conventions but remains for\n\
00303 # historical reasons. The newer PointCloud2 message has no\n\
00304 # such problem.\n\
00305 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00306 # (R,G,B) values packed into the least significant 24 bits,\n\
00307 # in order.\n\
00308 # \"intensity\" - laser or pixel intensity.\n\
00309 # \"distance\"\n\
00310 \n\
00311 # The channel name should give semantics of the channel (e.g.\n\
00312 # \"intensity\" instead of \"value\").\n\
00313 string name\n\
00314 \n\
00315 # The values array should be 1-1 with the elements of the associated\n\
00316 # PointCloud.\n\
00317 float32[] values\n\
00318 \n\
00319 "; }
00320 public:
00321 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00322
00323 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00324
00325 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00326 {
00327 ros::serialization::OStream stream(write_ptr, 1000000000);
00328 ros::serialization::serialize(stream, model);
00329 return stream.getData();
00330 }
00331
00332 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00333 {
00334 ros::serialization::IStream stream(read_ptr, 1000000000);
00335 ros::serialization::deserialize(stream, model);
00336 return stream.getData();
00337 }
00338
00339 ROS_DEPRECATED virtual uint32_t serializationLength() const
00340 {
00341 uint32_t size = 0;
00342 size += ros::serialization::serializationLength(model);
00343 return size;
00344 }
00345
00346 typedef boost::shared_ptr< ::articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> > Ptr;
00347 typedef boost::shared_ptr< ::articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> const> ConstPtr;
00348 };
00349 typedef ::articulation_msgs::GetModelPriorSrvResponse_<std::allocator<void> > GetModelPriorSrvResponse;
00350
00351 typedef boost::shared_ptr< ::articulation_msgs::GetModelPriorSrvResponse> GetModelPriorSrvResponsePtr;
00352 typedef boost::shared_ptr< ::articulation_msgs::GetModelPriorSrvResponse const> GetModelPriorSrvResponseConstPtr;
00353
00354 struct GetModelPriorSrv
00355 {
00356
00357 typedef GetModelPriorSrvRequest Request;
00358 typedef GetModelPriorSrvResponse Response;
00359 Request request;
00360 Response response;
00361
00362 typedef Request RequestType;
00363 typedef Response ResponseType;
00364 };
00365 }
00366
00367 namespace ros
00368 {
00369 namespace message_traits
00370 {
00371 template<class ContainerAllocator>
00372 struct MD5Sum< ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> > {
00373 static const char* value()
00374 {
00375 return "d41d8cd98f00b204e9800998ecf8427e";
00376 }
00377
00378 static const char* value(const ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00379 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL;
00380 static const uint64_t static_value2 = 0xe9800998ecf8427eULL;
00381 };
00382
00383 template<class ContainerAllocator>
00384 struct DataType< ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> > {
00385 static const char* value()
00386 {
00387 return "articulation_msgs/GetModelPriorSrvRequest";
00388 }
00389
00390 static const char* value(const ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00391 };
00392
00393 template<class ContainerAllocator>
00394 struct Definition< ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> > {
00395 static const char* value()
00396 {
00397 return "\n\
00398 \n\
00399 \n\
00400 \n\
00401 \n\
00402 \n\
00403 \n\
00404 ";
00405 }
00406
00407 static const char* value(const ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00408 };
00409
00410 template<class ContainerAllocator> struct IsFixedSize< ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> > : public TrueType {};
00411 }
00412 }
00413
00414
00415 namespace ros
00416 {
00417 namespace message_traits
00418 {
00419 template<class ContainerAllocator>
00420 struct MD5Sum< ::articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> > {
00421 static const char* value()
00422 {
00423 return "056375d531bc6dcbc8a3fedb4b45371f";
00424 }
00425
00426 static const char* value(const ::articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00427 static const uint64_t static_value1 = 0x056375d531bc6dcbULL;
00428 static const uint64_t static_value2 = 0xc8a3fedb4b45371fULL;
00429 };
00430
00431 template<class ContainerAllocator>
00432 struct DataType< ::articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> > {
00433 static const char* value()
00434 {
00435 return "articulation_msgs/GetModelPriorSrvResponse";
00436 }
00437
00438 static const char* value(const ::articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00439 };
00440
00441 template<class ContainerAllocator>
00442 struct Definition< ::articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> > {
00443 static const char* value()
00444 {
00445 return "articulation_msgs/ModelMsg[] model\n\
00446 \n\
00447 \n\
00448 ================================================================================\n\
00449 MSG: articulation_msgs/ModelMsg\n\
00450 # Single kinematic model\n\
00451 #\n\
00452 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00453 # The client may additionally specify a model id, that can be used to colorize the\n\
00454 # model when visualized using the RVIZ model display.\n\
00455 # \n\
00456 # For a list of currently implemented models, see the documetation at\n\
00457 # http://www.ros.org/wiki/articulation_models\n\
00458 #\n\
00459 #\n\
00460 \n\
00461 Header header # frame and timestamp\n\
00462 \n\
00463 int32 id # user specified model id\n\
00464 string name # name of the model family (e.g. \"rotational\",\n\
00465 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00466 articulation_msgs/ParamMsg[] params # model parameters\n\
00467 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00468 # that is evaluated using the model\n\
00469 \n\
00470 ================================================================================\n\
00471 MSG: std_msgs/Header\n\
00472 # Standard metadata for higher-level stamped data types.\n\
00473 # This is generally used to communicate timestamped data \n\
00474 # in a particular coordinate frame.\n\
00475 # \n\
00476 # sequence ID: consecutively increasing ID \n\
00477 uint32 seq\n\
00478 #Two-integer timestamp that is expressed as:\n\
00479 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00480 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00481 # time-handling sugar is provided by the client library\n\
00482 time stamp\n\
00483 #Frame this data is associated with\n\
00484 # 0: no frame\n\
00485 # 1: global frame\n\
00486 string frame_id\n\
00487 \n\
00488 ================================================================================\n\
00489 MSG: articulation_msgs/ParamMsg\n\
00490 # Single parameter passed to or from model fitting\n\
00491 #\n\
00492 # This mechanism allows to flexibly pass parameters to \n\
00493 # model fitting (and vice versa). Note that these parameters \n\
00494 # are model-specific: A client may supply additional\n\
00495 # parameters to the model estimator, and, similarly, a estimator\n\
00496 # may add the estimated model parameters to the model message.\n\
00497 # When the model is then evaluated, for example to make predictions\n\
00498 # or to compute the likelihood, the model class can then use\n\
00499 # these parameters.\n\
00500 #\n\
00501 # A parameter has a name, a value, and a type. The type globally\n\
00502 # indicates whether it is a prior parameter (prior to model fitting),\n\
00503 # or a model parameter (found during model fitting, using a maximum-\n\
00504 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00505 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00506 # can therefore already be cached).\n\
00507 #\n\
00508 # For a list of currently used parameters, see the documentation at\n\
00509 # http://www.ros.org/wiki/articulation_models\n\
00510 #\n\
00511 \n\
00512 uint8 PRIOR=0 # indicates a prior model parameter \n\
00513 # (e.g., \"sigma_position\")\n\
00514 uint8 PARAM=1 # indicates a estimated model parameter \n\
00515 # (e.g., \"rot_radius\", the estimated radius)\n\
00516 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00517 # the current trajectory\n\
00518 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00519 # data, given the model and its parameters)\n\
00520 \n\
00521 string name # name of the parameter\n\
00522 float64 value # value of the parameter\n\
00523 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00524 \n\
00525 \n\
00526 ================================================================================\n\
00527 MSG: articulation_msgs/TrackMsg\n\
00528 # Single kinematic trajectory\n\
00529 #\n\
00530 # This message contains a kinematic trajectory. The trajectory is specified\n\
00531 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00532 # the track is valid, and whether it includes orientation. The track id\n\
00533 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00534 # freely chosen by the client. \n\
00535 #\n\
00536 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00537 # Additional information may be associated to each pose using the channels\n\
00538 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00539 #\n\
00540 # After model evaluation,\n\
00541 # also the associated configurations of the object are stored in the channels,\n\
00542 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00543 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00544 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00545 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00546 # range is sampled, and the result is stored in pose_resampled.\n\
00547 # The vector pose_flags contains additional display flags for the poses in the\n\
00548 # pose vector, for example, whether a pose is visible and/or\n\
00549 # the end of a trajectory segment. At the moment, this is only used by the\n\
00550 # prior_model_learner.\n\
00551 #\n\
00552 \n\
00553 Header header # Timestamp and frame\n\
00554 int32 id # used-specified track id\n\
00555 \n\
00556 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00557 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00558 # (after model evaluation)\n\
00559 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00560 # the valid configuration range\n\
00561 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00562 \n\
00563 uint32 POSE_VISIBLE=1\n\
00564 uint32 POSE_END_OF_SEGMENT=2\n\
00565 \n\
00566 # Each channel should have the same number of elements as pose array, \n\
00567 # and the data in each channel should correspond 1:1 with each pose\n\
00568 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00569 sensor_msgs/ChannelFloat32[] channels \n\
00570 \n\
00571 \n\
00572 \n\
00573 ================================================================================\n\
00574 MSG: geometry_msgs/Pose\n\
00575 # A representation of pose in free space, composed of postion and orientation. \n\
00576 Point position\n\
00577 Quaternion orientation\n\
00578 \n\
00579 ================================================================================\n\
00580 MSG: geometry_msgs/Point\n\
00581 # This contains the position of a point in free space\n\
00582 float64 x\n\
00583 float64 y\n\
00584 float64 z\n\
00585 \n\
00586 ================================================================================\n\
00587 MSG: geometry_msgs/Quaternion\n\
00588 # This represents an orientation in free space in quaternion form.\n\
00589 \n\
00590 float64 x\n\
00591 float64 y\n\
00592 float64 z\n\
00593 float64 w\n\
00594 \n\
00595 ================================================================================\n\
00596 MSG: sensor_msgs/ChannelFloat32\n\
00597 # This message is used by the PointCloud message to hold optional data\n\
00598 # associated with each point in the cloud. The length of the values\n\
00599 # array should be the same as the length of the points array in the\n\
00600 # PointCloud, and each value should be associated with the corresponding\n\
00601 # point.\n\
00602 \n\
00603 # Channel names in existing practice include:\n\
00604 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00605 # This is opposite to usual conventions but remains for\n\
00606 # historical reasons. The newer PointCloud2 message has no\n\
00607 # such problem.\n\
00608 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00609 # (R,G,B) values packed into the least significant 24 bits,\n\
00610 # in order.\n\
00611 # \"intensity\" - laser or pixel intensity.\n\
00612 # \"distance\"\n\
00613 \n\
00614 # The channel name should give semantics of the channel (e.g.\n\
00615 # \"intensity\" instead of \"value\").\n\
00616 string name\n\
00617 \n\
00618 # The values array should be 1-1 with the elements of the associated\n\
00619 # PointCloud.\n\
00620 float32[] values\n\
00621 \n\
00622 ";
00623 }
00624
00625 static const char* value(const ::articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00626 };
00627
00628 }
00629 }
00630
00631 namespace ros
00632 {
00633 namespace serialization
00634 {
00635
00636 template<class ContainerAllocator> struct Serializer< ::articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> >
00637 {
00638 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00639 {
00640 }
00641
00642 ROS_DECLARE_ALLINONE_SERIALIZER;
00643 };
00644 }
00645 }
00646
00647
00648 namespace ros
00649 {
00650 namespace serialization
00651 {
00652
00653 template<class ContainerAllocator> struct Serializer< ::articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> >
00654 {
00655 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00656 {
00657 stream.next(m.model);
00658 }
00659
00660 ROS_DECLARE_ALLINONE_SERIALIZER;
00661 };
00662 }
00663 }
00664
00665 namespace ros
00666 {
00667 namespace service_traits
00668 {
00669 template<>
00670 struct MD5Sum<articulation_msgs::GetModelPriorSrv> {
00671 static const char* value()
00672 {
00673 return "056375d531bc6dcbc8a3fedb4b45371f";
00674 }
00675
00676 static const char* value(const articulation_msgs::GetModelPriorSrv&) { return value(); }
00677 };
00678
00679 template<>
00680 struct DataType<articulation_msgs::GetModelPriorSrv> {
00681 static const char* value()
00682 {
00683 return "articulation_msgs/GetModelPriorSrv";
00684 }
00685
00686 static const char* value(const articulation_msgs::GetModelPriorSrv&) { return value(); }
00687 };
00688
00689 template<class ContainerAllocator>
00690 struct MD5Sum<articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> > {
00691 static const char* value()
00692 {
00693 return "056375d531bc6dcbc8a3fedb4b45371f";
00694 }
00695
00696 static const char* value(const articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00697 };
00698
00699 template<class ContainerAllocator>
00700 struct DataType<articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> > {
00701 static const char* value()
00702 {
00703 return "articulation_msgs/GetModelPriorSrv";
00704 }
00705
00706 static const char* value(const articulation_msgs::GetModelPriorSrvRequest_<ContainerAllocator> &) { return value(); }
00707 };
00708
00709 template<class ContainerAllocator>
00710 struct MD5Sum<articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> > {
00711 static const char* value()
00712 {
00713 return "056375d531bc6dcbc8a3fedb4b45371f";
00714 }
00715
00716 static const char* value(const articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00717 };
00718
00719 template<class ContainerAllocator>
00720 struct DataType<articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> > {
00721 static const char* value()
00722 {
00723 return "articulation_msgs/GetModelPriorSrv";
00724 }
00725
00726 static const char* value(const articulation_msgs::GetModelPriorSrvResponse_<ContainerAllocator> &) { return value(); }
00727 };
00728
00729 }
00730 }
00731
00732 #endif // ARTICULATION_MSGS_SERVICE_GETMODELPRIORSRV_H
00733