00001
00002 #ifndef ARTICULATION_MSGS_SERVICE_ARTICULATEDOBJECTSRV_H
00003 #define ARTICULATION_MSGS_SERVICE_ARTICULATEDOBJECTSRV_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/ArticulatedObjectMsg.h"
00016
00017
00018 #include "articulation_msgs/ArticulatedObjectMsg.h"
00019
00020 namespace articulation_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct ArticulatedObjectSrvRequest_ : public ros::Message
00024 {
00025 typedef ArticulatedObjectSrvRequest_<ContainerAllocator> Type;
00026
00027 ArticulatedObjectSrvRequest_()
00028 : object()
00029 {
00030 }
00031
00032 ArticulatedObjectSrvRequest_(const ContainerAllocator& _alloc)
00033 : object(_alloc)
00034 {
00035 }
00036
00037 typedef ::articulation_msgs::ArticulatedObjectMsg_<ContainerAllocator> _object_type;
00038 ::articulation_msgs::ArticulatedObjectMsg_<ContainerAllocator> object;
00039
00040
00041 private:
00042 static const char* __s_getDataType_() { return "articulation_msgs/ArticulatedObjectSrvRequest"; }
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 "929d83624d0744de900991740e4bff8e"; }
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 "d13520b58d3ca45a23cc7f92f8661f22"; }
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 articulation_msgs/ArticulatedObjectMsg object\n\
00073 \n\
00074 \n\
00075 ================================================================================\n\
00076 MSG: articulation_msgs/ArticulatedObjectMsg\n\
00077 Header header\n\
00078 \n\
00079 articulation_msgs/TrackMsg[] parts # observed trajectories for each object part \n\
00080 articulation_msgs/ParamMsg[] params # global parameters\n\
00081 articulation_msgs/ModelMsg[] models # models, describing relationships between parts\n\
00082 visualization_msgs/MarkerArray markers # marker visualization of models/object \n\
00083 ================================================================================\n\
00084 MSG: std_msgs/Header\n\
00085 # Standard metadata for higher-level stamped data types.\n\
00086 # This is generally used to communicate timestamped data \n\
00087 # in a particular coordinate frame.\n\
00088 # \n\
00089 # sequence ID: consecutively increasing ID \n\
00090 uint32 seq\n\
00091 #Two-integer timestamp that is expressed as:\n\
00092 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00093 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00094 # time-handling sugar is provided by the client library\n\
00095 time stamp\n\
00096 #Frame this data is associated with\n\
00097 # 0: no frame\n\
00098 # 1: global frame\n\
00099 string frame_id\n\
00100 \n\
00101 ================================================================================\n\
00102 MSG: articulation_msgs/TrackMsg\n\
00103 # Single kinematic trajectory\n\
00104 #\n\
00105 # This message contains a kinematic trajectory. The trajectory is specified\n\
00106 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00107 # the track is valid, and whether it includes orientation. The track id\n\
00108 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00109 # freely chosen by the client. \n\
00110 #\n\
00111 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00112 # Additional information may be associated to each pose using the channels\n\
00113 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00114 #\n\
00115 # After model evaluation,\n\
00116 # also the associated configurations of the object are stored in the channels,\n\
00117 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00118 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00119 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00120 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00121 # range is sampled, and the result is stored in pose_resampled.\n\
00122 # The vector pose_flags contains additional display flags for the poses in the\n\
00123 # pose vector, for example, whether a pose is visible and/or\n\
00124 # the end of a trajectory segment. At the moment, this is only used by the\n\
00125 # prior_model_learner.\n\
00126 #\n\
00127 \n\
00128 Header header # Timestamp and frame\n\
00129 int32 id # used-specified track id\n\
00130 \n\
00131 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00132 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00133 # (after model evaluation)\n\
00134 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00135 # the valid configuration range\n\
00136 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00137 \n\
00138 uint32 POSE_VISIBLE=1\n\
00139 uint32 POSE_END_OF_SEGMENT=2\n\
00140 \n\
00141 # Each channel should have the same number of elements as pose array, \n\
00142 # and the data in each channel should correspond 1:1 with each pose\n\
00143 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00144 sensor_msgs/ChannelFloat32[] channels \n\
00145 \n\
00146 \n\
00147 \n\
00148 ================================================================================\n\
00149 MSG: geometry_msgs/Pose\n\
00150 # A representation of pose in free space, composed of postion and orientation. \n\
00151 Point position\n\
00152 Quaternion orientation\n\
00153 \n\
00154 ================================================================================\n\
00155 MSG: geometry_msgs/Point\n\
00156 # This contains the position of a point in free space\n\
00157 float64 x\n\
00158 float64 y\n\
00159 float64 z\n\
00160 \n\
00161 ================================================================================\n\
00162 MSG: geometry_msgs/Quaternion\n\
00163 # This represents an orientation in free space in quaternion form.\n\
00164 \n\
00165 float64 x\n\
00166 float64 y\n\
00167 float64 z\n\
00168 float64 w\n\
00169 \n\
00170 ================================================================================\n\
00171 MSG: sensor_msgs/ChannelFloat32\n\
00172 # This message is used by the PointCloud message to hold optional data\n\
00173 # associated with each point in the cloud. The length of the values\n\
00174 # array should be the same as the length of the points array in the\n\
00175 # PointCloud, and each value should be associated with the corresponding\n\
00176 # point.\n\
00177 \n\
00178 # Channel names in existing practice include:\n\
00179 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00180 # This is opposite to usual conventions but remains for\n\
00181 # historical reasons. The newer PointCloud2 message has no\n\
00182 # such problem.\n\
00183 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00184 # (R,G,B) values packed into the least significant 24 bits,\n\
00185 # in order.\n\
00186 # \"intensity\" - laser or pixel intensity.\n\
00187 # \"distance\"\n\
00188 \n\
00189 # The channel name should give semantics of the channel (e.g.\n\
00190 # \"intensity\" instead of \"value\").\n\
00191 string name\n\
00192 \n\
00193 # The values array should be 1-1 with the elements of the associated\n\
00194 # PointCloud.\n\
00195 float32[] values\n\
00196 \n\
00197 ================================================================================\n\
00198 MSG: articulation_msgs/ParamMsg\n\
00199 # Single parameter passed to or from model fitting\n\
00200 #\n\
00201 # This mechanism allows to flexibly pass parameters to \n\
00202 # model fitting (and vice versa). Note that these parameters \n\
00203 # are model-specific: A client may supply additional\n\
00204 # parameters to the model estimator, and, similarly, a estimator\n\
00205 # may add the estimated model parameters to the model message.\n\
00206 # When the model is then evaluated, for example to make predictions\n\
00207 # or to compute the likelihood, the model class can then use\n\
00208 # these parameters.\n\
00209 #\n\
00210 # A parameter has a name, a value, and a type. The type globally\n\
00211 # indicates whether it is a prior parameter (prior to model fitting),\n\
00212 # or a model parameter (found during model fitting, using a maximum-\n\
00213 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00214 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00215 # can therefore already be cached).\n\
00216 #\n\
00217 # For a list of currently used parameters, see the documentation at\n\
00218 # http://www.ros.org/wiki/articulation_models\n\
00219 #\n\
00220 \n\
00221 uint8 PRIOR=0 # indicates a prior model parameter \n\
00222 # (e.g., \"sigma_position\")\n\
00223 uint8 PARAM=1 # indicates a estimated model parameter \n\
00224 # (e.g., \"rot_radius\", the estimated radius)\n\
00225 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00226 # the current trajectory\n\
00227 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00228 # data, given the model and its parameters)\n\
00229 \n\
00230 string name # name of the parameter\n\
00231 float64 value # value of the parameter\n\
00232 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00233 \n\
00234 \n\
00235 ================================================================================\n\
00236 MSG: articulation_msgs/ModelMsg\n\
00237 # Single kinematic model\n\
00238 #\n\
00239 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00240 # The client may additionally specify a model id, that can be used to colorize the\n\
00241 # model when visualized using the RVIZ model display.\n\
00242 # \n\
00243 # For a list of currently implemented models, see the documetation at\n\
00244 # http://www.ros.org/wiki/articulation_models\n\
00245 #\n\
00246 #\n\
00247 \n\
00248 Header header # frame and timestamp\n\
00249 \n\
00250 int32 id # user specified model id\n\
00251 string name # name of the model family (e.g. \"rotational\",\n\
00252 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00253 articulation_msgs/ParamMsg[] params # model parameters\n\
00254 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00255 # that is evaluated using the model\n\
00256 \n\
00257 ================================================================================\n\
00258 MSG: visualization_msgs/MarkerArray\n\
00259 Marker[] markers\n\
00260 \n\
00261 ================================================================================\n\
00262 MSG: visualization_msgs/Marker\n\
00263 # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz\n\
00264 \n\
00265 byte ARROW=0\n\
00266 byte CUBE=1\n\
00267 byte SPHERE=2\n\
00268 byte CYLINDER=3\n\
00269 byte LINE_STRIP=4\n\
00270 byte LINE_LIST=5\n\
00271 byte CUBE_LIST=6\n\
00272 byte SPHERE_LIST=7\n\
00273 byte POINTS=8\n\
00274 byte TEXT_VIEW_FACING=9\n\
00275 byte MESH_RESOURCE=10\n\
00276 byte TRIANGLE_LIST=11\n\
00277 \n\
00278 byte ADD=0\n\
00279 byte MODIFY=0\n\
00280 byte DELETE=2\n\
00281 \n\
00282 Header header # header for time/frame information\n\
00283 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n\
00284 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n\
00285 int32 type # Type of object\n\
00286 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object\n\
00287 geometry_msgs/Pose pose # Pose of the object\n\
00288 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n\
00289 std_msgs/ColorRGBA color # Color [0.0-1.0]\n\
00290 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\
00291 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n\
00292 \n\
00293 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00294 geometry_msgs/Point[] points\n\
00295 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00296 #number of colors must either be 0 or equal to the number of points\n\
00297 #NOTE: alpha is not yet used\n\
00298 std_msgs/ColorRGBA[] colors\n\
00299 \n\
00300 # NOTE: only used for text markers\n\
00301 string text\n\
00302 \n\
00303 # NOTE: only used for MESH_RESOURCE markers\n\
00304 string mesh_resource\n\
00305 bool mesh_use_embedded_materials\n\
00306 \n\
00307 ================================================================================\n\
00308 MSG: geometry_msgs/Vector3\n\
00309 # This represents a vector in free space. \n\
00310 \n\
00311 float64 x\n\
00312 float64 y\n\
00313 float64 z\n\
00314 ================================================================================\n\
00315 MSG: std_msgs/ColorRGBA\n\
00316 float32 r\n\
00317 float32 g\n\
00318 float32 b\n\
00319 float32 a\n\
00320 \n\
00321 "; }
00322 public:
00323 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00324
00325 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00326
00327 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00328 {
00329 ros::serialization::OStream stream(write_ptr, 1000000000);
00330 ros::serialization::serialize(stream, object);
00331 return stream.getData();
00332 }
00333
00334 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00335 {
00336 ros::serialization::IStream stream(read_ptr, 1000000000);
00337 ros::serialization::deserialize(stream, object);
00338 return stream.getData();
00339 }
00340
00341 ROS_DEPRECATED virtual uint32_t serializationLength() const
00342 {
00343 uint32_t size = 0;
00344 size += ros::serialization::serializationLength(object);
00345 return size;
00346 }
00347
00348 typedef boost::shared_ptr< ::articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> > Ptr;
00349 typedef boost::shared_ptr< ::articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> const> ConstPtr;
00350 };
00351 typedef ::articulation_msgs::ArticulatedObjectSrvRequest_<std::allocator<void> > ArticulatedObjectSrvRequest;
00352
00353 typedef boost::shared_ptr< ::articulation_msgs::ArticulatedObjectSrvRequest> ArticulatedObjectSrvRequestPtr;
00354 typedef boost::shared_ptr< ::articulation_msgs::ArticulatedObjectSrvRequest const> ArticulatedObjectSrvRequestConstPtr;
00355
00356
00357 template <class ContainerAllocator>
00358 struct ArticulatedObjectSrvResponse_ : public ros::Message
00359 {
00360 typedef ArticulatedObjectSrvResponse_<ContainerAllocator> Type;
00361
00362 ArticulatedObjectSrvResponse_()
00363 : object()
00364 {
00365 }
00366
00367 ArticulatedObjectSrvResponse_(const ContainerAllocator& _alloc)
00368 : object(_alloc)
00369 {
00370 }
00371
00372 typedef ::articulation_msgs::ArticulatedObjectMsg_<ContainerAllocator> _object_type;
00373 ::articulation_msgs::ArticulatedObjectMsg_<ContainerAllocator> object;
00374
00375
00376 private:
00377 static const char* __s_getDataType_() { return "articulation_msgs/ArticulatedObjectSrvResponse"; }
00378 public:
00379 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00380
00381 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00382
00383 private:
00384 static const char* __s_getMD5Sum_() { return "929d83624d0744de900991740e4bff8e"; }
00385 public:
00386 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00387
00388 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00389
00390 private:
00391 static const char* __s_getServerMD5Sum_() { return "d13520b58d3ca45a23cc7f92f8661f22"; }
00392 public:
00393 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00394
00395 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00396
00397 private:
00398 static const char* __s_getMessageDefinition_() { return "articulation_msgs/ArticulatedObjectMsg object\n\
00399 \n\
00400 \n\
00401 \n\
00402 \n\
00403 \n\
00404 \n\
00405 ================================================================================\n\
00406 MSG: articulation_msgs/ArticulatedObjectMsg\n\
00407 Header header\n\
00408 \n\
00409 articulation_msgs/TrackMsg[] parts # observed trajectories for each object part \n\
00410 articulation_msgs/ParamMsg[] params # global parameters\n\
00411 articulation_msgs/ModelMsg[] models # models, describing relationships between parts\n\
00412 visualization_msgs/MarkerArray markers # marker visualization of models/object \n\
00413 ================================================================================\n\
00414 MSG: std_msgs/Header\n\
00415 # Standard metadata for higher-level stamped data types.\n\
00416 # This is generally used to communicate timestamped data \n\
00417 # in a particular coordinate frame.\n\
00418 # \n\
00419 # sequence ID: consecutively increasing ID \n\
00420 uint32 seq\n\
00421 #Two-integer timestamp that is expressed as:\n\
00422 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00423 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00424 # time-handling sugar is provided by the client library\n\
00425 time stamp\n\
00426 #Frame this data is associated with\n\
00427 # 0: no frame\n\
00428 # 1: global frame\n\
00429 string frame_id\n\
00430 \n\
00431 ================================================================================\n\
00432 MSG: articulation_msgs/TrackMsg\n\
00433 # Single kinematic trajectory\n\
00434 #\n\
00435 # This message contains a kinematic trajectory. The trajectory is specified\n\
00436 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00437 # the track is valid, and whether it includes orientation. The track id\n\
00438 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00439 # freely chosen by the client. \n\
00440 #\n\
00441 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00442 # Additional information may be associated to each pose using the channels\n\
00443 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00444 #\n\
00445 # After model evaluation,\n\
00446 # also the associated configurations of the object are stored in the channels,\n\
00447 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00448 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00449 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00450 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00451 # range is sampled, and the result is stored in pose_resampled.\n\
00452 # The vector pose_flags contains additional display flags for the poses in the\n\
00453 # pose vector, for example, whether a pose is visible and/or\n\
00454 # the end of a trajectory segment. At the moment, this is only used by the\n\
00455 # prior_model_learner.\n\
00456 #\n\
00457 \n\
00458 Header header # Timestamp and frame\n\
00459 int32 id # used-specified track id\n\
00460 \n\
00461 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00462 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00463 # (after model evaluation)\n\
00464 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00465 # the valid configuration range\n\
00466 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00467 \n\
00468 uint32 POSE_VISIBLE=1\n\
00469 uint32 POSE_END_OF_SEGMENT=2\n\
00470 \n\
00471 # Each channel should have the same number of elements as pose array, \n\
00472 # and the data in each channel should correspond 1:1 with each pose\n\
00473 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00474 sensor_msgs/ChannelFloat32[] channels \n\
00475 \n\
00476 \n\
00477 \n\
00478 ================================================================================\n\
00479 MSG: geometry_msgs/Pose\n\
00480 # A representation of pose in free space, composed of postion and orientation. \n\
00481 Point position\n\
00482 Quaternion orientation\n\
00483 \n\
00484 ================================================================================\n\
00485 MSG: geometry_msgs/Point\n\
00486 # This contains the position of a point in free space\n\
00487 float64 x\n\
00488 float64 y\n\
00489 float64 z\n\
00490 \n\
00491 ================================================================================\n\
00492 MSG: geometry_msgs/Quaternion\n\
00493 # This represents an orientation in free space in quaternion form.\n\
00494 \n\
00495 float64 x\n\
00496 float64 y\n\
00497 float64 z\n\
00498 float64 w\n\
00499 \n\
00500 ================================================================================\n\
00501 MSG: sensor_msgs/ChannelFloat32\n\
00502 # This message is used by the PointCloud message to hold optional data\n\
00503 # associated with each point in the cloud. The length of the values\n\
00504 # array should be the same as the length of the points array in the\n\
00505 # PointCloud, and each value should be associated with the corresponding\n\
00506 # point.\n\
00507 \n\
00508 # Channel names in existing practice include:\n\
00509 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00510 # This is opposite to usual conventions but remains for\n\
00511 # historical reasons. The newer PointCloud2 message has no\n\
00512 # such problem.\n\
00513 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00514 # (R,G,B) values packed into the least significant 24 bits,\n\
00515 # in order.\n\
00516 # \"intensity\" - laser or pixel intensity.\n\
00517 # \"distance\"\n\
00518 \n\
00519 # The channel name should give semantics of the channel (e.g.\n\
00520 # \"intensity\" instead of \"value\").\n\
00521 string name\n\
00522 \n\
00523 # The values array should be 1-1 with the elements of the associated\n\
00524 # PointCloud.\n\
00525 float32[] values\n\
00526 \n\
00527 ================================================================================\n\
00528 MSG: articulation_msgs/ParamMsg\n\
00529 # Single parameter passed to or from model fitting\n\
00530 #\n\
00531 # This mechanism allows to flexibly pass parameters to \n\
00532 # model fitting (and vice versa). Note that these parameters \n\
00533 # are model-specific: A client may supply additional\n\
00534 # parameters to the model estimator, and, similarly, a estimator\n\
00535 # may add the estimated model parameters to the model message.\n\
00536 # When the model is then evaluated, for example to make predictions\n\
00537 # or to compute the likelihood, the model class can then use\n\
00538 # these parameters.\n\
00539 #\n\
00540 # A parameter has a name, a value, and a type. The type globally\n\
00541 # indicates whether it is a prior parameter (prior to model fitting),\n\
00542 # or a model parameter (found during model fitting, using a maximum-\n\
00543 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00544 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00545 # can therefore already be cached).\n\
00546 #\n\
00547 # For a list of currently used parameters, see the documentation at\n\
00548 # http://www.ros.org/wiki/articulation_models\n\
00549 #\n\
00550 \n\
00551 uint8 PRIOR=0 # indicates a prior model parameter \n\
00552 # (e.g., \"sigma_position\")\n\
00553 uint8 PARAM=1 # indicates a estimated model parameter \n\
00554 # (e.g., \"rot_radius\", the estimated radius)\n\
00555 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00556 # the current trajectory\n\
00557 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00558 # data, given the model and its parameters)\n\
00559 \n\
00560 string name # name of the parameter\n\
00561 float64 value # value of the parameter\n\
00562 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00563 \n\
00564 \n\
00565 ================================================================================\n\
00566 MSG: articulation_msgs/ModelMsg\n\
00567 # Single kinematic model\n\
00568 #\n\
00569 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00570 # The client may additionally specify a model id, that can be used to colorize the\n\
00571 # model when visualized using the RVIZ model display.\n\
00572 # \n\
00573 # For a list of currently implemented models, see the documetation at\n\
00574 # http://www.ros.org/wiki/articulation_models\n\
00575 #\n\
00576 #\n\
00577 \n\
00578 Header header # frame and timestamp\n\
00579 \n\
00580 int32 id # user specified model id\n\
00581 string name # name of the model family (e.g. \"rotational\",\n\
00582 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00583 articulation_msgs/ParamMsg[] params # model parameters\n\
00584 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00585 # that is evaluated using the model\n\
00586 \n\
00587 ================================================================================\n\
00588 MSG: visualization_msgs/MarkerArray\n\
00589 Marker[] markers\n\
00590 \n\
00591 ================================================================================\n\
00592 MSG: visualization_msgs/Marker\n\
00593 # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz\n\
00594 \n\
00595 byte ARROW=0\n\
00596 byte CUBE=1\n\
00597 byte SPHERE=2\n\
00598 byte CYLINDER=3\n\
00599 byte LINE_STRIP=4\n\
00600 byte LINE_LIST=5\n\
00601 byte CUBE_LIST=6\n\
00602 byte SPHERE_LIST=7\n\
00603 byte POINTS=8\n\
00604 byte TEXT_VIEW_FACING=9\n\
00605 byte MESH_RESOURCE=10\n\
00606 byte TRIANGLE_LIST=11\n\
00607 \n\
00608 byte ADD=0\n\
00609 byte MODIFY=0\n\
00610 byte DELETE=2\n\
00611 \n\
00612 Header header # header for time/frame information\n\
00613 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n\
00614 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n\
00615 int32 type # Type of object\n\
00616 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object\n\
00617 geometry_msgs/Pose pose # Pose of the object\n\
00618 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n\
00619 std_msgs/ColorRGBA color # Color [0.0-1.0]\n\
00620 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\
00621 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n\
00622 \n\
00623 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00624 geometry_msgs/Point[] points\n\
00625 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00626 #number of colors must either be 0 or equal to the number of points\n\
00627 #NOTE: alpha is not yet used\n\
00628 std_msgs/ColorRGBA[] colors\n\
00629 \n\
00630 # NOTE: only used for text markers\n\
00631 string text\n\
00632 \n\
00633 # NOTE: only used for MESH_RESOURCE markers\n\
00634 string mesh_resource\n\
00635 bool mesh_use_embedded_materials\n\
00636 \n\
00637 ================================================================================\n\
00638 MSG: geometry_msgs/Vector3\n\
00639 # This represents a vector in free space. \n\
00640 \n\
00641 float64 x\n\
00642 float64 y\n\
00643 float64 z\n\
00644 ================================================================================\n\
00645 MSG: std_msgs/ColorRGBA\n\
00646 float32 r\n\
00647 float32 g\n\
00648 float32 b\n\
00649 float32 a\n\
00650 \n\
00651 "; }
00652 public:
00653 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00654
00655 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00656
00657 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00658 {
00659 ros::serialization::OStream stream(write_ptr, 1000000000);
00660 ros::serialization::serialize(stream, object);
00661 return stream.getData();
00662 }
00663
00664 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00665 {
00666 ros::serialization::IStream stream(read_ptr, 1000000000);
00667 ros::serialization::deserialize(stream, object);
00668 return stream.getData();
00669 }
00670
00671 ROS_DEPRECATED virtual uint32_t serializationLength() const
00672 {
00673 uint32_t size = 0;
00674 size += ros::serialization::serializationLength(object);
00675 return size;
00676 }
00677
00678 typedef boost::shared_ptr< ::articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> > Ptr;
00679 typedef boost::shared_ptr< ::articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> const> ConstPtr;
00680 };
00681 typedef ::articulation_msgs::ArticulatedObjectSrvResponse_<std::allocator<void> > ArticulatedObjectSrvResponse;
00682
00683 typedef boost::shared_ptr< ::articulation_msgs::ArticulatedObjectSrvResponse> ArticulatedObjectSrvResponsePtr;
00684 typedef boost::shared_ptr< ::articulation_msgs::ArticulatedObjectSrvResponse const> ArticulatedObjectSrvResponseConstPtr;
00685
00686 struct ArticulatedObjectSrv
00687 {
00688
00689 typedef ArticulatedObjectSrvRequest Request;
00690 typedef ArticulatedObjectSrvResponse Response;
00691 Request request;
00692 Response response;
00693
00694 typedef Request RequestType;
00695 typedef Response ResponseType;
00696 };
00697 }
00698
00699 namespace ros
00700 {
00701 namespace message_traits
00702 {
00703 template<class ContainerAllocator>
00704 struct MD5Sum< ::articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> > {
00705 static const char* value()
00706 {
00707 return "929d83624d0744de900991740e4bff8e";
00708 }
00709
00710 static const char* value(const ::articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> &) { return value(); }
00711 static const uint64_t static_value1 = 0x929d83624d0744deULL;
00712 static const uint64_t static_value2 = 0x900991740e4bff8eULL;
00713 };
00714
00715 template<class ContainerAllocator>
00716 struct DataType< ::articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> > {
00717 static const char* value()
00718 {
00719 return "articulation_msgs/ArticulatedObjectSrvRequest";
00720 }
00721
00722 static const char* value(const ::articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> &) { return value(); }
00723 };
00724
00725 template<class ContainerAllocator>
00726 struct Definition< ::articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> > {
00727 static const char* value()
00728 {
00729 return "\n\
00730 \n\
00731 \n\
00732 \n\
00733 \n\
00734 \n\
00735 \n\
00736 \n\
00737 \n\
00738 articulation_msgs/ArticulatedObjectMsg object\n\
00739 \n\
00740 \n\
00741 ================================================================================\n\
00742 MSG: articulation_msgs/ArticulatedObjectMsg\n\
00743 Header header\n\
00744 \n\
00745 articulation_msgs/TrackMsg[] parts # observed trajectories for each object part \n\
00746 articulation_msgs/ParamMsg[] params # global parameters\n\
00747 articulation_msgs/ModelMsg[] models # models, describing relationships between parts\n\
00748 visualization_msgs/MarkerArray markers # marker visualization of models/object \n\
00749 ================================================================================\n\
00750 MSG: std_msgs/Header\n\
00751 # Standard metadata for higher-level stamped data types.\n\
00752 # This is generally used to communicate timestamped data \n\
00753 # in a particular coordinate frame.\n\
00754 # \n\
00755 # sequence ID: consecutively increasing ID \n\
00756 uint32 seq\n\
00757 #Two-integer timestamp that is expressed as:\n\
00758 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00759 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00760 # time-handling sugar is provided by the client library\n\
00761 time stamp\n\
00762 #Frame this data is associated with\n\
00763 # 0: no frame\n\
00764 # 1: global frame\n\
00765 string frame_id\n\
00766 \n\
00767 ================================================================================\n\
00768 MSG: articulation_msgs/TrackMsg\n\
00769 # Single kinematic trajectory\n\
00770 #\n\
00771 # This message contains a kinematic trajectory. The trajectory is specified\n\
00772 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
00773 # the track is valid, and whether it includes orientation. The track id\n\
00774 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
00775 # freely chosen by the client. \n\
00776 #\n\
00777 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
00778 # Additional information may be associated to each pose using the channels\n\
00779 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
00780 #\n\
00781 # After model evaluation,\n\
00782 # also the associated configurations of the object are stored in the channels,\n\
00783 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
00784 # Model evaluation also projects the poses in the pose vector onto the model,\n\
00785 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
00786 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
00787 # range is sampled, and the result is stored in pose_resampled.\n\
00788 # The vector pose_flags contains additional display flags for the poses in the\n\
00789 # pose vector, for example, whether a pose is visible and/or\n\
00790 # the end of a trajectory segment. At the moment, this is only used by the\n\
00791 # prior_model_learner.\n\
00792 #\n\
00793 \n\
00794 Header header # Timestamp and frame\n\
00795 int32 id # used-specified track id\n\
00796 \n\
00797 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
00798 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
00799 # (after model evaluation)\n\
00800 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
00801 # the valid configuration range\n\
00802 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
00803 \n\
00804 uint32 POSE_VISIBLE=1\n\
00805 uint32 POSE_END_OF_SEGMENT=2\n\
00806 \n\
00807 # Each channel should have the same number of elements as pose array, \n\
00808 # and the data in each channel should correspond 1:1 with each pose\n\
00809 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
00810 sensor_msgs/ChannelFloat32[] channels \n\
00811 \n\
00812 \n\
00813 \n\
00814 ================================================================================\n\
00815 MSG: geometry_msgs/Pose\n\
00816 # A representation of pose in free space, composed of postion and orientation. \n\
00817 Point position\n\
00818 Quaternion orientation\n\
00819 \n\
00820 ================================================================================\n\
00821 MSG: geometry_msgs/Point\n\
00822 # This contains the position of a point in free space\n\
00823 float64 x\n\
00824 float64 y\n\
00825 float64 z\n\
00826 \n\
00827 ================================================================================\n\
00828 MSG: geometry_msgs/Quaternion\n\
00829 # This represents an orientation in free space in quaternion form.\n\
00830 \n\
00831 float64 x\n\
00832 float64 y\n\
00833 float64 z\n\
00834 float64 w\n\
00835 \n\
00836 ================================================================================\n\
00837 MSG: sensor_msgs/ChannelFloat32\n\
00838 # This message is used by the PointCloud message to hold optional data\n\
00839 # associated with each point in the cloud. The length of the values\n\
00840 # array should be the same as the length of the points array in the\n\
00841 # PointCloud, and each value should be associated with the corresponding\n\
00842 # point.\n\
00843 \n\
00844 # Channel names in existing practice include:\n\
00845 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00846 # This is opposite to usual conventions but remains for\n\
00847 # historical reasons. The newer PointCloud2 message has no\n\
00848 # such problem.\n\
00849 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00850 # (R,G,B) values packed into the least significant 24 bits,\n\
00851 # in order.\n\
00852 # \"intensity\" - laser or pixel intensity.\n\
00853 # \"distance\"\n\
00854 \n\
00855 # The channel name should give semantics of the channel (e.g.\n\
00856 # \"intensity\" instead of \"value\").\n\
00857 string name\n\
00858 \n\
00859 # The values array should be 1-1 with the elements of the associated\n\
00860 # PointCloud.\n\
00861 float32[] values\n\
00862 \n\
00863 ================================================================================\n\
00864 MSG: articulation_msgs/ParamMsg\n\
00865 # Single parameter passed to or from model fitting\n\
00866 #\n\
00867 # This mechanism allows to flexibly pass parameters to \n\
00868 # model fitting (and vice versa). Note that these parameters \n\
00869 # are model-specific: A client may supply additional\n\
00870 # parameters to the model estimator, and, similarly, a estimator\n\
00871 # may add the estimated model parameters to the model message.\n\
00872 # When the model is then evaluated, for example to make predictions\n\
00873 # or to compute the likelihood, the model class can then use\n\
00874 # these parameters.\n\
00875 #\n\
00876 # A parameter has a name, a value, and a type. The type globally\n\
00877 # indicates whether it is a prior parameter (prior to model fitting),\n\
00878 # or a model parameter (found during model fitting, using a maximum-\n\
00879 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
00880 # or the BIC are a typical \"side\"-product of model estimation, and\n\
00881 # can therefore already be cached).\n\
00882 #\n\
00883 # For a list of currently used parameters, see the documentation at\n\
00884 # http://www.ros.org/wiki/articulation_models\n\
00885 #\n\
00886 \n\
00887 uint8 PRIOR=0 # indicates a prior model parameter \n\
00888 # (e.g., \"sigma_position\")\n\
00889 uint8 PARAM=1 # indicates a estimated model parameter \n\
00890 # (e.g., \"rot_radius\", the estimated radius)\n\
00891 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
00892 # the current trajectory\n\
00893 # (e.g., \"loglikelihood\", the log likelihood of the\n\
00894 # data, given the model and its parameters)\n\
00895 \n\
00896 string name # name of the parameter\n\
00897 float64 value # value of the parameter\n\
00898 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
00899 \n\
00900 \n\
00901 ================================================================================\n\
00902 MSG: articulation_msgs/ModelMsg\n\
00903 # Single kinematic model\n\
00904 #\n\
00905 # A kinematic model is defined by its model class name, and a set of parameters. \n\
00906 # The client may additionally specify a model id, that can be used to colorize the\n\
00907 # model when visualized using the RVIZ model display.\n\
00908 # \n\
00909 # For a list of currently implemented models, see the documetation at\n\
00910 # http://www.ros.org/wiki/articulation_models\n\
00911 #\n\
00912 #\n\
00913 \n\
00914 Header header # frame and timestamp\n\
00915 \n\
00916 int32 id # user specified model id\n\
00917 string name # name of the model family (e.g. \"rotational\",\n\
00918 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
00919 articulation_msgs/ParamMsg[] params # model parameters\n\
00920 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
00921 # that is evaluated using the model\n\
00922 \n\
00923 ================================================================================\n\
00924 MSG: visualization_msgs/MarkerArray\n\
00925 Marker[] markers\n\
00926 \n\
00927 ================================================================================\n\
00928 MSG: visualization_msgs/Marker\n\
00929 # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz\n\
00930 \n\
00931 byte ARROW=0\n\
00932 byte CUBE=1\n\
00933 byte SPHERE=2\n\
00934 byte CYLINDER=3\n\
00935 byte LINE_STRIP=4\n\
00936 byte LINE_LIST=5\n\
00937 byte CUBE_LIST=6\n\
00938 byte SPHERE_LIST=7\n\
00939 byte POINTS=8\n\
00940 byte TEXT_VIEW_FACING=9\n\
00941 byte MESH_RESOURCE=10\n\
00942 byte TRIANGLE_LIST=11\n\
00943 \n\
00944 byte ADD=0\n\
00945 byte MODIFY=0\n\
00946 byte DELETE=2\n\
00947 \n\
00948 Header header # header for time/frame information\n\
00949 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n\
00950 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n\
00951 int32 type # Type of object\n\
00952 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object\n\
00953 geometry_msgs/Pose pose # Pose of the object\n\
00954 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n\
00955 std_msgs/ColorRGBA color # Color [0.0-1.0]\n\
00956 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\
00957 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n\
00958 \n\
00959 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00960 geometry_msgs/Point[] points\n\
00961 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
00962 #number of colors must either be 0 or equal to the number of points\n\
00963 #NOTE: alpha is not yet used\n\
00964 std_msgs/ColorRGBA[] colors\n\
00965 \n\
00966 # NOTE: only used for text markers\n\
00967 string text\n\
00968 \n\
00969 # NOTE: only used for MESH_RESOURCE markers\n\
00970 string mesh_resource\n\
00971 bool mesh_use_embedded_materials\n\
00972 \n\
00973 ================================================================================\n\
00974 MSG: geometry_msgs/Vector3\n\
00975 # This represents a vector in free space. \n\
00976 \n\
00977 float64 x\n\
00978 float64 y\n\
00979 float64 z\n\
00980 ================================================================================\n\
00981 MSG: std_msgs/ColorRGBA\n\
00982 float32 r\n\
00983 float32 g\n\
00984 float32 b\n\
00985 float32 a\n\
00986 \n\
00987 ";
00988 }
00989
00990 static const char* value(const ::articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> &) { return value(); }
00991 };
00992
00993 }
00994 }
00995
00996
00997 namespace ros
00998 {
00999 namespace message_traits
01000 {
01001 template<class ContainerAllocator>
01002 struct MD5Sum< ::articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> > {
01003 static const char* value()
01004 {
01005 return "929d83624d0744de900991740e4bff8e";
01006 }
01007
01008 static const char* value(const ::articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> &) { return value(); }
01009 static const uint64_t static_value1 = 0x929d83624d0744deULL;
01010 static const uint64_t static_value2 = 0x900991740e4bff8eULL;
01011 };
01012
01013 template<class ContainerAllocator>
01014 struct DataType< ::articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> > {
01015 static const char* value()
01016 {
01017 return "articulation_msgs/ArticulatedObjectSrvResponse";
01018 }
01019
01020 static const char* value(const ::articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> &) { return value(); }
01021 };
01022
01023 template<class ContainerAllocator>
01024 struct Definition< ::articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> > {
01025 static const char* value()
01026 {
01027 return "articulation_msgs/ArticulatedObjectMsg object\n\
01028 \n\
01029 \n\
01030 \n\
01031 \n\
01032 \n\
01033 \n\
01034 ================================================================================\n\
01035 MSG: articulation_msgs/ArticulatedObjectMsg\n\
01036 Header header\n\
01037 \n\
01038 articulation_msgs/TrackMsg[] parts # observed trajectories for each object part \n\
01039 articulation_msgs/ParamMsg[] params # global parameters\n\
01040 articulation_msgs/ModelMsg[] models # models, describing relationships between parts\n\
01041 visualization_msgs/MarkerArray markers # marker visualization of models/object \n\
01042 ================================================================================\n\
01043 MSG: std_msgs/Header\n\
01044 # Standard metadata for higher-level stamped data types.\n\
01045 # This is generally used to communicate timestamped data \n\
01046 # in a particular coordinate frame.\n\
01047 # \n\
01048 # sequence ID: consecutively increasing ID \n\
01049 uint32 seq\n\
01050 #Two-integer timestamp that is expressed as:\n\
01051 # * stamp.secs: seconds (stamp_secs) since epoch\n\
01052 # * stamp.nsecs: nanoseconds since stamp_secs\n\
01053 # time-handling sugar is provided by the client library\n\
01054 time stamp\n\
01055 #Frame this data is associated with\n\
01056 # 0: no frame\n\
01057 # 1: global frame\n\
01058 string frame_id\n\
01059 \n\
01060 ================================================================================\n\
01061 MSG: articulation_msgs/TrackMsg\n\
01062 # Single kinematic trajectory\n\
01063 #\n\
01064 # This message contains a kinematic trajectory. The trajectory is specified\n\
01065 # as a vector of 6D poses. An additional flag, track_type, indicates whether\n\
01066 # the track is valid, and whether it includes orientation. The track id\n\
01067 # can be used for automatic coloring in the RVIZ track plugin, and can be \n\
01068 # freely chosen by the client. \n\
01069 #\n\
01070 # A model is fitting only from the trajectory stored in the pose[]-vector. \n\
01071 # Additional information may be associated to each pose using the channels\n\
01072 # vector, with arbitrary # fields (e.g., to include applied/measured forces). \n\
01073 #\n\
01074 # After model evaluation,\n\
01075 # also the associated configurations of the object are stored in the channels,\n\
01076 # named \"q[0]\"..\"q[DOF-1]\", where DOF is the number of degrees of freedom.\n\
01077 # Model evaluation also projects the poses in the pose vector onto the model,\n\
01078 # and stores these ideal poses in the vector pose_projected. Further, during model\n\
01079 # evaluation, a new set of (uniform) configurations over the valid configuration\n\
01080 # range is sampled, and the result is stored in pose_resampled.\n\
01081 # The vector pose_flags contains additional display flags for the poses in the\n\
01082 # pose vector, for example, whether a pose is visible and/or\n\
01083 # the end of a trajectory segment. At the moment, this is only used by the\n\
01084 # prior_model_learner.\n\
01085 #\n\
01086 \n\
01087 Header header # Timestamp and frame\n\
01088 int32 id # used-specified track id\n\
01089 \n\
01090 geometry_msgs/Pose[] pose # sequence of poses, defining the observed trajectory\n\
01091 geometry_msgs/Pose[] pose_projected # sequence of poses, projected to the model \n\
01092 # (after model evaluation)\n\
01093 geometry_msgs/Pose[] pose_resampled # sequence of poses, re-sampled from the model in\n\
01094 # the valid configuration range\n\
01095 uint32[] pose_flags # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT\n\
01096 \n\
01097 uint32 POSE_VISIBLE=1\n\
01098 uint32 POSE_END_OF_SEGMENT=2\n\
01099 \n\
01100 # Each channel should have the same number of elements as pose array, \n\
01101 # and the data in each channel should correspond 1:1 with each pose\n\
01102 # possible channels: \"width\", \"height\", \"rgb\", ...\n\
01103 sensor_msgs/ChannelFloat32[] channels \n\
01104 \n\
01105 \n\
01106 \n\
01107 ================================================================================\n\
01108 MSG: geometry_msgs/Pose\n\
01109 # A representation of pose in free space, composed of postion and orientation. \n\
01110 Point position\n\
01111 Quaternion orientation\n\
01112 \n\
01113 ================================================================================\n\
01114 MSG: geometry_msgs/Point\n\
01115 # This contains the position of a point in free space\n\
01116 float64 x\n\
01117 float64 y\n\
01118 float64 z\n\
01119 \n\
01120 ================================================================================\n\
01121 MSG: geometry_msgs/Quaternion\n\
01122 # This represents an orientation in free space in quaternion form.\n\
01123 \n\
01124 float64 x\n\
01125 float64 y\n\
01126 float64 z\n\
01127 float64 w\n\
01128 \n\
01129 ================================================================================\n\
01130 MSG: sensor_msgs/ChannelFloat32\n\
01131 # This message is used by the PointCloud message to hold optional data\n\
01132 # associated with each point in the cloud. The length of the values\n\
01133 # array should be the same as the length of the points array in the\n\
01134 # PointCloud, and each value should be associated with the corresponding\n\
01135 # point.\n\
01136 \n\
01137 # Channel names in existing practice include:\n\
01138 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
01139 # This is opposite to usual conventions but remains for\n\
01140 # historical reasons. The newer PointCloud2 message has no\n\
01141 # such problem.\n\
01142 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
01143 # (R,G,B) values packed into the least significant 24 bits,\n\
01144 # in order.\n\
01145 # \"intensity\" - laser or pixel intensity.\n\
01146 # \"distance\"\n\
01147 \n\
01148 # The channel name should give semantics of the channel (e.g.\n\
01149 # \"intensity\" instead of \"value\").\n\
01150 string name\n\
01151 \n\
01152 # The values array should be 1-1 with the elements of the associated\n\
01153 # PointCloud.\n\
01154 float32[] values\n\
01155 \n\
01156 ================================================================================\n\
01157 MSG: articulation_msgs/ParamMsg\n\
01158 # Single parameter passed to or from model fitting\n\
01159 #\n\
01160 # This mechanism allows to flexibly pass parameters to \n\
01161 # model fitting (and vice versa). Note that these parameters \n\
01162 # are model-specific: A client may supply additional\n\
01163 # parameters to the model estimator, and, similarly, a estimator\n\
01164 # may add the estimated model parameters to the model message.\n\
01165 # When the model is then evaluated, for example to make predictions\n\
01166 # or to compute the likelihood, the model class can then use\n\
01167 # these parameters.\n\
01168 #\n\
01169 # A parameter has a name, a value, and a type. The type globally\n\
01170 # indicates whether it is a prior parameter (prior to model fitting),\n\
01171 # or a model parameter (found during model fitting, using a maximum-\n\
01172 # likelihood estimator), or a cached evaluation (e.g., the likelihood\n\
01173 # or the BIC are a typical \"side\"-product of model estimation, and\n\
01174 # can therefore already be cached).\n\
01175 #\n\
01176 # For a list of currently used parameters, see the documentation at\n\
01177 # http://www.ros.org/wiki/articulation_models\n\
01178 #\n\
01179 \n\
01180 uint8 PRIOR=0 # indicates a prior model parameter \n\
01181 # (e.g., \"sigma_position\")\n\
01182 uint8 PARAM=1 # indicates a estimated model parameter \n\
01183 # (e.g., \"rot_radius\", the estimated radius)\n\
01184 uint8 EVAL=2 # indicates a cached evaluation of the model, given \n\
01185 # the current trajectory\n\
01186 # (e.g., \"loglikelihood\", the log likelihood of the\n\
01187 # data, given the model and its parameters)\n\
01188 \n\
01189 string name # name of the parameter\n\
01190 float64 value # value of the parameter\n\
01191 uint8 type # type of the parameter (PRIOR, PARAM, EVAL)\n\
01192 \n\
01193 \n\
01194 ================================================================================\n\
01195 MSG: articulation_msgs/ModelMsg\n\
01196 # Single kinematic model\n\
01197 #\n\
01198 # A kinematic model is defined by its model class name, and a set of parameters. \n\
01199 # The client may additionally specify a model id, that can be used to colorize the\n\
01200 # model when visualized using the RVIZ model display.\n\
01201 # \n\
01202 # For a list of currently implemented models, see the documetation at\n\
01203 # http://www.ros.org/wiki/articulation_models\n\
01204 #\n\
01205 #\n\
01206 \n\
01207 Header header # frame and timestamp\n\
01208 \n\
01209 int32 id # user specified model id\n\
01210 string name # name of the model family (e.g. \"rotational\",\n\
01211 # \"prismatic\", \"pca-gp\", \"rigid\")\n\
01212 articulation_msgs/ParamMsg[] params # model parameters\n\
01213 articulation_msgs/TrackMsg track # trajectory from which the model is estimated, or\n\
01214 # that is evaluated using the model\n\
01215 \n\
01216 ================================================================================\n\
01217 MSG: visualization_msgs/MarkerArray\n\
01218 Marker[] markers\n\
01219 \n\
01220 ================================================================================\n\
01221 MSG: visualization_msgs/Marker\n\
01222 # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz\n\
01223 \n\
01224 byte ARROW=0\n\
01225 byte CUBE=1\n\
01226 byte SPHERE=2\n\
01227 byte CYLINDER=3\n\
01228 byte LINE_STRIP=4\n\
01229 byte LINE_LIST=5\n\
01230 byte CUBE_LIST=6\n\
01231 byte SPHERE_LIST=7\n\
01232 byte POINTS=8\n\
01233 byte TEXT_VIEW_FACING=9\n\
01234 byte MESH_RESOURCE=10\n\
01235 byte TRIANGLE_LIST=11\n\
01236 \n\
01237 byte ADD=0\n\
01238 byte MODIFY=0\n\
01239 byte DELETE=2\n\
01240 \n\
01241 Header header # header for time/frame information\n\
01242 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\n\
01243 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later\n\
01244 int32 type # Type of object\n\
01245 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object\n\
01246 geometry_msgs/Pose pose # Pose of the object\n\
01247 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\n\
01248 std_msgs/ColorRGBA color # Color [0.0-1.0]\n\
01249 duration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\
01250 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n\
01251 \n\
01252 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
01253 geometry_msgs/Point[] points\n\
01254 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n\
01255 #number of colors must either be 0 or equal to the number of points\n\
01256 #NOTE: alpha is not yet used\n\
01257 std_msgs/ColorRGBA[] colors\n\
01258 \n\
01259 # NOTE: only used for text markers\n\
01260 string text\n\
01261 \n\
01262 # NOTE: only used for MESH_RESOURCE markers\n\
01263 string mesh_resource\n\
01264 bool mesh_use_embedded_materials\n\
01265 \n\
01266 ================================================================================\n\
01267 MSG: geometry_msgs/Vector3\n\
01268 # This represents a vector in free space. \n\
01269 \n\
01270 float64 x\n\
01271 float64 y\n\
01272 float64 z\n\
01273 ================================================================================\n\
01274 MSG: std_msgs/ColorRGBA\n\
01275 float32 r\n\
01276 float32 g\n\
01277 float32 b\n\
01278 float32 a\n\
01279 \n\
01280 ";
01281 }
01282
01283 static const char* value(const ::articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> &) { return value(); }
01284 };
01285
01286 }
01287 }
01288
01289 namespace ros
01290 {
01291 namespace serialization
01292 {
01293
01294 template<class ContainerAllocator> struct Serializer< ::articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> >
01295 {
01296 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01297 {
01298 stream.next(m.object);
01299 }
01300
01301 ROS_DECLARE_ALLINONE_SERIALIZER;
01302 };
01303 }
01304 }
01305
01306
01307 namespace ros
01308 {
01309 namespace serialization
01310 {
01311
01312 template<class ContainerAllocator> struct Serializer< ::articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> >
01313 {
01314 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01315 {
01316 stream.next(m.object);
01317 }
01318
01319 ROS_DECLARE_ALLINONE_SERIALIZER;
01320 };
01321 }
01322 }
01323
01324 namespace ros
01325 {
01326 namespace service_traits
01327 {
01328 template<>
01329 struct MD5Sum<articulation_msgs::ArticulatedObjectSrv> {
01330 static const char* value()
01331 {
01332 return "d13520b58d3ca45a23cc7f92f8661f22";
01333 }
01334
01335 static const char* value(const articulation_msgs::ArticulatedObjectSrv&) { return value(); }
01336 };
01337
01338 template<>
01339 struct DataType<articulation_msgs::ArticulatedObjectSrv> {
01340 static const char* value()
01341 {
01342 return "articulation_msgs/ArticulatedObjectSrv";
01343 }
01344
01345 static const char* value(const articulation_msgs::ArticulatedObjectSrv&) { return value(); }
01346 };
01347
01348 template<class ContainerAllocator>
01349 struct MD5Sum<articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> > {
01350 static const char* value()
01351 {
01352 return "d13520b58d3ca45a23cc7f92f8661f22";
01353 }
01354
01355 static const char* value(const articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> &) { return value(); }
01356 };
01357
01358 template<class ContainerAllocator>
01359 struct DataType<articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> > {
01360 static const char* value()
01361 {
01362 return "articulation_msgs/ArticulatedObjectSrv";
01363 }
01364
01365 static const char* value(const articulation_msgs::ArticulatedObjectSrvRequest_<ContainerAllocator> &) { return value(); }
01366 };
01367
01368 template<class ContainerAllocator>
01369 struct MD5Sum<articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> > {
01370 static const char* value()
01371 {
01372 return "d13520b58d3ca45a23cc7f92f8661f22";
01373 }
01374
01375 static const char* value(const articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> &) { return value(); }
01376 };
01377
01378 template<class ContainerAllocator>
01379 struct DataType<articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> > {
01380 static const char* value()
01381 {
01382 return "articulation_msgs/ArticulatedObjectSrv";
01383 }
01384
01385 static const char* value(const articulation_msgs::ArticulatedObjectSrvResponse_<ContainerAllocator> &) { return value(); }
01386 };
01387
01388 }
01389 }
01390
01391 #endif // ARTICULATION_MSGS_SERVICE_ARTICULATEDOBJECTSRV_H
01392