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