00001
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 typedef boost::shared_ptr< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> > Ptr;
00085 typedef boost::shared_ptr< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> const> ConstPtr;
00086 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00087 };
00088 typedef ::cogman_msgs::ArmHandGoal_<std::allocator<void> > ArmHandGoal;
00089
00090 typedef boost::shared_ptr< ::cogman_msgs::ArmHandGoal> ArmHandGoalPtr;
00091 typedef boost::shared_ptr< ::cogman_msgs::ArmHandGoal const> ArmHandGoalConstPtr;
00092
00093
00094 template<typename ContainerAllocator>
00095 std::ostream& operator<<(std::ostream& s, const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> & v)
00096 {
00097 ros::message_operations::Printer< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> >::stream(s, "", v);
00098 return s;}
00099
00100 }
00101
00102 namespace ros
00103 {
00104 namespace message_traits
00105 {
00106 template<class ContainerAllocator> struct IsMessage< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> > : public TrueType {};
00107 template<class ContainerAllocator> struct IsMessage< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> const> : public TrueType {};
00108 template<class ContainerAllocator>
00109 struct MD5Sum< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> > {
00110 static const char* value()
00111 {
00112 return "3a564cf8a4d7611dab9e91da15079bfc";
00113 }
00114
00115 static const char* value(const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> &) { return value(); }
00116 static const uint64_t static_value1 = 0x3a564cf8a4d7611dULL;
00117 static const uint64_t static_value2 = 0xab9e91da15079bfcULL;
00118 };
00119
00120 template<class ContainerAllocator>
00121 struct DataType< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> > {
00122 static const char* value()
00123 {
00124 return "cogman_msgs/ArmHandGoal";
00125 }
00126
00127 static const char* value(const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> &) { return value(); }
00128 };
00129
00130 template<class ContainerAllocator>
00131 struct Definition< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> > {
00132 static const char* value()
00133 {
00134 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00135 string command # 'arm_cart_loid', 'arm_cart_pose', 'arm_cart_name', 'arm_joints', 'arm_joint_name', 'reach_primitive', 'hand_primitive', 'lift', 'put_down'\n\
00136 string pose_name # When moving to pre-defined poses, cointains the name\n\
00137 float32[] joint_angles # If command is 'arm_joints', the joint angles\n\
00138 geometry_msgs/Pose end_effector_pose # command=arm_cart_pose: where the arm should go\n\
00139 uint64 end_effector_loid # one lo_id where the arm should go\n\
00140 string hand_primitive # Allowed strings: open open_thumb90 3pinch 2pinch cup_top peace handshake noop. Used when command is 'finger_primitive'\n\
00141 string object_type # If command is 'reach_primitive', it will define how to grasp (orientation ...)\n\
00142 uint64[] obstacle_ids # List of lo_id's corresponding to obstacles\n\
00143 float32 distance # For reach_primitive: distance from grasp point to approach point (m). For 'lift', distance to lift up (m)\n\
00144 float32 supporting_plane # Height of the table (m)\n\
00145 \n\
00146 ================================================================================\n\
00147 MSG: geometry_msgs/Pose\n\
00148 # A representation of pose in free space, composed of postion and orientation. \n\
00149 Point position\n\
00150 Quaternion orientation\n\
00151 \n\
00152 ================================================================================\n\
00153 MSG: geometry_msgs/Point\n\
00154 # This contains the position of a point in free space\n\
00155 float64 x\n\
00156 float64 y\n\
00157 float64 z\n\
00158 \n\
00159 ================================================================================\n\
00160 MSG: geometry_msgs/Quaternion\n\
00161 # This represents an orientation in free space in quaternion form.\n\
00162 \n\
00163 float64 x\n\
00164 float64 y\n\
00165 float64 z\n\
00166 float64 w\n\
00167 \n\
00168 ";
00169 }
00170
00171 static const char* value(const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> &) { return value(); }
00172 };
00173
00174 }
00175 }
00176
00177 namespace ros
00178 {
00179 namespace serialization
00180 {
00181
00182 template<class ContainerAllocator> struct Serializer< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> >
00183 {
00184 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00185 {
00186 stream.next(m.command);
00187 stream.next(m.pose_name);
00188 stream.next(m.joint_angles);
00189 stream.next(m.end_effector_pose);
00190 stream.next(m.end_effector_loid);
00191 stream.next(m.hand_primitive);
00192 stream.next(m.object_type);
00193 stream.next(m.obstacle_ids);
00194 stream.next(m.distance);
00195 stream.next(m.supporting_plane);
00196 }
00197
00198 ROS_DECLARE_ALLINONE_SERIALIZER;
00199 };
00200 }
00201 }
00202
00203 namespace ros
00204 {
00205 namespace message_operations
00206 {
00207
00208 template<class ContainerAllocator>
00209 struct Printer< ::cogman_msgs::ArmHandGoal_<ContainerAllocator> >
00210 {
00211 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::cogman_msgs::ArmHandGoal_<ContainerAllocator> & v)
00212 {
00213 s << indent << "command: ";
00214 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.command);
00215 s << indent << "pose_name: ";
00216 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.pose_name);
00217 s << indent << "joint_angles[]" << std::endl;
00218 for (size_t i = 0; i < v.joint_angles.size(); ++i)
00219 {
00220 s << indent << " joint_angles[" << i << "]: ";
00221 Printer<float>::stream(s, indent + " ", v.joint_angles[i]);
00222 }
00223 s << indent << "end_effector_pose: ";
00224 s << std::endl;
00225 Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.end_effector_pose);
00226 s << indent << "end_effector_loid: ";
00227 Printer<uint64_t>::stream(s, indent + " ", v.end_effector_loid);
00228 s << indent << "hand_primitive: ";
00229 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.hand_primitive);
00230 s << indent << "object_type: ";
00231 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.object_type);
00232 s << indent << "obstacle_ids[]" << std::endl;
00233 for (size_t i = 0; i < v.obstacle_ids.size(); ++i)
00234 {
00235 s << indent << " obstacle_ids[" << i << "]: ";
00236 Printer<uint64_t>::stream(s, indent + " ", v.obstacle_ids[i]);
00237 }
00238 s << indent << "distance: ";
00239 Printer<float>::stream(s, indent + " ", v.distance);
00240 s << indent << "supporting_plane: ";
00241 Printer<float>::stream(s, indent + " ", v.supporting_plane);
00242 }
00243 };
00244
00245
00246 }
00247 }
00248
00249 #endif // COGMAN_MSGS_MESSAGE_ARMHANDGOAL_H
00250