00001
00002 #ifndef CHOMP_MOTION_PLANNER_SERVICE_GETSTATECOST_H
00003 #define CHOMP_MOTION_PLANNER_SERVICE_GETSTATECOST_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 "motion_planning_msgs/RobotState.h"
00016
00017
00018
00019 namespace chomp_motion_planner
00020 {
00021 template <class ContainerAllocator>
00022 struct GetStateCostRequest_ : public ros::Message
00023 {
00024 typedef GetStateCostRequest_<ContainerAllocator> Type;
00025
00026 GetStateCostRequest_()
00027 : link_names()
00028 , robot_state()
00029 {
00030 }
00031
00032 GetStateCostRequest_(const ContainerAllocator& _alloc)
00033 : link_names(_alloc)
00034 , robot_state(_alloc)
00035 {
00036 }
00037
00038 typedef std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > _link_names_type;
00039 std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > link_names;
00040
00041 typedef ::motion_planning_msgs::RobotState_<ContainerAllocator> _robot_state_type;
00042 ::motion_planning_msgs::RobotState_<ContainerAllocator> robot_state;
00043
00044
00045 ROS_DEPRECATED uint32_t get_link_names_size() const { return (uint32_t)link_names.size(); }
00046 ROS_DEPRECATED void set_link_names_size(uint32_t size) { link_names.resize((size_t)size); }
00047 ROS_DEPRECATED void get_link_names_vec(std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) const { vec = this->link_names; }
00048 ROS_DEPRECATED void set_link_names_vec(const std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > & vec) { this->link_names = vec; }
00049 private:
00050 static const char* __s_getDataType_() { return "chomp_motion_planner/GetStateCostRequest"; }
00051 public:
00052 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00053
00054 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00055
00056 private:
00057 static const char* __s_getMD5Sum_() { return "8eb8c1ec9dda8058aa5e5d82c1d8cda6"; }
00058 public:
00059 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00060
00061 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00062
00063 private:
00064 static const char* __s_getServerMD5Sum_() { return "e5ac7b8628485266624f522d76c812fd"; }
00065 public:
00066 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00067
00068 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00069
00070 private:
00071 static const char* __s_getMessageDefinition_() { return "\n\
00072 \n\
00073 \n\
00074 string[] link_names\n\
00075 \n\
00076 motion_planning_msgs/RobotState robot_state\n\
00077 \n\
00078 ================================================================================\n\
00079 MSG: motion_planning_msgs/RobotState\n\
00080 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00081 sensor_msgs/JointState joint_state\n\
00082 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00083 ================================================================================\n\
00084 MSG: sensor_msgs/JointState\n\
00085 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00086 #\n\
00087 # The state of each joint (revolute or prismatic) is defined by:\n\
00088 # * the position of the joint (rad or m),\n\
00089 # * the velocity of the joint (rad/s or m/s) and \n\
00090 # * the effort that is applied in the joint (Nm or N).\n\
00091 #\n\
00092 # Each joint is uniquely identified by its name\n\
00093 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00094 # in one message have to be recorded at the same time.\n\
00095 #\n\
00096 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00097 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00098 # effort associated with them, you can leave the effort array empty. \n\
00099 #\n\
00100 # All arrays in this message should have the same size, or be empty.\n\
00101 # This is the only way to uniquely associate the joint name with the correct\n\
00102 # states.\n\
00103 \n\
00104 \n\
00105 Header header\n\
00106 \n\
00107 string[] name\n\
00108 float64[] position\n\
00109 float64[] velocity\n\
00110 float64[] effort\n\
00111 \n\
00112 ================================================================================\n\
00113 MSG: std_msgs/Header\n\
00114 # Standard metadata for higher-level stamped data types.\n\
00115 # This is generally used to communicate timestamped data \n\
00116 # in a particular coordinate frame.\n\
00117 # \n\
00118 # sequence ID: consecutively increasing ID \n\
00119 uint32 seq\n\
00120 #Two-integer timestamp that is expressed as:\n\
00121 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00122 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00123 # time-handling sugar is provided by the client library\n\
00124 time stamp\n\
00125 #Frame this data is associated with\n\
00126 # 0: no frame\n\
00127 # 1: global frame\n\
00128 string frame_id\n\
00129 \n\
00130 ================================================================================\n\
00131 MSG: motion_planning_msgs/MultiDOFJointState\n\
00132 #A representation of a multi-dof joint state\n\
00133 time stamp\n\
00134 string[] joint_names\n\
00135 string[] frame_ids\n\
00136 string[] child_frame_ids\n\
00137 geometry_msgs/Pose[] poses\n\
00138 \n\
00139 ================================================================================\n\
00140 MSG: geometry_msgs/Pose\n\
00141 # A representation of pose in free space, composed of postion and orientation. \n\
00142 Point position\n\
00143 Quaternion orientation\n\
00144 \n\
00145 ================================================================================\n\
00146 MSG: geometry_msgs/Point\n\
00147 # This contains the position of a point in free space\n\
00148 float64 x\n\
00149 float64 y\n\
00150 float64 z\n\
00151 \n\
00152 ================================================================================\n\
00153 MSG: geometry_msgs/Quaternion\n\
00154 # This represents an orientation in free space in quaternion form.\n\
00155 \n\
00156 float64 x\n\
00157 float64 y\n\
00158 float64 z\n\
00159 float64 w\n\
00160 \n\
00161 "; }
00162 public:
00163 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00164
00165 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00166
00167 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00168 {
00169 ros::serialization::OStream stream(write_ptr, 1000000000);
00170 ros::serialization::serialize(stream, link_names);
00171 ros::serialization::serialize(stream, robot_state);
00172 return stream.getData();
00173 }
00174
00175 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00176 {
00177 ros::serialization::IStream stream(read_ptr, 1000000000);
00178 ros::serialization::deserialize(stream, link_names);
00179 ros::serialization::deserialize(stream, robot_state);
00180 return stream.getData();
00181 }
00182
00183 ROS_DEPRECATED virtual uint32_t serializationLength() const
00184 {
00185 uint32_t size = 0;
00186 size += ros::serialization::serializationLength(link_names);
00187 size += ros::serialization::serializationLength(robot_state);
00188 return size;
00189 }
00190
00191 typedef boost::shared_ptr< ::chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> > Ptr;
00192 typedef boost::shared_ptr< ::chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> const> ConstPtr;
00193 };
00194 typedef ::chomp_motion_planner::GetStateCostRequest_<std::allocator<void> > GetStateCostRequest;
00195
00196 typedef boost::shared_ptr< ::chomp_motion_planner::GetStateCostRequest> GetStateCostRequestPtr;
00197 typedef boost::shared_ptr< ::chomp_motion_planner::GetStateCostRequest const> GetStateCostRequestConstPtr;
00198
00199
00200 template <class ContainerAllocator>
00201 struct GetStateCostResponse_ : public ros::Message
00202 {
00203 typedef GetStateCostResponse_<ContainerAllocator> Type;
00204
00205 GetStateCostResponse_()
00206 : valid(false)
00207 , costs()
00208 {
00209 }
00210
00211 GetStateCostResponse_(const ContainerAllocator& _alloc)
00212 : valid(false)
00213 , costs(_alloc)
00214 {
00215 }
00216
00217 typedef uint8_t _valid_type;
00218 uint8_t valid;
00219
00220 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _costs_type;
00221 std::vector<double, typename ContainerAllocator::template rebind<double>::other > costs;
00222
00223
00224 ROS_DEPRECATED uint32_t get_costs_size() const { return (uint32_t)costs.size(); }
00225 ROS_DEPRECATED void set_costs_size(uint32_t size) { costs.resize((size_t)size); }
00226 ROS_DEPRECATED void get_costs_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->costs; }
00227 ROS_DEPRECATED void set_costs_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->costs = vec; }
00228 private:
00229 static const char* __s_getDataType_() { return "chomp_motion_planner/GetStateCostResponse"; }
00230 public:
00231 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00232
00233 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00234
00235 private:
00236 static const char* __s_getMD5Sum_() { return "125a150f1be009a543837c8732501336"; }
00237 public:
00238 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00239
00240 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00241
00242 private:
00243 static const char* __s_getServerMD5Sum_() { return "e5ac7b8628485266624f522d76c812fd"; }
00244 public:
00245 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00246
00247 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00248
00249 private:
00250 static const char* __s_getMessageDefinition_() { return "\n\
00251 bool valid\n\
00252 \n\
00253 float64[] costs\n\
00254 \n\
00255 \n\
00256 "; }
00257 public:
00258 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00259
00260 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00261
00262 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00263 {
00264 ros::serialization::OStream stream(write_ptr, 1000000000);
00265 ros::serialization::serialize(stream, valid);
00266 ros::serialization::serialize(stream, costs);
00267 return stream.getData();
00268 }
00269
00270 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00271 {
00272 ros::serialization::IStream stream(read_ptr, 1000000000);
00273 ros::serialization::deserialize(stream, valid);
00274 ros::serialization::deserialize(stream, costs);
00275 return stream.getData();
00276 }
00277
00278 ROS_DEPRECATED virtual uint32_t serializationLength() const
00279 {
00280 uint32_t size = 0;
00281 size += ros::serialization::serializationLength(valid);
00282 size += ros::serialization::serializationLength(costs);
00283 return size;
00284 }
00285
00286 typedef boost::shared_ptr< ::chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> > Ptr;
00287 typedef boost::shared_ptr< ::chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> const> ConstPtr;
00288 };
00289 typedef ::chomp_motion_planner::GetStateCostResponse_<std::allocator<void> > GetStateCostResponse;
00290
00291 typedef boost::shared_ptr< ::chomp_motion_planner::GetStateCostResponse> GetStateCostResponsePtr;
00292 typedef boost::shared_ptr< ::chomp_motion_planner::GetStateCostResponse const> GetStateCostResponseConstPtr;
00293
00294 struct GetStateCost
00295 {
00296
00297 typedef GetStateCostRequest Request;
00298 typedef GetStateCostResponse Response;
00299 Request request;
00300 Response response;
00301
00302 typedef Request RequestType;
00303 typedef Response ResponseType;
00304 };
00305 }
00306
00307 namespace ros
00308 {
00309 namespace message_traits
00310 {
00311 template<class ContainerAllocator>
00312 struct MD5Sum< ::chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> > {
00313 static const char* value()
00314 {
00315 return "8eb8c1ec9dda8058aa5e5d82c1d8cda6";
00316 }
00317
00318 static const char* value(const ::chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> &) { return value(); }
00319 static const uint64_t static_value1 = 0x8eb8c1ec9dda8058ULL;
00320 static const uint64_t static_value2 = 0xaa5e5d82c1d8cda6ULL;
00321 };
00322
00323 template<class ContainerAllocator>
00324 struct DataType< ::chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> > {
00325 static const char* value()
00326 {
00327 return "chomp_motion_planner/GetStateCostRequest";
00328 }
00329
00330 static const char* value(const ::chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> &) { return value(); }
00331 };
00332
00333 template<class ContainerAllocator>
00334 struct Definition< ::chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> > {
00335 static const char* value()
00336 {
00337 return "\n\
00338 \n\
00339 \n\
00340 string[] link_names\n\
00341 \n\
00342 motion_planning_msgs/RobotState robot_state\n\
00343 \n\
00344 ================================================================================\n\
00345 MSG: motion_planning_msgs/RobotState\n\
00346 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00347 sensor_msgs/JointState joint_state\n\
00348 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00349 ================================================================================\n\
00350 MSG: sensor_msgs/JointState\n\
00351 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00352 #\n\
00353 # The state of each joint (revolute or prismatic) is defined by:\n\
00354 # * the position of the joint (rad or m),\n\
00355 # * the velocity of the joint (rad/s or m/s) and \n\
00356 # * the effort that is applied in the joint (Nm or N).\n\
00357 #\n\
00358 # Each joint is uniquely identified by its name\n\
00359 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00360 # in one message have to be recorded at the same time.\n\
00361 #\n\
00362 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00363 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00364 # effort associated with them, you can leave the effort array empty. \n\
00365 #\n\
00366 # All arrays in this message should have the same size, or be empty.\n\
00367 # This is the only way to uniquely associate the joint name with the correct\n\
00368 # states.\n\
00369 \n\
00370 \n\
00371 Header header\n\
00372 \n\
00373 string[] name\n\
00374 float64[] position\n\
00375 float64[] velocity\n\
00376 float64[] effort\n\
00377 \n\
00378 ================================================================================\n\
00379 MSG: std_msgs/Header\n\
00380 # Standard metadata for higher-level stamped data types.\n\
00381 # This is generally used to communicate timestamped data \n\
00382 # in a particular coordinate frame.\n\
00383 # \n\
00384 # sequence ID: consecutively increasing ID \n\
00385 uint32 seq\n\
00386 #Two-integer timestamp that is expressed as:\n\
00387 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00388 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00389 # time-handling sugar is provided by the client library\n\
00390 time stamp\n\
00391 #Frame this data is associated with\n\
00392 # 0: no frame\n\
00393 # 1: global frame\n\
00394 string frame_id\n\
00395 \n\
00396 ================================================================================\n\
00397 MSG: motion_planning_msgs/MultiDOFJointState\n\
00398 #A representation of a multi-dof joint state\n\
00399 time stamp\n\
00400 string[] joint_names\n\
00401 string[] frame_ids\n\
00402 string[] child_frame_ids\n\
00403 geometry_msgs/Pose[] poses\n\
00404 \n\
00405 ================================================================================\n\
00406 MSG: geometry_msgs/Pose\n\
00407 # A representation of pose in free space, composed of postion and orientation. \n\
00408 Point position\n\
00409 Quaternion orientation\n\
00410 \n\
00411 ================================================================================\n\
00412 MSG: geometry_msgs/Point\n\
00413 # This contains the position of a point in free space\n\
00414 float64 x\n\
00415 float64 y\n\
00416 float64 z\n\
00417 \n\
00418 ================================================================================\n\
00419 MSG: geometry_msgs/Quaternion\n\
00420 # This represents an orientation in free space in quaternion form.\n\
00421 \n\
00422 float64 x\n\
00423 float64 y\n\
00424 float64 z\n\
00425 float64 w\n\
00426 \n\
00427 ";
00428 }
00429
00430 static const char* value(const ::chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> &) { return value(); }
00431 };
00432
00433 }
00434 }
00435
00436
00437 namespace ros
00438 {
00439 namespace message_traits
00440 {
00441 template<class ContainerAllocator>
00442 struct MD5Sum< ::chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> > {
00443 static const char* value()
00444 {
00445 return "125a150f1be009a543837c8732501336";
00446 }
00447
00448 static const char* value(const ::chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> &) { return value(); }
00449 static const uint64_t static_value1 = 0x125a150f1be009a5ULL;
00450 static const uint64_t static_value2 = 0x43837c8732501336ULL;
00451 };
00452
00453 template<class ContainerAllocator>
00454 struct DataType< ::chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> > {
00455 static const char* value()
00456 {
00457 return "chomp_motion_planner/GetStateCostResponse";
00458 }
00459
00460 static const char* value(const ::chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> &) { return value(); }
00461 };
00462
00463 template<class ContainerAllocator>
00464 struct Definition< ::chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> > {
00465 static const char* value()
00466 {
00467 return "\n\
00468 bool valid\n\
00469 \n\
00470 float64[] costs\n\
00471 \n\
00472 \n\
00473 ";
00474 }
00475
00476 static const char* value(const ::chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> &) { return value(); }
00477 };
00478
00479 }
00480 }
00481
00482 namespace ros
00483 {
00484 namespace serialization
00485 {
00486
00487 template<class ContainerAllocator> struct Serializer< ::chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> >
00488 {
00489 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00490 {
00491 stream.next(m.link_names);
00492 stream.next(m.robot_state);
00493 }
00494
00495 ROS_DECLARE_ALLINONE_SERIALIZER;
00496 };
00497 }
00498 }
00499
00500
00501 namespace ros
00502 {
00503 namespace serialization
00504 {
00505
00506 template<class ContainerAllocator> struct Serializer< ::chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> >
00507 {
00508 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00509 {
00510 stream.next(m.valid);
00511 stream.next(m.costs);
00512 }
00513
00514 ROS_DECLARE_ALLINONE_SERIALIZER;
00515 };
00516 }
00517 }
00518
00519 namespace ros
00520 {
00521 namespace service_traits
00522 {
00523 template<>
00524 struct MD5Sum<chomp_motion_planner::GetStateCost> {
00525 static const char* value()
00526 {
00527 return "e5ac7b8628485266624f522d76c812fd";
00528 }
00529
00530 static const char* value(const chomp_motion_planner::GetStateCost&) { return value(); }
00531 };
00532
00533 template<>
00534 struct DataType<chomp_motion_planner::GetStateCost> {
00535 static const char* value()
00536 {
00537 return "chomp_motion_planner/GetStateCost";
00538 }
00539
00540 static const char* value(const chomp_motion_planner::GetStateCost&) { return value(); }
00541 };
00542
00543 template<class ContainerAllocator>
00544 struct MD5Sum<chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> > {
00545 static const char* value()
00546 {
00547 return "e5ac7b8628485266624f522d76c812fd";
00548 }
00549
00550 static const char* value(const chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> &) { return value(); }
00551 };
00552
00553 template<class ContainerAllocator>
00554 struct DataType<chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> > {
00555 static const char* value()
00556 {
00557 return "chomp_motion_planner/GetStateCost";
00558 }
00559
00560 static const char* value(const chomp_motion_planner::GetStateCostRequest_<ContainerAllocator> &) { return value(); }
00561 };
00562
00563 template<class ContainerAllocator>
00564 struct MD5Sum<chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> > {
00565 static const char* value()
00566 {
00567 return "e5ac7b8628485266624f522d76c812fd";
00568 }
00569
00570 static const char* value(const chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> &) { return value(); }
00571 };
00572
00573 template<class ContainerAllocator>
00574 struct DataType<chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> > {
00575 static const char* value()
00576 {
00577 return "chomp_motion_planner/GetStateCost";
00578 }
00579
00580 static const char* value(const chomp_motion_planner::GetStateCostResponse_<ContainerAllocator> &) { return value(); }
00581 };
00582
00583 }
00584 }
00585
00586 #endif // CHOMP_MOTION_PLANNER_SERVICE_GETSTATECOST_H
00587