00001
00002 #ifndef PLANNING_ENVIRONMENT_MSGS_SERVICE_GETGROUPINFO_H
00003 #define PLANNING_ENVIRONMENT_MSGS_SERVICE_GETGROUPINFO_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015
00016
00017 #include "motion_planning_msgs/ArmNavigationErrorCodes.h"
00018
00019 namespace planning_environment_msgs
00020 {
00021 template <class ContainerAllocator>
00022 struct GetGroupInfoRequest_ : public ros::Message
00023 {
00024 typedef GetGroupInfoRequest_<ContainerAllocator> Type;
00025
00026 GetGroupInfoRequest_()
00027 : group_name()
00028 {
00029 }
00030
00031 GetGroupInfoRequest_(const ContainerAllocator& _alloc)
00032 : group_name(_alloc)
00033 {
00034 }
00035
00036 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _group_name_type;
00037 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > group_name;
00038
00039
00040 private:
00041 static const char* __s_getDataType_() { return "planning_environment_msgs/GetGroupInfoRequest"; }
00042 public:
00043 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00044
00045 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00046
00047 private:
00048 static const char* __s_getMD5Sum_() { return "967d0b0c0d858ded8a6a69abbce0c981"; }
00049 public:
00050 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00051
00052 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00053
00054 private:
00055 static const char* __s_getServerMD5Sum_() { return "ea5e90e42fb70a06b53bacff792b6742"; }
00056 public:
00057 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00058
00059 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00060
00061 private:
00062 static const char* __s_getMessageDefinition_() { return "\n\
00063 \n\
00064 \n\
00065 \n\
00066 \n\
00067 \n\
00068 \n\
00069 string group_name\n\
00070 \n\
00071 \n\
00072 "; }
00073 public:
00074 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00075
00076 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00077
00078 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00079 {
00080 ros::serialization::OStream stream(write_ptr, 1000000000);
00081 ros::serialization::serialize(stream, group_name);
00082 return stream.getData();
00083 }
00084
00085 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00086 {
00087 ros::serialization::IStream stream(read_ptr, 1000000000);
00088 ros::serialization::deserialize(stream, group_name);
00089 return stream.getData();
00090 }
00091
00092 ROS_DEPRECATED virtual uint32_t serializationLength() const
00093 {
00094 uint32_t size = 0;
00095 size += ros::serialization::serializationLength(group_name);
00096 return size;
00097 }
00098
00099 typedef boost::shared_ptr< ::planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> > Ptr;
00100 typedef boost::shared_ptr< ::planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> const> ConstPtr;
00101 };
00102 typedef ::planning_environment_msgs::GetGroupInfoRequest_<std::allocator<void> > GetGroupInfoRequest;
00103
00104 typedef boost::shared_ptr< ::planning_environment_msgs::GetGroupInfoRequest> GetGroupInfoRequestPtr;
00105 typedef boost::shared_ptr< ::planning_environment_msgs::GetGroupInfoRequest const> GetGroupInfoRequestConstPtr;
00106
00107
00108 template <class ContainerAllocator>
00109 struct GetGroupInfoResponse_ : public ros::Message
00110 {
00111 typedef GetGroupInfoResponse_<ContainerAllocator> Type;
00112
00113 GetGroupInfoResponse_()
00114 : joint_names()
00115 , link_names()
00116 , error_code()
00117 {
00118 }
00119
00120 GetGroupInfoResponse_(const ContainerAllocator& _alloc)
00121 : joint_names(_alloc)
00122 , link_names(_alloc)
00123 , error_code(_alloc)
00124 {
00125 }
00126
00127 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 > _joint_names_type;
00128 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 > joint_names;
00129
00130 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;
00131 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;
00132
00133 typedef ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type;
00134 ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code;
00135
00136
00137 ROS_DEPRECATED uint32_t get_joint_names_size() const { return (uint32_t)joint_names.size(); }
00138 ROS_DEPRECATED void set_joint_names_size(uint32_t size) { joint_names.resize((size_t)size); }
00139 ROS_DEPRECATED void get_joint_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->joint_names; }
00140 ROS_DEPRECATED void set_joint_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->joint_names = vec; }
00141 ROS_DEPRECATED uint32_t get_link_names_size() const { return (uint32_t)link_names.size(); }
00142 ROS_DEPRECATED void set_link_names_size(uint32_t size) { link_names.resize((size_t)size); }
00143 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; }
00144 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; }
00145 private:
00146 static const char* __s_getDataType_() { return "planning_environment_msgs/GetGroupInfoResponse"; }
00147 public:
00148 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00149
00150 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00151
00152 private:
00153 static const char* __s_getMD5Sum_() { return "65f397a9c63c76b7f5a87fbdac0c50a1"; }
00154 public:
00155 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00156
00157 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00158
00159 private:
00160 static const char* __s_getServerMD5Sum_() { return "ea5e90e42fb70a06b53bacff792b6742"; }
00161 public:
00162 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00163
00164 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00165
00166 private:
00167 static const char* __s_getMessageDefinition_() { return "\n\
00168 \n\
00169 string[] joint_names\n\
00170 \n\
00171 \n\
00172 string[] link_names\n\
00173 \n\
00174 \n\
00175 \n\
00176 \n\
00177 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00178 \n\
00179 \n\
00180 ================================================================================\n\
00181 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00182 int32 val\n\
00183 \n\
00184 # overall behavior\n\
00185 int32 PLANNING_FAILED=-1\n\
00186 int32 SUCCESS=1\n\
00187 int32 TIMED_OUT=-2\n\
00188 \n\
00189 # start state errors\n\
00190 int32 START_STATE_IN_COLLISION=-3\n\
00191 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00192 \n\
00193 # goal errors\n\
00194 int32 GOAL_IN_COLLISION=-5\n\
00195 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00196 \n\
00197 # robot state\n\
00198 int32 INVALID_ROBOT_STATE=-7\n\
00199 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00200 \n\
00201 # planning request errors\n\
00202 int32 INVALID_PLANNER_ID=-9\n\
00203 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00204 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00205 int32 INVALID_GROUP_NAME=-12\n\
00206 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00207 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00208 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00209 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00210 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00211 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00212 \n\
00213 # state/trajectory monitor errors\n\
00214 int32 INVALID_TRAJECTORY=-19\n\
00215 int32 INVALID_INDEX=-20\n\
00216 int32 JOINT_LIMITS_VIOLATED=-21\n\
00217 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00218 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00219 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00220 int32 JOINTS_NOT_MOVING=-25\n\
00221 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00222 \n\
00223 # system errors\n\
00224 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00225 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00226 int32 ROBOT_STATE_STALE=-29\n\
00227 int32 SENSOR_INFO_STALE=-30\n\
00228 \n\
00229 # kinematics errors\n\
00230 int32 NO_IK_SOLUTION=-31\n\
00231 int32 INVALID_LINK_NAME=-32\n\
00232 int32 IK_LINK_IN_COLLISION=-33\n\
00233 int32 NO_FK_SOLUTION=-34\n\
00234 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00235 \n\
00236 # general errors\n\
00237 int32 INVALID_TIMEOUT=-36\n\
00238 \n\
00239 \n\
00240 "; }
00241 public:
00242 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00243
00244 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00245
00246 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00247 {
00248 ros::serialization::OStream stream(write_ptr, 1000000000);
00249 ros::serialization::serialize(stream, joint_names);
00250 ros::serialization::serialize(stream, link_names);
00251 ros::serialization::serialize(stream, error_code);
00252 return stream.getData();
00253 }
00254
00255 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00256 {
00257 ros::serialization::IStream stream(read_ptr, 1000000000);
00258 ros::serialization::deserialize(stream, joint_names);
00259 ros::serialization::deserialize(stream, link_names);
00260 ros::serialization::deserialize(stream, error_code);
00261 return stream.getData();
00262 }
00263
00264 ROS_DEPRECATED virtual uint32_t serializationLength() const
00265 {
00266 uint32_t size = 0;
00267 size += ros::serialization::serializationLength(joint_names);
00268 size += ros::serialization::serializationLength(link_names);
00269 size += ros::serialization::serializationLength(error_code);
00270 return size;
00271 }
00272
00273 typedef boost::shared_ptr< ::planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> > Ptr;
00274 typedef boost::shared_ptr< ::planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> const> ConstPtr;
00275 };
00276 typedef ::planning_environment_msgs::GetGroupInfoResponse_<std::allocator<void> > GetGroupInfoResponse;
00277
00278 typedef boost::shared_ptr< ::planning_environment_msgs::GetGroupInfoResponse> GetGroupInfoResponsePtr;
00279 typedef boost::shared_ptr< ::planning_environment_msgs::GetGroupInfoResponse const> GetGroupInfoResponseConstPtr;
00280
00281 struct GetGroupInfo
00282 {
00283
00284 typedef GetGroupInfoRequest Request;
00285 typedef GetGroupInfoResponse Response;
00286 Request request;
00287 Response response;
00288
00289 typedef Request RequestType;
00290 typedef Response ResponseType;
00291 };
00292 }
00293
00294 namespace ros
00295 {
00296 namespace message_traits
00297 {
00298 template<class ContainerAllocator>
00299 struct MD5Sum< ::planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> > {
00300 static const char* value()
00301 {
00302 return "967d0b0c0d858ded8a6a69abbce0c981";
00303 }
00304
00305 static const char* value(const ::planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> &) { return value(); }
00306 static const uint64_t static_value1 = 0x967d0b0c0d858dedULL;
00307 static const uint64_t static_value2 = 0x8a6a69abbce0c981ULL;
00308 };
00309
00310 template<class ContainerAllocator>
00311 struct DataType< ::planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> > {
00312 static const char* value()
00313 {
00314 return "planning_environment_msgs/GetGroupInfoRequest";
00315 }
00316
00317 static const char* value(const ::planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> &) { return value(); }
00318 };
00319
00320 template<class ContainerAllocator>
00321 struct Definition< ::planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> > {
00322 static const char* value()
00323 {
00324 return "\n\
00325 \n\
00326 \n\
00327 \n\
00328 \n\
00329 \n\
00330 \n\
00331 string group_name\n\
00332 \n\
00333 \n\
00334 ";
00335 }
00336
00337 static const char* value(const ::planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> &) { return value(); }
00338 };
00339
00340 }
00341 }
00342
00343
00344 namespace ros
00345 {
00346 namespace message_traits
00347 {
00348 template<class ContainerAllocator>
00349 struct MD5Sum< ::planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> > {
00350 static const char* value()
00351 {
00352 return "65f397a9c63c76b7f5a87fbdac0c50a1";
00353 }
00354
00355 static const char* value(const ::planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> &) { return value(); }
00356 static const uint64_t static_value1 = 0x65f397a9c63c76b7ULL;
00357 static const uint64_t static_value2 = 0xf5a87fbdac0c50a1ULL;
00358 };
00359
00360 template<class ContainerAllocator>
00361 struct DataType< ::planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> > {
00362 static const char* value()
00363 {
00364 return "planning_environment_msgs/GetGroupInfoResponse";
00365 }
00366
00367 static const char* value(const ::planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> &) { return value(); }
00368 };
00369
00370 template<class ContainerAllocator>
00371 struct Definition< ::planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> > {
00372 static const char* value()
00373 {
00374 return "\n\
00375 \n\
00376 string[] joint_names\n\
00377 \n\
00378 \n\
00379 string[] link_names\n\
00380 \n\
00381 \n\
00382 \n\
00383 \n\
00384 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00385 \n\
00386 \n\
00387 ================================================================================\n\
00388 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00389 int32 val\n\
00390 \n\
00391 # overall behavior\n\
00392 int32 PLANNING_FAILED=-1\n\
00393 int32 SUCCESS=1\n\
00394 int32 TIMED_OUT=-2\n\
00395 \n\
00396 # start state errors\n\
00397 int32 START_STATE_IN_COLLISION=-3\n\
00398 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00399 \n\
00400 # goal errors\n\
00401 int32 GOAL_IN_COLLISION=-5\n\
00402 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00403 \n\
00404 # robot state\n\
00405 int32 INVALID_ROBOT_STATE=-7\n\
00406 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00407 \n\
00408 # planning request errors\n\
00409 int32 INVALID_PLANNER_ID=-9\n\
00410 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00411 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00412 int32 INVALID_GROUP_NAME=-12\n\
00413 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00414 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00415 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00416 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00417 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00418 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00419 \n\
00420 # state/trajectory monitor errors\n\
00421 int32 INVALID_TRAJECTORY=-19\n\
00422 int32 INVALID_INDEX=-20\n\
00423 int32 JOINT_LIMITS_VIOLATED=-21\n\
00424 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00425 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00426 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00427 int32 JOINTS_NOT_MOVING=-25\n\
00428 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00429 \n\
00430 # system errors\n\
00431 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00432 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00433 int32 ROBOT_STATE_STALE=-29\n\
00434 int32 SENSOR_INFO_STALE=-30\n\
00435 \n\
00436 # kinematics errors\n\
00437 int32 NO_IK_SOLUTION=-31\n\
00438 int32 INVALID_LINK_NAME=-32\n\
00439 int32 IK_LINK_IN_COLLISION=-33\n\
00440 int32 NO_FK_SOLUTION=-34\n\
00441 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00442 \n\
00443 # general errors\n\
00444 int32 INVALID_TIMEOUT=-36\n\
00445 \n\
00446 \n\
00447 ";
00448 }
00449
00450 static const char* value(const ::planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> &) { return value(); }
00451 };
00452
00453 }
00454 }
00455
00456 namespace ros
00457 {
00458 namespace serialization
00459 {
00460
00461 template<class ContainerAllocator> struct Serializer< ::planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> >
00462 {
00463 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00464 {
00465 stream.next(m.group_name);
00466 }
00467
00468 ROS_DECLARE_ALLINONE_SERIALIZER;
00469 };
00470 }
00471 }
00472
00473
00474 namespace ros
00475 {
00476 namespace serialization
00477 {
00478
00479 template<class ContainerAllocator> struct Serializer< ::planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> >
00480 {
00481 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00482 {
00483 stream.next(m.joint_names);
00484 stream.next(m.link_names);
00485 stream.next(m.error_code);
00486 }
00487
00488 ROS_DECLARE_ALLINONE_SERIALIZER;
00489 };
00490 }
00491 }
00492
00493 namespace ros
00494 {
00495 namespace service_traits
00496 {
00497 template<>
00498 struct MD5Sum<planning_environment_msgs::GetGroupInfo> {
00499 static const char* value()
00500 {
00501 return "ea5e90e42fb70a06b53bacff792b6742";
00502 }
00503
00504 static const char* value(const planning_environment_msgs::GetGroupInfo&) { return value(); }
00505 };
00506
00507 template<>
00508 struct DataType<planning_environment_msgs::GetGroupInfo> {
00509 static const char* value()
00510 {
00511 return "planning_environment_msgs/GetGroupInfo";
00512 }
00513
00514 static const char* value(const planning_environment_msgs::GetGroupInfo&) { return value(); }
00515 };
00516
00517 template<class ContainerAllocator>
00518 struct MD5Sum<planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> > {
00519 static const char* value()
00520 {
00521 return "ea5e90e42fb70a06b53bacff792b6742";
00522 }
00523
00524 static const char* value(const planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> &) { return value(); }
00525 };
00526
00527 template<class ContainerAllocator>
00528 struct DataType<planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> > {
00529 static const char* value()
00530 {
00531 return "planning_environment_msgs/GetGroupInfo";
00532 }
00533
00534 static const char* value(const planning_environment_msgs::GetGroupInfoRequest_<ContainerAllocator> &) { return value(); }
00535 };
00536
00537 template<class ContainerAllocator>
00538 struct MD5Sum<planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> > {
00539 static const char* value()
00540 {
00541 return "ea5e90e42fb70a06b53bacff792b6742";
00542 }
00543
00544 static const char* value(const planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> &) { return value(); }
00545 };
00546
00547 template<class ContainerAllocator>
00548 struct DataType<planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> > {
00549 static const char* value()
00550 {
00551 return "planning_environment_msgs/GetGroupInfo";
00552 }
00553
00554 static const char* value(const planning_environment_msgs::GetGroupInfoResponse_<ContainerAllocator> &) { return value(); }
00555 };
00556
00557 }
00558 }
00559
00560 #endif // PLANNING_ENVIRONMENT_MSGS_SERVICE_GETGROUPINFO_H
00561