00001
00002 #ifndef COGMAN_MSGS_MESSAGE_ARMHANDGOAL_H
00003 #define COGMAN_MSGS_MESSAGE_ARMHANDGOAL_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 "geometry_msgs/Pose.h"
00014
00015 namespace cogman_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct ArmHandGoal_ : public ros::Message
00019 {
00020 typedef ArmHandGoal_<ContainerAllocator> Type;
00021
00022 ArmHandGoal_()
00023 : command()
00024 , pose_name()
00025 , joint_angles()
00026 , end_effector_pose()
00027 , end_effector_loid(0)
00028 , hand_primitive()
00029 , object_type()
00030 , obstacle_ids()
00031 , distance(0.0)
00032 , supporting_plane(0.0)
00033 {
00034 }
00035
00036 ArmHandGoal_(const ContainerAllocator& _alloc)
00037 : command(_alloc)
00038 , pose_name(_alloc)
00039 , joint_angles(_alloc)
00040 , end_effector_pose(_alloc)
00041 , end_effector_loid(0)
00042 , hand_primitive(_alloc)
00043 , object_type(_alloc)
00044 , obstacle_ids(_alloc)
00045 , distance(0.0)
00046 , supporting_plane(0.0)
00047 {
00048 }
00049
00050 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _command_type;
00051 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > command;
00052
00053 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _pose_name_type;
00054 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > pose_name;
00055
00056 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _joint_angles_type;
00057 std::vector<float, typename ContainerAllocator::template rebind<float>::other > joint_angles;
00058
00059 typedef ::geometry_msgs::Pose_<ContainerAllocator> _end_effector_pose_type;
00060 ::geometry_msgs::Pose_<ContainerAllocator> end_effector_pose;
00061
00062 typedef uint64_t _end_effector_loid_type;
00063 uint64_t end_effector_loid;
00064
00065 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _hand_primitive_type;
00066 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > hand_primitive;
00067
00068 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _object_type_type;
00069 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > object_type;
00070
00071 typedef std::vector<uint64_t, typename ContainerAllocator::template rebind<uint64_t>::other > _obstacle_ids_type;
00072 std::vector<uint64_t, typename ContainerAllocator::template rebind<uint64_t>::other > obstacle_ids;
00073
00074 typedef float _distance_type;
00075 float distance;
00076
00077 typedef float _supporting_plane_type;
00078 float supporting_plane;
00079
00080
00081 ROS_DEPRECATED uint32_t get_joint_angles_size() const { return (uint32_t)joint_angles.size(); }
00082 ROS_DEPRECATED void set_joint_angles_size(uint32_t size) { joint_angles.resize((size_t)size); }
00083 ROS_DEPRECATED void get_joint_angles_vec(std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) const { vec = this->joint_angles; }
00084 ROS_DEPRECATED void set_joint_angles_vec(const std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) { this->joint_angles = vec; }
00085 ROS_DEPRECATED uint32_t get_obstacle_ids_size() const { return (uint32_t)obstacle_ids.size(); }
00086 ROS_DEPRECATED void set_obstacle_ids_size(uint32_t size) { obstacle_ids.resize((size_t)size); }
00087 ROS_DEPRECATED void get_obstacle_ids_vec(std::vector<uint64_t, typename ContainerAllocator::template rebind<uint64_t>::other > & vec) const { vec = this->obstacle_ids; }
00088 ROS_DEPRECATED void set_obstacle_ids_vec(const std::vector<uint64_t, typename ContainerAllocator::template rebind<uint64_t>::other > & vec) { this->obstacle_ids = vec; }
00089 private:
00090 static const char* __s_getDataType_() { return "cogman_msgs/ArmHandGoal"; }
00091 public:
00092 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00093
00094 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00095
00096 private:
00097 static const char* __s_getMD5Sum_() { return "3a564cf8a4d7611dab9e91da15079bfc"; }
00098 public:
00099 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00100
00101 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00102
00103 private:
00104 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00105 string command # 'arm_cart_loid', 'arm_cart_pose', 'arm_cart_name', 'arm_joints', 'arm_joint_name', 'reach_primitive', 'hand_primitive', 'lift', 'put_down'\n\
00106 string pose_name # When moving to pre-defined poses, cointains the name\n\
00107 float32[] joint_angles # If command is 'arm_joints', the joint angles\n\
00108 geometry_msgs/Pose end_effector_pose # command=arm_cart_pose: where the arm should go\n\
00109 uint64 end_effector_loid # one lo_id where the arm should go\n\
00110 string hand_primitive # Allowed strings: open open_thumb90 3pinch 2pinch cup_top peace handshake noop. Used when command is 'finger_primitive'\n\
00111 string object_type # If command is 'reach_primitive', it will define how to grasp (orientation ...)\n\
00112 uint64[] obstacle_ids # List of lo_id's corresponding to obstacles\n\
00113 float32 distance # For reach_primitive: distance from grasp point to approach point (m). For 'lift', distance to lift up (m)\n\
00114 float32 supporting_plane # Height of the table (m)\n\
00115 \n\
00116 ================================================================================\n\
00117 MSG: geometry_msgs/Pose\n\
00118 # A representation of pose in free space, composed of postion and orientation. \n\
00119 Point position\n\
00120 Quaternion orientation\n\
00121 \n\
00122 ================================================================================\n\
00123 MSG: geometry_msgs/Point\n\
00124 # This contains the position of a point in free space\n\
00125 float64 x\n\
00126 float64 y\n\
00127 float64 z\n\
00128 \n\
00129 ================================================================================\n\
00130 MSG: geometry_msgs/Quaternion\n\
00131 # This represents an orientation in free space in quaternion form.\n\
00132 \n\
00133 float64 x\n\
00134 float64 y\n\
00135 float64 z\n\
00136 float64 w\n\
00137 \n\
00138 "; }
00139 public:
00140 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00141
00142 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00143
00144 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00145 {
00146 ros::serialization::OStream stream(write_ptr, 1000000000);
00147 ros::serialization::serialize(stream, command);
00148 ros::serialization::serialize(stream, pose_name);
00149 ros::serialization::serialize(stream, joint_angles);
00150 ros::serialization::serialize(stream, end_effector_pose);
00151 ros::serialization::serialize(stream, end_effector_loid);
00152 ros::serialization::serialize(stream, hand_primitive);
00153 ros::serialization::serialize(stream, object_type);
00154 ros::serialization::serialize(stream, obstacle_ids);
00155 ros::serialization::serialize(stream, distance);
00156 ros::serialization::serialize(stream, supporting_plane);
00157 return stream.getData();
00158 }
00159
00160 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00161 {
00162 ros::serialization::IStream stream(read_ptr, 1000000000);
00163 ros::serialization::deserialize(stream, command);
00164 ros::serialization::deserialize(stream, pose_name);
00165 ros::serialization::deserialize(stream, joint_angles);
00166 ros::serialization::deserialize(stream, end_effector_pose);
00167 ros::serialization::deserialize(stream, end_effector_loid);
00168 ros::serialization::deserialize(stream, hand_primitive);
00169 ros::serialization::deserialize(stream, object_type);
00170 ros::serialization::deserialize(stream, obstacle_ids);
00171 ros::serialization::deserialize(stream, distance);
00172 ros::serialization::deserialize(stream, supporting_plane);
00173 return stream.getData();
00174 }
00175
00176 ROS_DEPRECATED virtual uint32_t serializationLength() const
00177 {
00178 uint32_t size = 0;
00179 size += ros::serialization::serializationLength(command);
00180 size += ros::serialization::serializationLength(pose_name);
00181 size += ros::serialization::serializationLength(joint_angles);
00182 size += ros::serialization::serializationLength(end_effector_pose);
00183 size += ros::serialization::serializationLength(end_effector_loid);
00184 size += ros::serialization::serializationLength(hand_primitive);
00185 size += ros::serialization::serializationLength(object_type);
00186 size += ros::serialization::serializationLength(obstacle_ids);
00187 size += ros::serialization::serializationLength(distance);
00188 size += ros::serialization::serializationLength(supporting_plane);
00189 return size;
00190 }
00191
00192 typedef boost::shared_ptr< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> > Ptr;
00193 typedef boost::shared_ptr< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> const> ConstPtr;
00194 };
00195 typedef ::cogman_msgs::ArmHandGoal_<std::allocator<void> > ArmHandGoal;
00196
00197 typedef boost::shared_ptr< ::cogman_msgs::ArmHandGoal> ArmHandGoalPtr;
00198 typedef boost::shared_ptr< ::cogman_msgs::ArmHandGoal const> ArmHandGoalConstPtr;
00199
00200
00201 template<typename ContainerAllocator>
00202 std::ostream& operator<<(std::ostream& s, const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> & v)
00203 {
00204 ros::message_operations::Printer< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> >::stream(s, "", v);
00205 return s;}
00206
00207 }
00208
00209 namespace ros
00210 {
00211 namespace message_traits
00212 {
00213 template<class ContainerAllocator>
00214 struct MD5Sum< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> > {
00215 static const char* value()
00216 {
00217 return "3a564cf8a4d7611dab9e91da15079bfc";
00218 }
00219
00220 static const char* value(const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> &) { return value(); }
00221 static const uint64_t static_value1 = 0x3a564cf8a4d7611dULL;
00222 static const uint64_t static_value2 = 0xab9e91da15079bfcULL;
00223 };
00224
00225 template<class ContainerAllocator>
00226 struct DataType< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> > {
00227 static const char* value()
00228 {
00229 return "cogman_msgs/ArmHandGoal";
00230 }
00231
00232 static const char* value(const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> &) { return value(); }
00233 };
00234
00235 template<class ContainerAllocator>
00236 struct Definition< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> > {
00237 static const char* value()
00238 {
00239 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00240 string command # 'arm_cart_loid', 'arm_cart_pose', 'arm_cart_name', 'arm_joints', 'arm_joint_name', 'reach_primitive', 'hand_primitive', 'lift', 'put_down'\n\
00241 string pose_name # When moving to pre-defined poses, cointains the name\n\
00242 float32[] joint_angles # If command is 'arm_joints', the joint angles\n\
00243 geometry_msgs/Pose end_effector_pose # command=arm_cart_pose: where the arm should go\n\
00244 uint64 end_effector_loid # one lo_id where the arm should go\n\
00245 string hand_primitive # Allowed strings: open open_thumb90 3pinch 2pinch cup_top peace handshake noop. Used when command is 'finger_primitive'\n\
00246 string object_type # If command is 'reach_primitive', it will define how to grasp (orientation ...)\n\
00247 uint64[] obstacle_ids # List of lo_id's corresponding to obstacles\n\
00248 float32 distance # For reach_primitive: distance from grasp point to approach point (m). For 'lift', distance to lift up (m)\n\
00249 float32 supporting_plane # Height of the table (m)\n\
00250 \n\
00251 ================================================================================\n\
00252 MSG: geometry_msgs/Pose\n\
00253 # A representation of pose in free space, composed of postion and orientation. \n\
00254 Point position\n\
00255 Quaternion orientation\n\
00256 \n\
00257 ================================================================================\n\
00258 MSG: geometry_msgs/Point\n\
00259 # This contains the position of a point in free space\n\
00260 float64 x\n\
00261 float64 y\n\
00262 float64 z\n\
00263 \n\
00264 ================================================================================\n\
00265 MSG: geometry_msgs/Quaternion\n\
00266 # This represents an orientation in free space in quaternion form.\n\
00267 \n\
00268 float64 x\n\
00269 float64 y\n\
00270 float64 z\n\
00271 float64 w\n\
00272 \n\
00273 ";
00274 }
00275
00276 static const char* value(const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> &) { return value(); }
00277 };
00278
00279 }
00280 }
00281
00282 namespace ros
00283 {
00284 namespace serialization
00285 {
00286
00287 template<class ContainerAllocator> struct Serializer< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> >
00288 {
00289 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00290 {
00291 stream.next(m.command);
00292 stream.next(m.pose_name);
00293 stream.next(m.joint_angles);
00294 stream.next(m.end_effector_pose);
00295 stream.next(m.end_effector_loid);
00296 stream.next(m.hand_primitive);
00297 stream.next(m.object_type);
00298 stream.next(m.obstacle_ids);
00299 stream.next(m.distance);
00300 stream.next(m.supporting_plane);
00301 }
00302
00303 ROS_DECLARE_ALLINONE_SERIALIZER;
00304 };
00305 }
00306 }
00307
00308 namespace ros
00309 {
00310 namespace message_operations
00311 {
00312
00313 template<class ContainerAllocator>
00314 struct Printer< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> >
00315 {
00316 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> & v)
00317 {
00318 s << indent << "command: ";
00319 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.command);
00320 s << indent << "pose_name: ";
00321 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.pose_name);
00322 s << indent << "joint_angles[]" << std::endl;
00323 for (size_t i = 0; i < v.joint_angles.size(); ++i)
00324 {
00325 s << indent << " joint_angles[" << i << "]: ";
00326 Printer<float>::stream(s, indent + " ", v.joint_angles[i]);
00327 }
00328 s << indent << "end_effector_pose: ";
00329 s << std::endl;
00330 Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.end_effector_pose);
00331 s << indent << "end_effector_loid: ";
00332 Printer<uint64_t>::stream(s, indent + " ", v.end_effector_loid);
00333 s << indent << "hand_primitive: ";
00334 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.hand_primitive);
00335 s << indent << "object_type: ";
00336 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.object_type);
00337 s << indent << "obstacle_ids[]" << std::endl;
00338 for (size_t i = 0; i < v.obstacle_ids.size(); ++i)
00339 {
00340 s << indent << " obstacle_ids[" << i << "]: ";
00341 Printer<uint64_t>::stream(s, indent + " ", v.obstacle_ids[i]);
00342 }
00343 s << indent << "distance: ";
00344 Printer<float>::stream(s, indent + " ", v.distance);
00345 s << indent << "supporting_plane: ";
00346 Printer<float>::stream(s, indent + " ", v.supporting_plane);
00347 }
00348 };
00349
00350
00351 }
00352 }
00353
00354 #endif // COGMAN_MSGS_MESSAGE_ARMHANDGOAL_H
00355