00001
00002 #ifndef ARTICULATION_MSGS_SERVICE_TRACKMODELSRV_H
00003 #define ARTICULATION_MSGS_SERVICE_TRACKMODELSRV_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 #include "articulation_msgs/ModelMsg.h"
00016
00017
00018 #include "articulation_msgs/ModelMsg.h"
00019
00020 namespace articulation_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct TrackModelSrvRequest_ : public ros::Message
00024 {
00025 typedef TrackModelSrvRequest_<ContainerAllocator> Type;
00026
00027 TrackModelSrvRequest_()
00028 : model()
00029 {
00030 }
00031
00032 TrackModelSrvRequest_(const ContainerAllocator& _alloc)
00033 : model(_alloc)
00034 {
00035 }
00036
00037 typedef ::articulation_msgs::ModelMsg_<ContainerAllocator> _model_type;
00038 ::articulation_msgs::ModelMsg_<ContainerAllocator> model;
00039
00040
00041 private:
00042 static const char* __s_getDataType_() { return "articulation_msgs/TrackModelSrvRequest"; }
00043 public:
00044 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00045
00046 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00047
00048 private:
00049 static const char* __s_getMD5Sum_() { return "056375d531bc6dcbc8a3fedb4b45371f"; }
00050 public:
00051 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00052
00053 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00054
00055 private:
00056 static const char* __s_getServerMD5Sum_() { return "eba693fb01232c71f70038728ca60d66"; }
00057 public:
00058 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00059
00060 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00061
00062 private:
00063 static const char* __s_getMessageDefinition_() { return "\n\
00064 \n\
00065 \n\
00066 \n\
00067 \n\
00068 \n\
00069 \n\
00070 \n\
00071 \n\
00072 \n\
00073 \n\
00074 articulation_msgs/ModelMsg model\n\
00075 \n\
00076 \n\
00077 ================================================================================\n\
00078 MSG: articulation_msgs/ModelMsg\n\
00079 # Single kinematic model\n\
00080 #\n\
00081 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00082 # The client may additionally specify a model id, that can be used to colorize the\n\
00083 # model when visualized using the RVIZ model display.\n\
00084 # \n\
00085 # For a list of currently implemented models, see the documetation at\n\
00086 # http://www.ros.org/wiki/articulation_models\n\
00087 #\n\
00088 #\n\
00089 \n\
00090 Header header # frame and timestamp\n\
00091 \n\
00092 int32 id # user specified model id\n\
00093 string name # name of the model family (e.g. \"rotational\",\n\
00094 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00095 articulation_msgs/ParamMsg[] params # model parameters\n\
00096 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00097 # that is evaluated using the model\n\
00098 \n\
00099 ================================================================================\n\
00100 MSG: std_msgs/Header\n\
00101 # Standard metadata for higher-level stamped data types.\n\
00102 # This is generally used to communicate timestamped data \n\
00103 # in a particular coordinate frame.\n\
00104 # \n\
00105 # sequence ID: consecutively increasing ID \n\
00106 uint32 seq\n\
00107 #Two-integer timestamp that is expressed as:\n\
00108 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00109 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00110 # time-handling sugar is provided by the client library\n\
00111 time stamp\n\
00112 #Frame this data is associated with\n\
00113 # 0: no frame\n\
00114 # 1: global frame\n\
00115 string frame_id\n\
00116 \n\
00117 ================================================================================\n\
00118 MSG: articulation_msgs/ParamMsg\n\
00119 # Single parameter passed to or from model fitting\n\
00120 #\n\
00121 # This mechanism allows to flexibly pass parameters to \n\
00122 # model fitting (and vice versa). Note that these parameters \n\
00123 # are model-specific: A client may supply additional\n\
00124 # parameters to the model estimator, and, similarly, a estimator\n\
00125 # may add the estimated model parameters to the model message.\n\
00126 # When the model is then evaluated, for example to make predictions\n\
00127 # or to compute the likelihood, the model class can then use\n\
00128 # these parameters.\n\
00129 #\n\
00130 # A parameter has a name, a value, and a type. The type globally\n\
00131 # indicates whether it is a prior parameter (prior to model fitting),\n\
00132 # or a model parameter (found during model fitting, using a maximum-\n\
00133 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00134 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00135 # can therefore already be cached).\n\
00136 #\n\
00137 # For a list of currently used parameters, see the documentation at\n\
00138 # http://www.ros.org/wiki/articulation_models\n\
00139 #\n\
00140 \n\
00141 uint8 PRIOR=0 # indicates a prior model parameter \n\
00142 # (e.g., \"sigma_position\")\n\
00143 uint8 PARAM=1 # indicates a estimated model parameter \n\
00144 # (e.g., \"rot_radius\", the estimated radius)\n\
00145 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00146 # the current trajectory\n\
00147 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00148 # data, given the model and its parameters)\n\
00149 \n\
00150 string name # name of the parameter\n\
00151 float64 value # value of the parameter\n\
00152 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00153 \n\
00154 \n\
00155 ================================================================================\n\
00156 MSG: articulation_msgs/TrackMsg\n\
00157 # Single kinematic trajectory\n\
00158 #\n\
00159 # This message contains a kinematic trajectory. The trajectory is specified\n\
00160 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00161 # the track is valid, and whether it includes orientation. The track id\n\
00162 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00163 # freely chosen by the client. \n\
00164 #\n\
00165 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00166 # Additional information may be associated to each pose using the channels\n\
00167 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00168 #\n\
00169 # After model evaluation,\n\
00170 # also the associated configurations of the object are stored in the channels,\n\
00171 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00172 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00173 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00174 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00175 # range is sampled, and the result is stored in pose_resampled.\n\
00176 # The vector pose_flags contains additional display flags for the poses in the\n\
00177 # pose vector, for example, whether a pose is visible and/or\n\
00178 # the end of a trajectory segment. At the moment, this is only used by the\n\
00179 # prior_model_learner.\n\
00180 #\n\
00181 \n\
00182 Header header # Timestamp and frame\n\
00183 int32 id # used-specified track id\n\
00184 \n\
00185 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00186 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00187 # (after model evaluation)\n\
00188 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00189 # the valid configuration range\n\
00190 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00191 \n\
00192 uint32 POSE_VISIBLE=1\n\
00193 uint32 POSE_END_OF_SEGMENT=2\n\
00194 \n\
00195 # Each channel should have the same number of elements as pose array, \n\
00196 # and the data in each channel should correspond 1:1 with each pose\n\
00197 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00198 sensor_msgs/ChannelFloat32[] channels \n\
00199 \n\
00200 \n\
00201 \n\
00202 ================================================================================\n\
00203 MSG: geometry_msgs/Pose\n\
00204 # A representation of pose in free space, composed of postion and orientation. \n\
00205 Point position\n\
00206 Quaternion orientation\n\
00207 \n\
00208 ================================================================================\n\
00209 MSG: geometry_msgs/Point\n\
00210 # This contains the position of a point in free space\n\
00211 float64 x\n\
00212 float64 y\n\
00213 float64 z\n\
00214 \n\
00215 ================================================================================\n\
00216 MSG: geometry_msgs/Quaternion\n\
00217 # This represents an orientation in free space in quaternion form.\n\
00218 \n\
00219 float64 x\n\
00220 float64 y\n\
00221 float64 z\n\
00222 float64 w\n\
00223 \n\
00224 ================================================================================\n\
00225 MSG: sensor_msgs/ChannelFloat32\n\
00226 # This message is used by the PointCloud message to hold optional data\n\
00227 # associated with each point in the cloud. The length of the values\n\
00228 # array should be the same as the length of the points array in the\n\
00229 # PointCloud, and each value should be associated with the corresponding\n\
00230 # point.\n\
00231 \n\
00232 # Channel names in existing practice include:\n\
00233 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00234 # This is opposite to usual conventions but remains for\n\
00235 # historical reasons. The newer PointCloud2 message has no\n\
00236 # such problem.\n\
00237 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00238 # (R,G,B) values packed into the least significant 24 bits,\n\
00239 # in order.\n\
00240 # \"intensity\" - laser or pixel intensity.\n\
00241 # \"distance\"\n\
00242 \n\
00243 # The channel name should give semantics of the channel (e.g.\n\
00244 # \"intensity\" instead of \"value\").\n\
00245 string name\n\
00246 \n\
00247 # The values array should be 1-1 with the elements of the associated\n\
00248 # PointCloud.\n\
00249 float32[] values\n\
00250 \n\
00251 "; }
00252 public:
00253 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00254
00255 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00256
00257 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00258 {
00259 ros::serialization::OStream stream(write_ptr, 1000000000);
00260 ros::serialization::serialize(stream, model);
00261 return stream.getData();
00262 }
00263
00264 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00265 {
00266 ros::serialization::IStream stream(read_ptr, 1000000000);
00267 ros::serialization::deserialize(stream, model);
00268 return stream.getData();
00269 }
00270
00271 ROS_DEPRECATED virtual uint32_t serializationLength() const
00272 {
00273 uint32_t size = 0;
00274 size += ros::serialization::serializationLength(model);
00275 return size;
00276 }
00277
00278 typedef boost::shared_ptr< ::articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> > Ptr;
00279 typedef boost::shared_ptr< ::articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> const> ConstPtr;
00280 };
00281 typedef ::articulation_msgs::TrackModelSrvRequest_<std::allocator<void> > TrackModelSrvRequest;
00282
00283 typedef boost::shared_ptr< ::articulation_msgs::TrackModelSrvRequest> TrackModelSrvRequestPtr;
00284 typedef boost::shared_ptr< ::articulation_msgs::TrackModelSrvRequest const> TrackModelSrvRequestConstPtr;
00285
00286
00287 template <class ContainerAllocator>
00288 struct TrackModelSrvResponse_ : public ros::Message
00289 {
00290 typedef TrackModelSrvResponse_<ContainerAllocator> Type;
00291
00292 TrackModelSrvResponse_()
00293 : model()
00294 {
00295 }
00296
00297 TrackModelSrvResponse_(const ContainerAllocator& _alloc)
00298 : model(_alloc)
00299 {
00300 }
00301
00302 typedef ::articulation_msgs::ModelMsg_<ContainerAllocator> _model_type;
00303 ::articulation_msgs::ModelMsg_<ContainerAllocator> model;
00304
00305
00306 private:
00307 static const char* __s_getDataType_() { return "articulation_msgs/TrackModelSrvResponse"; }
00308 public:
00309 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00310
00311 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00312
00313 private:
00314 static const char* __s_getMD5Sum_() { return "056375d531bc6dcbc8a3fedb4b45371f"; }
00315 public:
00316 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00317
00318 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00319
00320 private:
00321 static const char* __s_getServerMD5Sum_() { return "eba693fb01232c71f70038728ca60d66"; }
00322 public:
00323 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00324
00325 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00326
00327 private:
00328 static const char* __s_getMessageDefinition_() { return "articulation_msgs/ModelMsg model\n\
00329 \n\
00330 \n\
00331 \n\
00332 \n\
00333 \n\
00334 \n\
00335 ================================================================================\n\
00336 MSG: articulation_msgs/ModelMsg\n\
00337 # Single kinematic model\n\
00338 #\n\
00339 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00340 # The client may additionally specify a model id, that can be used to colorize the\n\
00341 # model when visualized using the RVIZ model display.\n\
00342 # \n\
00343 # For a list of currently implemented models, see the documetation at\n\
00344 # http://www.ros.org/wiki/articulation_models\n\
00345 #\n\
00346 #\n\
00347 \n\
00348 Header header # frame and timestamp\n\
00349 \n\
00350 int32 id # user specified model id\n\
00351 string name # name of the model family (e.g. \"rotational\",\n\
00352 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00353 articulation_msgs/ParamMsg[] params # model parameters\n\
00354 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00355 # that is evaluated using the model\n\
00356 \n\
00357 ================================================================================\n\
00358 MSG: std_msgs/Header\n\
00359 # Standard metadata for higher-level stamped data types.\n\
00360 # This is generally used to communicate timestamped data \n\
00361 # in a particular coordinate frame.\n\
00362 # \n\
00363 # sequence ID: consecutively increasing ID \n\
00364 uint32 seq\n\
00365 #Two-integer timestamp that is expressed as:\n\
00366 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00367 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00368 # time-handling sugar is provided by the client library\n\
00369 time stamp\n\
00370 #Frame this data is associated with\n\
00371 # 0: no frame\n\
00372 # 1: global frame\n\
00373 string frame_id\n\
00374 \n\
00375 ================================================================================\n\
00376 MSG: articulation_msgs/ParamMsg\n\
00377 # Single parameter passed to or from model fitting\n\
00378 #\n\
00379 # This mechanism allows to flexibly pass parameters to \n\
00380 # model fitting (and vice versa). Note that these parameters \n\
00381 # are model-specific: A client may supply additional\n\
00382 # parameters to the model estimator, and, similarly, a estimator\n\
00383 # may add the estimated model parameters to the model message.\n\
00384 # When the model is then evaluated, for example to make predictions\n\
00385 # or to compute the likelihood, the model class can then use\n\
00386 # these parameters.\n\
00387 #\n\
00388 # A parameter has a name, a value, and a type. The type globally\n\
00389 # indicates whether it is a prior parameter (prior to model fitting),\n\
00390 # or a model parameter (found during model fitting, using a maximum-\n\
00391 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00392 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00393 # can therefore already be cached).\n\
00394 #\n\
00395 # For a list of currently used parameters, see the documentation at\n\
00396 # http://www.ros.org/wiki/articulation_models\n\
00397 #\n\
00398 \n\
00399 uint8 PRIOR=0 # indicates a prior model parameter \n\
00400 # (e.g., \"sigma_position\")\n\
00401 uint8 PARAM=1 # indicates a estimated model parameter \n\
00402 # (e.g., \"rot_radius\", the estimated radius)\n\
00403 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00404 # the current trajectory\n\
00405 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00406 # data, given the model and its parameters)\n\
00407 \n\
00408 string name # name of the parameter\n\
00409 float64 value # value of the parameter\n\
00410 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00411 \n\
00412 \n\
00413 ================================================================================\n\
00414 MSG: articulation_msgs/TrackMsg\n\
00415 # Single kinematic trajectory\n\
00416 #\n\
00417 # This message contains a kinematic trajectory. The trajectory is specified\n\
00418 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00419 # the track is valid, and whether it includes orientation. The track id\n\
00420 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00421 # freely chosen by the client. \n\
00422 #\n\
00423 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00424 # Additional information may be associated to each pose using the channels\n\
00425 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00426 #\n\
00427 # After model evaluation,\n\
00428 # also the associated configurations of the object are stored in the channels,\n\
00429 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00430 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00431 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00432 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00433 # range is sampled, and the result is stored in pose_resampled.\n\
00434 # The vector pose_flags contains additional display flags for the poses in the\n\
00435 # pose vector, for example, whether a pose is visible and/or\n\
00436 # the end of a trajectory segment. At the moment, this is only used by the\n\
00437 # prior_model_learner.\n\
00438 #\n\
00439 \n\
00440 Header header # Timestamp and frame\n\
00441 int32 id # used-specified track id\n\
00442 \n\
00443 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00444 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00445 # (after model evaluation)\n\
00446 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00447 # the valid configuration range\n\
00448 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00449 \n\
00450 uint32 POSE_VISIBLE=1\n\
00451 uint32 POSE_END_OF_SEGMENT=2\n\
00452 \n\
00453 # Each channel should have the same number of elements as pose array, \n\
00454 # and the data in each channel should correspond 1:1 with each pose\n\
00455 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00456 sensor_msgs/ChannelFloat32[] channels \n\
00457 \n\
00458 \n\
00459 \n\
00460 ================================================================================\n\
00461 MSG: geometry_msgs/Pose\n\
00462 # A representation of pose in free space, composed of postion and orientation. \n\
00463 Point position\n\
00464 Quaternion orientation\n\
00465 \n\
00466 ================================================================================\n\
00467 MSG: geometry_msgs/Point\n\
00468 # This contains the position of a point in free space\n\
00469 float64 x\n\
00470 float64 y\n\
00471 float64 z\n\
00472 \n\
00473 ================================================================================\n\
00474 MSG: geometry_msgs/Quaternion\n\
00475 # This represents an orientation in free space in quaternion form.\n\
00476 \n\
00477 float64 x\n\
00478 float64 y\n\
00479 float64 z\n\
00480 float64 w\n\
00481 \n\
00482 ================================================================================\n\
00483 MSG: sensor_msgs/ChannelFloat32\n\
00484 # This message is used by the PointCloud message to hold optional data\n\
00485 # associated with each point in the cloud. The length of the values\n\
00486 # array should be the same as the length of the points array in the\n\
00487 # PointCloud, and each value should be associated with the corresponding\n\
00488 # point.\n\
00489 \n\
00490 # Channel names in existing practice include:\n\
00491 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00492 # This is opposite to usual conventions but remains for\n\
00493 # historical reasons. The newer PointCloud2 message has no\n\
00494 # such problem.\n\
00495 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00496 # (R,G,B) values packed into the least significant 24 bits,\n\
00497 # in order.\n\
00498 # \"intensity\" - laser or pixel intensity.\n\
00499 # \"distance\"\n\
00500 \n\
00501 # The channel name should give semantics of the channel (e.g.\n\
00502 # \"intensity\" instead of \"value\").\n\
00503 string name\n\
00504 \n\
00505 # The values array should be 1-1 with the elements of the associated\n\
00506 # PointCloud.\n\
00507 float32[] values\n\
00508 \n\
00509 "; }
00510 public:
00511 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00512
00513 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00514
00515 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00516 {
00517 ros::serialization::OStream stream(write_ptr, 1000000000);
00518 ros::serialization::serialize(stream, model);
00519 return stream.getData();
00520 }
00521
00522 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00523 {
00524 ros::serialization::IStream stream(read_ptr, 1000000000);
00525 ros::serialization::deserialize(stream, model);
00526 return stream.getData();
00527 }
00528
00529 ROS_DEPRECATED virtual uint32_t serializationLength() const
00530 {
00531 uint32_t size = 0;
00532 size += ros::serialization::serializationLength(model);
00533 return size;
00534 }
00535
00536 typedef boost::shared_ptr< ::articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> > Ptr;
00537 typedef boost::shared_ptr< ::articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> const> ConstPtr;
00538 };
00539 typedef ::articulation_msgs::TrackModelSrvResponse_<std::allocator<void> > TrackModelSrvResponse;
00540
00541 typedef boost::shared_ptr< ::articulation_msgs::TrackModelSrvResponse> TrackModelSrvResponsePtr;
00542 typedef boost::shared_ptr< ::articulation_msgs::TrackModelSrvResponse const> TrackModelSrvResponseConstPtr;
00543
00544 struct TrackModelSrv
00545 {
00546
00547 typedef TrackModelSrvRequest Request;
00548 typedef TrackModelSrvResponse Response;
00549 Request request;
00550 Response response;
00551
00552 typedef Request RequestType;
00553 typedef Response ResponseType;
00554 };
00555 }
00556
00557 namespace ros
00558 {
00559 namespace message_traits
00560 {
00561 template<class ContainerAllocator>
00562 struct MD5Sum< ::articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> > {
00563 static const char* value()
00564 {
00565 return "056375d531bc6dcbc8a3fedb4b45371f";
00566 }
00567
00568 static const char* value(const ::articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> &) { return value(); }
00569 static const uint64_t static_value1 = 0x056375d531bc6dcbULL;
00570 static const uint64_t static_value2 = 0xc8a3fedb4b45371fULL;
00571 };
00572
00573 template<class ContainerAllocator>
00574 struct DataType< ::articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> > {
00575 static const char* value()
00576 {
00577 return "articulation_msgs/TrackModelSrvRequest";
00578 }
00579
00580 static const char* value(const ::articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> &) { return value(); }
00581 };
00582
00583 template<class ContainerAllocator>
00584 struct Definition< ::articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> > {
00585 static const char* value()
00586 {
00587 return "\n\
00588 \n\
00589 \n\
00590 \n\
00591 \n\
00592 \n\
00593 \n\
00594 \n\
00595 \n\
00596 \n\
00597 \n\
00598 articulation_msgs/ModelMsg model\n\
00599 \n\
00600 \n\
00601 ================================================================================\n\
00602 MSG: articulation_msgs/ModelMsg\n\
00603 # Single kinematic model\n\
00604 #\n\
00605 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00606 # The client may additionally specify a model id, that can be used to colorize the\n\
00607 # model when visualized using the RVIZ model display.\n\
00608 # \n\
00609 # For a list of currently implemented models, see the documetation at\n\
00610 # http://www.ros.org/wiki/articulation_models\n\
00611 #\n\
00612 #\n\
00613 \n\
00614 Header header # frame and timestamp\n\
00615 \n\
00616 int32 id # user specified model id\n\
00617 string name # name of the model family (e.g. \"rotational\",\n\
00618 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00619 articulation_msgs/ParamMsg[] params # model parameters\n\
00620 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00621 # that is evaluated using the model\n\
00622 \n\
00623 ================================================================================\n\
00624 MSG: std_msgs/Header\n\
00625 # Standard metadata for higher-level stamped data types.\n\
00626 # This is generally used to communicate timestamped data \n\
00627 # in a particular coordinate frame.\n\
00628 # \n\
00629 # sequence ID: consecutively increasing ID \n\
00630 uint32 seq\n\
00631 #Two-integer timestamp that is expressed as:\n\
00632 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00633 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00634 # time-handling sugar is provided by the client library\n\
00635 time stamp\n\
00636 #Frame this data is associated with\n\
00637 # 0: no frame\n\
00638 # 1: global frame\n\
00639 string frame_id\n\
00640 \n\
00641 ================================================================================\n\
00642 MSG: articulation_msgs/ParamMsg\n\
00643 # Single parameter passed to or from model fitting\n\
00644 #\n\
00645 # This mechanism allows to flexibly pass parameters to \n\
00646 # model fitting (and vice versa). Note that these parameters \n\
00647 # are model-specific: A client may supply additional\n\
00648 # parameters to the model estimator, and, similarly, a estimator\n\
00649 # may add the estimated model parameters to the model message.\n\
00650 # When the model is then evaluated, for example to make predictions\n\
00651 # or to compute the likelihood, the model class can then use\n\
00652 # these parameters.\n\
00653 #\n\
00654 # A parameter has a name, a value, and a type. The type globally\n\
00655 # indicates whether it is a prior parameter (prior to model fitting),\n\
00656 # or a model parameter (found during model fitting, using a maximum-\n\
00657 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00658 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00659 # can therefore already be cached).\n\
00660 #\n\
00661 # For a list of currently used parameters, see the documentation at\n\
00662 # http://www.ros.org/wiki/articulation_models\n\
00663 #\n\
00664 \n\
00665 uint8 PRIOR=0 # indicates a prior model parameter \n\
00666 # (e.g., \"sigma_position\")\n\
00667 uint8 PARAM=1 # indicates a estimated model parameter \n\
00668 # (e.g., \"rot_radius\", the estimated radius)\n\
00669 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00670 # the current trajectory\n\
00671 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00672 # data, given the model and its parameters)\n\
00673 \n\
00674 string name # name of the parameter\n\
00675 float64 value # value of the parameter\n\
00676 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00677 \n\
00678 \n\
00679 ================================================================================\n\
00680 MSG: articulation_msgs/TrackMsg\n\
00681 # Single kinematic trajectory\n\
00682 #\n\
00683 # This message contains a kinematic trajectory. The trajectory is specified\n\
00684 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00685 # the track is valid, and whether it includes orientation. The track id\n\
00686 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00687 # freely chosen by the client. \n\
00688 #\n\
00689 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00690 # Additional information may be associated to each pose using the channels\n\
00691 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00692 #\n\
00693 # After model evaluation,\n\
00694 # also the associated configurations of the object are stored in the channels,\n\
00695 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00696 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00697 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00698 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00699 # range is sampled, and the result is stored in pose_resampled.\n\
00700 # The vector pose_flags contains additional display flags for the poses in the\n\
00701 # pose vector, for example, whether a pose is visible and/or\n\
00702 # the end of a trajectory segment. At the moment, this is only used by the\n\
00703 # prior_model_learner.\n\
00704 #\n\
00705 \n\
00706 Header header # Timestamp and frame\n\
00707 int32 id # used-specified track id\n\
00708 \n\
00709 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00710 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00711 # (after model evaluation)\n\
00712 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00713 # the valid configuration range\n\
00714 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00715 \n\
00716 uint32 POSE_VISIBLE=1\n\
00717 uint32 POSE_END_OF_SEGMENT=2\n\
00718 \n\
00719 # Each channel should have the same number of elements as pose array, \n\
00720 # and the data in each channel should correspond 1:1 with each pose\n\
00721 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00722 sensor_msgs/ChannelFloat32[] channels \n\
00723 \n\
00724 \n\
00725 \n\
00726 ================================================================================\n\
00727 MSG: geometry_msgs/Pose\n\
00728 # A representation of pose in free space, composed of postion and orientation. \n\
00729 Point position\n\
00730 Quaternion orientation\n\
00731 \n\
00732 ================================================================================\n\
00733 MSG: geometry_msgs/Point\n\
00734 # This contains the position of a point in free space\n\
00735 float64 x\n\
00736 float64 y\n\
00737 float64 z\n\
00738 \n\
00739 ================================================================================\n\
00740 MSG: geometry_msgs/Quaternion\n\
00741 # This represents an orientation in free space in quaternion form.\n\
00742 \n\
00743 float64 x\n\
00744 float64 y\n\
00745 float64 z\n\
00746 float64 w\n\
00747 \n\
00748 ================================================================================\n\
00749 MSG: sensor_msgs/ChannelFloat32\n\
00750 # This message is used by the PointCloud message to hold optional data\n\
00751 # associated with each point in the cloud. The length of the values\n\
00752 # array should be the same as the length of the points array in the\n\
00753 # PointCloud, and each value should be associated with the corresponding\n\
00754 # point.\n\
00755 \n\
00756 # Channel names in existing practice include:\n\
00757 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00758 # This is opposite to usual conventions but remains for\n\
00759 # historical reasons. The newer PointCloud2 message has no\n\
00760 # such problem.\n\
00761 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00762 # (R,G,B) values packed into the least significant 24 bits,\n\
00763 # in order.\n\
00764 # \"intensity\" - laser or pixel intensity.\n\
00765 # \"distance\"\n\
00766 \n\
00767 # The channel name should give semantics of the channel (e.g.\n\
00768 # \"intensity\" instead of \"value\").\n\
00769 string name\n\
00770 \n\
00771 # The values array should be 1-1 with the elements of the associated\n\
00772 # PointCloud.\n\
00773 float32[] values\n\
00774 \n\
00775 ";
00776 }
00777
00778 static const char* value(const ::articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> &) { return value(); }
00779 };
00780
00781 }
00782 }
00783
00784
00785 namespace ros
00786 {
00787 namespace message_traits
00788 {
00789 template<class ContainerAllocator>
00790 struct MD5Sum< ::articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> > {
00791 static const char* value()
00792 {
00793 return "056375d531bc6dcbc8a3fedb4b45371f";
00794 }
00795
00796 static const char* value(const ::articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> &) { return value(); }
00797 static const uint64_t static_value1 = 0x056375d531bc6dcbULL;
00798 static const uint64_t static_value2 = 0xc8a3fedb4b45371fULL;
00799 };
00800
00801 template<class ContainerAllocator>
00802 struct DataType< ::articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> > {
00803 static const char* value()
00804 {
00805 return "articulation_msgs/TrackModelSrvResponse";
00806 }
00807
00808 static const char* value(const ::articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> &) { return value(); }
00809 };
00810
00811 template<class ContainerAllocator>
00812 struct Definition< ::articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> > {
00813 static const char* value()
00814 {
00815 return "articulation_msgs/ModelMsg model\n\
00816 \n\
00817 \n\
00818 \n\
00819 \n\
00820 \n\
00821 \n\
00822 ================================================================================\n\
00823 MSG: articulation_msgs/ModelMsg\n\
00824 # Single kinematic model\n\
00825 #\n\
00826 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00827 # The client may additionally specify a model id, that can be used to colorize the\n\
00828 # model when visualized using the RVIZ model display.\n\
00829 # \n\
00830 # For a list of currently implemented models, see the documetation at\n\
00831 # http://www.ros.org/wiki/articulation_models\n\
00832 #\n\
00833 #\n\
00834 \n\
00835 Header header # frame and timestamp\n\
00836 \n\
00837 int32 id # user specified model id\n\
00838 string name # name of the model family (e.g. \"rotational\",\n\
00839 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00840 articulation_msgs/ParamMsg[] params # model parameters\n\
00841 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00842 # that is evaluated using the model\n\
00843 \n\
00844 ================================================================================\n\
00845 MSG: std_msgs/Header\n\
00846 # Standard metadata for higher-level stamped data types.\n\
00847 # This is generally used to communicate timestamped data \n\
00848 # in a particular coordinate frame.\n\
00849 # \n\
00850 # sequence ID: consecutively increasing ID \n\
00851 uint32 seq\n\
00852 #Two-integer timestamp that is expressed as:\n\
00853 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00854 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00855 # time-handling sugar is provided by the client library\n\
00856 time stamp\n\
00857 #Frame this data is associated with\n\
00858 # 0: no frame\n\
00859 # 1: global frame\n\
00860 string frame_id\n\
00861 \n\
00862 ================================================================================\n\
00863 MSG: articulation_msgs/ParamMsg\n\
00864 # Single parameter passed to or from model fitting\n\
00865 #\n\
00866 # This mechanism allows to flexibly pass parameters to \n\
00867 # model fitting (and vice versa). Note that these parameters \n\
00868 # are model-specific: A client may supply additional\n\
00869 # parameters to the model estimator, and, similarly, a estimator\n\
00870 # may add the estimated model parameters to the model message.\n\
00871 # When the model is then evaluated, for example to make predictions\n\
00872 # or to compute the likelihood, the model class can then use\n\
00873 # these parameters.\n\
00874 #\n\
00875 # A parameter has a name, a value, and a type. The type globally\n\
00876 # indicates whether it is a prior parameter (prior to model fitting),\n\
00877 # or a model parameter (found during model fitting, using a maximum-\n\
00878 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00879 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00880 # can therefore already be cached).\n\
00881 #\n\
00882 # For a list of currently used parameters, see the documentation at\n\
00883 # http://www.ros.org/wiki/articulation_models\n\
00884 #\n\
00885 \n\
00886 uint8 PRIOR=0 # indicates a prior model parameter \n\
00887 # (e.g., \"sigma_position\")\n\
00888 uint8 PARAM=1 # indicates a estimated model parameter \n\
00889 # (e.g., \"rot_radius\", the estimated radius)\n\
00890 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00891 # the current trajectory\n\
00892 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00893 # data, given the model and its parameters)\n\
00894 \n\
00895 string name # name of the parameter\n\
00896 float64 value # value of the parameter\n\
00897 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00898 \n\
00899 \n\
00900 ================================================================================\n\
00901 MSG: articulation_msgs/TrackMsg\n\
00902 # Single kinematic trajectory\n\
00903 #\n\
00904 # This message contains a kinematic trajectory. The trajectory is specified\n\
00905 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00906 # the track is valid, and whether it includes orientation. The track id\n\
00907 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00908 # freely chosen by the client. \n\
00909 #\n\
00910 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00911 # Additional information may be associated to each pose using the channels\n\
00912 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00913 #\n\
00914 # After model evaluation,\n\
00915 # also the associated configurations of the object are stored in the channels,\n\
00916 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00917 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00918 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00919 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00920 # range is sampled, and the result is stored in pose_resampled.\n\
00921 # The vector pose_flags contains additional display flags for the poses in the\n\
00922 # pose vector, for example, whether a pose is visible and/or\n\
00923 # the end of a trajectory segment. At the moment, this is only used by the\n\
00924 # prior_model_learner.\n\
00925 #\n\
00926 \n\
00927 Header header # Timestamp and frame\n\
00928 int32 id # used-specified track id\n\
00929 \n\
00930 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00931 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00932 # (after model evaluation)\n\
00933 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00934 # the valid configuration range\n\
00935 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00936 \n\
00937 uint32 POSE_VISIBLE=1\n\
00938 uint32 POSE_END_OF_SEGMENT=2\n\
00939 \n\
00940 # Each channel should have the same number of elements as pose array, \n\
00941 # and the data in each channel should correspond 1:1 with each pose\n\
00942 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00943 sensor_msgs/ChannelFloat32[] channels \n\
00944 \n\
00945 \n\
00946 \n\
00947 ================================================================================\n\
00948 MSG: geometry_msgs/Pose\n\
00949 # A representation of pose in free space, composed of postion and orientation. \n\
00950 Point position\n\
00951 Quaternion orientation\n\
00952 \n\
00953 ================================================================================\n\
00954 MSG: geometry_msgs/Point\n\
00955 # This contains the position of a point in free space\n\
00956 float64 x\n\
00957 float64 y\n\
00958 float64 z\n\
00959 \n\
00960 ================================================================================\n\
00961 MSG: geometry_msgs/Quaternion\n\
00962 # This represents an orientation in free space in quaternion form.\n\
00963 \n\
00964 float64 x\n\
00965 float64 y\n\
00966 float64 z\n\
00967 float64 w\n\
00968 \n\
00969 ================================================================================\n\
00970 MSG: sensor_msgs/ChannelFloat32\n\
00971 # This message is used by the PointCloud message to hold optional data\n\
00972 # associated with each point in the cloud. The length of the values\n\
00973 # array should be the same as the length of the points array in the\n\
00974 # PointCloud, and each value should be associated with the corresponding\n\
00975 # point.\n\
00976 \n\
00977 # Channel names in existing practice include:\n\
00978 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00979 # This is opposite to usual conventions but remains for\n\
00980 # historical reasons. The newer PointCloud2 message has no\n\
00981 # such problem.\n\
00982 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00983 # (R,G,B) values packed into the least significant 24 bits,\n\
00984 # in order.\n\
00985 # \"intensity\" - laser or pixel intensity.\n\
00986 # \"distance\"\n\
00987 \n\
00988 # The channel name should give semantics of the channel (e.g.\n\
00989 # \"intensity\" instead of \"value\").\n\
00990 string name\n\
00991 \n\
00992 # The values array should be 1-1 with the elements of the associated\n\
00993 # PointCloud.\n\
00994 float32[] values\n\
00995 \n\
00996 ";
00997 }
00998
00999 static const char* value(const ::articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> &) { return value(); }
01000 };
01001
01002 }
01003 }
01004
01005 namespace ros
01006 {
01007 namespace serialization
01008 {
01009
01010 template<class ContainerAllocator> struct Serializer< ::articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> >
01011 {
01012 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01013 {
01014 stream.next(m.model);
01015 }
01016
01017 ROS_DECLARE_ALLINONE_SERIALIZER;
01018 };
01019 }
01020 }
01021
01022
01023 namespace ros
01024 {
01025 namespace serialization
01026 {
01027
01028 template<class ContainerAllocator> struct Serializer< ::articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> >
01029 {
01030 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01031 {
01032 stream.next(m.model);
01033 }
01034
01035 ROS_DECLARE_ALLINONE_SERIALIZER;
01036 };
01037 }
01038 }
01039
01040 namespace ros
01041 {
01042 namespace service_traits
01043 {
01044 template<>
01045 struct MD5Sum<articulation_msgs::TrackModelSrv> {
01046 static const char* value()
01047 {
01048 return "eba693fb01232c71f70038728ca60d66";
01049 }
01050
01051 static const char* value(const articulation_msgs::TrackModelSrv&) { return value(); }
01052 };
01053
01054 template<>
01055 struct DataType<articulation_msgs::TrackModelSrv> {
01056 static const char* value()
01057 {
01058 return "articulation_msgs/TrackModelSrv";
01059 }
01060
01061 static const char* value(const articulation_msgs::TrackModelSrv&) { return value(); }
01062 };
01063
01064 template<class ContainerAllocator>
01065 struct MD5Sum<articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> > {
01066 static const char* value()
01067 {
01068 return "eba693fb01232c71f70038728ca60d66";
01069 }
01070
01071 static const char* value(const articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> &) { return value(); }
01072 };
01073
01074 template<class ContainerAllocator>
01075 struct DataType<articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> > {
01076 static const char* value()
01077 {
01078 return "articulation_msgs/TrackModelSrv";
01079 }
01080
01081 static const char* value(const articulation_msgs::TrackModelSrvRequest_<ContainerAllocator> &) { return value(); }
01082 };
01083
01084 template<class ContainerAllocator>
01085 struct MD5Sum<articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> > {
01086 static const char* value()
01087 {
01088 return "eba693fb01232c71f70038728ca60d66";
01089 }
01090
01091 static const char* value(const articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> &) { return value(); }
01092 };
01093
01094 template<class ContainerAllocator>
01095 struct DataType<articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> > {
01096 static const char* value()
01097 {
01098 return "articulation_msgs/TrackModelSrv";
01099 }
01100
01101 static const char* value(const articulation_msgs::TrackModelSrvResponse_<ContainerAllocator> &) { return value(); }
01102 };
01103
01104 }
01105 }
01106
01107 #endif // ARTICULATION_MSGS_SERVICE_TRACKMODELSRV_H
01108