00001
00002 #ifndef OBJECT_MANIPULATION_MSGS_MESSAGE_GRASPHANDPOSTUREEXECUTIONACTIONGOAL_H
00003 #define OBJECT_MANIPULATION_MSGS_MESSAGE_GRASPHANDPOSTUREEXECUTIONACTIONGOAL_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 "std_msgs/Header.h"
00014 #include "actionlib_msgs/GoalID.h"
00015 #include "object_manipulation_msgs/GraspHandPostureExecutionGoal.h"
00016
00017 namespace object_manipulation_msgs
00018 {
00019 template <class ContainerAllocator>
00020 struct GraspHandPostureExecutionActionGoal_ : public ros::Message
00021 {
00022 typedef GraspHandPostureExecutionActionGoal_<ContainerAllocator> Type;
00023
00024 GraspHandPostureExecutionActionGoal_()
00025 : header()
00026 , goal_id()
00027 , goal()
00028 {
00029 }
00030
00031 GraspHandPostureExecutionActionGoal_(const ContainerAllocator& _alloc)
00032 : header(_alloc)
00033 , goal_id(_alloc)
00034 , goal(_alloc)
00035 {
00036 }
00037
00038 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00039 ::std_msgs::Header_<ContainerAllocator> header;
00040
00041 typedef ::actionlib_msgs::GoalID_<ContainerAllocator> _goal_id_type;
00042 ::actionlib_msgs::GoalID_<ContainerAllocator> goal_id;
00043
00044 typedef ::object_manipulation_msgs::GraspHandPostureExecutionGoal_<ContainerAllocator> _goal_type;
00045 ::object_manipulation_msgs::GraspHandPostureExecutionGoal_<ContainerAllocator> goal;
00046
00047
00048 private:
00049 static const char* __s_getDataType_() { return "object_manipulation_msgs/GraspHandPostureExecutionActionGoal"; }
00050 public:
00051 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00052
00053 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00054
00055 private:
00056 static const char* __s_getMD5Sum_() { return "1ba739716c146e27d08403de62e960f1"; }
00057 public:
00058 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00059
00060 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00061
00062 private:
00063 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00064 \n\
00065 Header header\n\
00066 actionlib_msgs/GoalID goal_id\n\
00067 GraspHandPostureExecutionGoal goal\n\
00068 \n\
00069 ================================================================================\n\
00070 MSG: std_msgs/Header\n\
00071 # Standard metadata for higher-level stamped data types.\n\
00072 # This is generally used to communicate timestamped data \n\
00073 # in a particular coordinate frame.\n\
00074 # \n\
00075 # sequence ID: consecutively increasing ID \n\
00076 uint32 seq\n\
00077 #Two-integer timestamp that is expressed as:\n\
00078 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00079 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00080 # time-handling sugar is provided by the client library\n\
00081 time stamp\n\
00082 #Frame this data is associated with\n\
00083 # 0: no frame\n\
00084 # 1: global frame\n\
00085 string frame_id\n\
00086 \n\
00087 ================================================================================\n\
00088 MSG: actionlib_msgs/GoalID\n\
00089 # The stamp should store the time at which this goal was requested.\n\
00090 # It is used by an action server when it tries to preempt all\n\
00091 # goals that were requested before a certain time\n\
00092 time stamp\n\
00093 \n\
00094 # The id provides a way to associate feedback and\n\
00095 # result message with specific goal requests. The id\n\
00096 # specified must be unique.\n\
00097 string id\n\
00098 \n\
00099 \n\
00100 ================================================================================\n\
00101 MSG: object_manipulation_msgs/GraspHandPostureExecutionGoal\n\
00102 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00103 # an action for requesting the finger posture part of grasp be physically carried out by a hand\n\
00104 # the name of the arm being used is not in here, as this will be sent to a specific action server\n\
00105 # for each arm\n\
00106 \n\
00107 # the grasp to be executed\n\
00108 Grasp grasp\n\
00109 \n\
00110 # the goal of this action\n\
00111 # requests that the hand be set in the pre-grasp posture\n\
00112 int32 PRE_GRASP=1\n\
00113 # requests that the hand execute the actual grasp\n\
00114 int32 GRASP=2\n\
00115 # requests that the hand open to release the object\n\
00116 int32 RELEASE=3\n\
00117 int32 goal\n\
00118 \n\
00119 \n\
00120 ================================================================================\n\
00121 MSG: object_manipulation_msgs/Grasp\n\
00122 \n\
00123 # The internal posture of the hand for the pre-grasp\n\
00124 # only positions are used\n\
00125 sensor_msgs/JointState pre_grasp_posture\n\
00126 \n\
00127 # The internal posture of the hand for the grasp\n\
00128 # positions and efforts are used\n\
00129 sensor_msgs/JointState grasp_posture\n\
00130 \n\
00131 # The position of the end-effector for the grasp relative to the object\n\
00132 geometry_msgs/Pose grasp_pose\n\
00133 \n\
00134 # The estimated probability of success for this grasp\n\
00135 float64 success_probability\n\
00136 \n\
00137 # Debug flag to indicate that this grasp would be the best in its cluster\n\
00138 bool cluster_rep\n\
00139 ================================================================================\n\
00140 MSG: sensor_msgs/JointState\n\
00141 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00142 #\n\
00143 # The state of each joint (revolute or prismatic) is defined by:\n\
00144 # * the position of the joint (rad or m),\n\
00145 # * the velocity of the joint (rad/s or m/s) and \n\
00146 # * the effort that is applied in the joint (Nm or N).\n\
00147 #\n\
00148 # Each joint is uniquely identified by its name\n\
00149 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00150 # in one message have to be recorded at the same time.\n\
00151 #\n\
00152 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00153 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00154 # effort associated with them, you can leave the effort array empty. \n\
00155 #\n\
00156 # All arrays in this message should have the same size, or be empty.\n\
00157 # This is the only way to uniquely associate the joint name with the correct\n\
00158 # states.\n\
00159 \n\
00160 \n\
00161 Header header\n\
00162 \n\
00163 string[] name\n\
00164 float64[] position\n\
00165 float64[] velocity\n\
00166 float64[] effort\n\
00167 \n\
00168 ================================================================================\n\
00169 MSG: geometry_msgs/Pose\n\
00170 # A representation of pose in free space, composed of postion and orientation. \n\
00171 Point position\n\
00172 Quaternion orientation\n\
00173 \n\
00174 ================================================================================\n\
00175 MSG: geometry_msgs/Point\n\
00176 # This contains the position of a point in free space\n\
00177 float64 x\n\
00178 float64 y\n\
00179 float64 z\n\
00180 \n\
00181 ================================================================================\n\
00182 MSG: geometry_msgs/Quaternion\n\
00183 # This represents an orientation in free space in quaternion form.\n\
00184 \n\
00185 float64 x\n\
00186 float64 y\n\
00187 float64 z\n\
00188 float64 w\n\
00189 \n\
00190 "; }
00191 public:
00192 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00193
00194 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00195
00196 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00197 {
00198 ros::serialization::OStream stream(write_ptr, 1000000000);
00199 ros::serialization::serialize(stream, header);
00200 ros::serialization::serialize(stream, goal_id);
00201 ros::serialization::serialize(stream, goal);
00202 return stream.getData();
00203 }
00204
00205 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00206 {
00207 ros::serialization::IStream stream(read_ptr, 1000000000);
00208 ros::serialization::deserialize(stream, header);
00209 ros::serialization::deserialize(stream, goal_id);
00210 ros::serialization::deserialize(stream, goal);
00211 return stream.getData();
00212 }
00213
00214 ROS_DEPRECATED virtual uint32_t serializationLength() const
00215 {
00216 uint32_t size = 0;
00217 size += ros::serialization::serializationLength(header);
00218 size += ros::serialization::serializationLength(goal_id);
00219 size += ros::serialization::serializationLength(goal);
00220 return size;
00221 }
00222
00223 typedef boost::shared_ptr< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> > Ptr;
00224 typedef boost::shared_ptr< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> const> ConstPtr;
00225 };
00226 typedef ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<std::allocator<void> > GraspHandPostureExecutionActionGoal;
00227
00228 typedef boost::shared_ptr< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal> GraspHandPostureExecutionActionGoalPtr;
00229 typedef boost::shared_ptr< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal const> GraspHandPostureExecutionActionGoalConstPtr;
00230
00231
00232 template<typename ContainerAllocator>
00233 std::ostream& operator<<(std::ostream& s, const ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> & v)
00234 {
00235 ros::message_operations::Printer< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> >::stream(s, "", v);
00236 return s;}
00237
00238 }
00239
00240 namespace ros
00241 {
00242 namespace message_traits
00243 {
00244 template<class ContainerAllocator>
00245 struct MD5Sum< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> > {
00246 static const char* value()
00247 {
00248 return "1ba739716c146e27d08403de62e960f1";
00249 }
00250
00251 static const char* value(const ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> &) { return value(); }
00252 static const uint64_t static_value1 = 0x1ba739716c146e27ULL;
00253 static const uint64_t static_value2 = 0xd08403de62e960f1ULL;
00254 };
00255
00256 template<class ContainerAllocator>
00257 struct DataType< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> > {
00258 static const char* value()
00259 {
00260 return "object_manipulation_msgs/GraspHandPostureExecutionActionGoal";
00261 }
00262
00263 static const char* value(const ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> &) { return value(); }
00264 };
00265
00266 template<class ContainerAllocator>
00267 struct Definition< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> > {
00268 static const char* value()
00269 {
00270 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00271 \n\
00272 Header header\n\
00273 actionlib_msgs/GoalID goal_id\n\
00274 GraspHandPostureExecutionGoal goal\n\
00275 \n\
00276 ================================================================================\n\
00277 MSG: std_msgs/Header\n\
00278 # Standard metadata for higher-level stamped data types.\n\
00279 # This is generally used to communicate timestamped data \n\
00280 # in a particular coordinate frame.\n\
00281 # \n\
00282 # sequence ID: consecutively increasing ID \n\
00283 uint32 seq\n\
00284 #Two-integer timestamp that is expressed as:\n\
00285 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00286 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00287 # time-handling sugar is provided by the client library\n\
00288 time stamp\n\
00289 #Frame this data is associated with\n\
00290 # 0: no frame\n\
00291 # 1: global frame\n\
00292 string frame_id\n\
00293 \n\
00294 ================================================================================\n\
00295 MSG: actionlib_msgs/GoalID\n\
00296 # The stamp should store the time at which this goal was requested.\n\
00297 # It is used by an action server when it tries to preempt all\n\
00298 # goals that were requested before a certain time\n\
00299 time stamp\n\
00300 \n\
00301 # The id provides a way to associate feedback and\n\
00302 # result message with specific goal requests. The id\n\
00303 # specified must be unique.\n\
00304 string id\n\
00305 \n\
00306 \n\
00307 ================================================================================\n\
00308 MSG: object_manipulation_msgs/GraspHandPostureExecutionGoal\n\
00309 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00310 # an action for requesting the finger posture part of grasp be physically carried out by a hand\n\
00311 # the name of the arm being used is not in here, as this will be sent to a specific action server\n\
00312 # for each arm\n\
00313 \n\
00314 # the grasp to be executed\n\
00315 Grasp grasp\n\
00316 \n\
00317 # the goal of this action\n\
00318 # requests that the hand be set in the pre-grasp posture\n\
00319 int32 PRE_GRASP=1\n\
00320 # requests that the hand execute the actual grasp\n\
00321 int32 GRASP=2\n\
00322 # requests that the hand open to release the object\n\
00323 int32 RELEASE=3\n\
00324 int32 goal\n\
00325 \n\
00326 \n\
00327 ================================================================================\n\
00328 MSG: object_manipulation_msgs/Grasp\n\
00329 \n\
00330 # The internal posture of the hand for the pre-grasp\n\
00331 # only positions are used\n\
00332 sensor_msgs/JointState pre_grasp_posture\n\
00333 \n\
00334 # The internal posture of the hand for the grasp\n\
00335 # positions and efforts are used\n\
00336 sensor_msgs/JointState grasp_posture\n\
00337 \n\
00338 # The position of the end-effector for the grasp relative to the object\n\
00339 geometry_msgs/Pose grasp_pose\n\
00340 \n\
00341 # The estimated probability of success for this grasp\n\
00342 float64 success_probability\n\
00343 \n\
00344 # Debug flag to indicate that this grasp would be the best in its cluster\n\
00345 bool cluster_rep\n\
00346 ================================================================================\n\
00347 MSG: sensor_msgs/JointState\n\
00348 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00349 #\n\
00350 # The state of each joint (revolute or prismatic) is defined by:\n\
00351 # * the position of the joint (rad or m),\n\
00352 # * the velocity of the joint (rad/s or m/s) and \n\
00353 # * the effort that is applied in the joint (Nm or N).\n\
00354 #\n\
00355 # Each joint is uniquely identified by its name\n\
00356 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00357 # in one message have to be recorded at the same time.\n\
00358 #\n\
00359 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00360 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00361 # effort associated with them, you can leave the effort array empty. \n\
00362 #\n\
00363 # All arrays in this message should have the same size, or be empty.\n\
00364 # This is the only way to uniquely associate the joint name with the correct\n\
00365 # states.\n\
00366 \n\
00367 \n\
00368 Header header\n\
00369 \n\
00370 string[] name\n\
00371 float64[] position\n\
00372 float64[] velocity\n\
00373 float64[] effort\n\
00374 \n\
00375 ================================================================================\n\
00376 MSG: geometry_msgs/Pose\n\
00377 # A representation of pose in free space, composed of postion and orientation. \n\
00378 Point position\n\
00379 Quaternion orientation\n\
00380 \n\
00381 ================================================================================\n\
00382 MSG: geometry_msgs/Point\n\
00383 # This contains the position of a point in free space\n\
00384 float64 x\n\
00385 float64 y\n\
00386 float64 z\n\
00387 \n\
00388 ================================================================================\n\
00389 MSG: geometry_msgs/Quaternion\n\
00390 # This represents an orientation in free space in quaternion form.\n\
00391 \n\
00392 float64 x\n\
00393 float64 y\n\
00394 float64 z\n\
00395 float64 w\n\
00396 \n\
00397 ";
00398 }
00399
00400 static const char* value(const ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> &) { return value(); }
00401 };
00402
00403 template<class ContainerAllocator> struct HasHeader< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> > : public TrueType {};
00404 template<class ContainerAllocator> struct HasHeader< const ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> > : public TrueType {};
00405 }
00406 }
00407
00408 namespace ros
00409 {
00410 namespace serialization
00411 {
00412
00413 template<class ContainerAllocator> struct Serializer< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> >
00414 {
00415 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00416 {
00417 stream.next(m.header);
00418 stream.next(m.goal_id);
00419 stream.next(m.goal);
00420 }
00421
00422 ROS_DECLARE_ALLINONE_SERIALIZER;
00423 };
00424 }
00425 }
00426
00427 namespace ros
00428 {
00429 namespace message_operations
00430 {
00431
00432 template<class ContainerAllocator>
00433 struct Printer< ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> >
00434 {
00435 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::object_manipulation_msgs::GraspHandPostureExecutionActionGoal_<ContainerAllocator> & v)
00436 {
00437 s << indent << "header: ";
00438 s << std::endl;
00439 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00440 s << indent << "goal_id: ";
00441 s << std::endl;
00442 Printer< ::actionlib_msgs::GoalID_<ContainerAllocator> >::stream(s, indent + " ", v.goal_id);
00443 s << indent << "goal: ";
00444 s << std::endl;
00445 Printer< ::object_manipulation_msgs::GraspHandPostureExecutionGoal_<ContainerAllocator> >::stream(s, indent + " ", v.goal);
00446 }
00447 };
00448
00449
00450 }
00451 }
00452
00453 #endif // OBJECT_MANIPULATION_MSGS_MESSAGE_GRASPHANDPOSTUREEXECUTIONACTIONGOAL_H
00454