00001
00002 #ifndef PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERFINDCONTACTFEEDBACK_H
00003 #define PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERFINDCONTACTFEEDBACK_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 "pr2_gripper_sensor_msgs/PR2GripperFindContactData.h"
00014
00015 namespace pr2_gripper_sensor_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct PR2GripperFindContactFeedback_ : public ros::Message
00019 {
00020 typedef PR2GripperFindContactFeedback_<ContainerAllocator> Type;
00021
00022 PR2GripperFindContactFeedback_()
00023 : data()
00024 {
00025 }
00026
00027 PR2GripperFindContactFeedback_(const ContainerAllocator& _alloc)
00028 : data(_alloc)
00029 {
00030 }
00031
00032 typedef ::pr2_gripper_sensor_msgs::PR2GripperFindContactData_<ContainerAllocator> _data_type;
00033 ::pr2_gripper_sensor_msgs::PR2GripperFindContactData_<ContainerAllocator> data;
00034
00035
00036 private:
00037 static const char* __s_getDataType_() { return "pr2_gripper_sensor_msgs/PR2GripperFindContactFeedback"; }
00038 public:
00039 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00040
00041 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00042
00043 private:
00044 static const char* __s_getMD5Sum_() { return "a1cc8c2fc9268b550e6167f268f97574"; }
00045 public:
00046 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00047
00048 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00049
00050 private:
00051 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00052 # feedback\n\
00053 PR2GripperFindContactData data\n\
00054 \n\
00055 \n\
00056 \n\
00057 ================================================================================\n\
00058 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactData\n\
00059 # Time the data was recorded at\n\
00060 time stamp\n\
00061 \n\
00062 # true when our contact conditions have been met\n\
00063 # (see PR2GripperFindContact command)\n\
00064 bool contact_conditions_met\n\
00065 \n\
00066 # the finger contact conditions \n\
00067 # true if the finger experienced a contact event\n\
00068 #\n\
00069 # contact events are defined as contact with the fingerpads\n\
00070 # as either steady-state or high-freq force events\n\
00071 bool left_fingertip_pad_contact\n\
00072 bool right_fingertip_pad_contact\n\
00073 \n\
00074 # the force experinced by the finger Pads (N)\n\
00075 # NOTE:this ignores data from the edges of the finger pressure\n\
00076 float64 left_fingertip_pad_force\n\
00077 float64 right_fingertip_pad_force\n\
00078 \n\
00079 # the current joint position (m)\n\
00080 float64 joint_position\n\
00081 \n\
00082 # the virtual (parallel) joint effort (N)\n\
00083 float64 joint_effort\n\
00084 \n\
00085 # the control state of our realtime controller\n\
00086 PR2GripperSensorRTState rtstate\n\
00087 ================================================================================\n\
00088 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState\n\
00089 # the control state of our realtime controller\n\
00090 int8 realtime_controller_state\n\
00091 \n\
00092 # predefined values to indicate our realtime_controller_state\n\
00093 int8 DISABLED = 0\n\
00094 int8 POSITION_SERVO = 3\n\
00095 int8 FORCE_SERVO = 4\n\
00096 int8 FIND_CONTACT = 5\n\
00097 int8 SLIP_SERVO = 6\n\
00098 "; }
00099 public:
00100 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00101
00102 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00103
00104 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00105 {
00106 ros::serialization::OStream stream(write_ptr, 1000000000);
00107 ros::serialization::serialize(stream, data);
00108 return stream.getData();
00109 }
00110
00111 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00112 {
00113 ros::serialization::IStream stream(read_ptr, 1000000000);
00114 ros::serialization::deserialize(stream, data);
00115 return stream.getData();
00116 }
00117
00118 ROS_DEPRECATED virtual uint32_t serializationLength() const
00119 {
00120 uint32_t size = 0;
00121 size += ros::serialization::serializationLength(data);
00122 return size;
00123 }
00124
00125 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> > Ptr;
00126 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> const> ConstPtr;
00127 };
00128 typedef ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<std::allocator<void> > PR2GripperFindContactFeedback;
00129
00130 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback> PR2GripperFindContactFeedbackPtr;
00131 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback const> PR2GripperFindContactFeedbackConstPtr;
00132
00133
00134 template<typename ContainerAllocator>
00135 std::ostream& operator<<(std::ostream& s, const ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> & v)
00136 {
00137 ros::message_operations::Printer< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> >::stream(s, "", v);
00138 return s;}
00139
00140 }
00141
00142 namespace ros
00143 {
00144 namespace message_traits
00145 {
00146 template<class ContainerAllocator>
00147 struct MD5Sum< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> > {
00148 static const char* value()
00149 {
00150 return "a1cc8c2fc9268b550e6167f268f97574";
00151 }
00152
00153 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> &) { return value(); }
00154 static const uint64_t static_value1 = 0xa1cc8c2fc9268b55ULL;
00155 static const uint64_t static_value2 = 0x0e6167f268f97574ULL;
00156 };
00157
00158 template<class ContainerAllocator>
00159 struct DataType< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> > {
00160 static const char* value()
00161 {
00162 return "pr2_gripper_sensor_msgs/PR2GripperFindContactFeedback";
00163 }
00164
00165 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> &) { return value(); }
00166 };
00167
00168 template<class ContainerAllocator>
00169 struct Definition< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> > {
00170 static const char* value()
00171 {
00172 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00173 # feedback\n\
00174 PR2GripperFindContactData data\n\
00175 \n\
00176 \n\
00177 \n\
00178 ================================================================================\n\
00179 MSG: pr2_gripper_sensor_msgs/PR2GripperFindContactData\n\
00180 # Time the data was recorded at\n\
00181 time stamp\n\
00182 \n\
00183 # true when our contact conditions have been met\n\
00184 # (see PR2GripperFindContact command)\n\
00185 bool contact_conditions_met\n\
00186 \n\
00187 # the finger contact conditions \n\
00188 # true if the finger experienced a contact event\n\
00189 #\n\
00190 # contact events are defined as contact with the fingerpads\n\
00191 # as either steady-state or high-freq force events\n\
00192 bool left_fingertip_pad_contact\n\
00193 bool right_fingertip_pad_contact\n\
00194 \n\
00195 # the force experinced by the finger Pads (N)\n\
00196 # NOTE:this ignores data from the edges of the finger pressure\n\
00197 float64 left_fingertip_pad_force\n\
00198 float64 right_fingertip_pad_force\n\
00199 \n\
00200 # the current joint position (m)\n\
00201 float64 joint_position\n\
00202 \n\
00203 # the virtual (parallel) joint effort (N)\n\
00204 float64 joint_effort\n\
00205 \n\
00206 # the control state of our realtime controller\n\
00207 PR2GripperSensorRTState rtstate\n\
00208 ================================================================================\n\
00209 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState\n\
00210 # the control state of our realtime controller\n\
00211 int8 realtime_controller_state\n\
00212 \n\
00213 # predefined values to indicate our realtime_controller_state\n\
00214 int8 DISABLED = 0\n\
00215 int8 POSITION_SERVO = 3\n\
00216 int8 FORCE_SERVO = 4\n\
00217 int8 FIND_CONTACT = 5\n\
00218 int8 SLIP_SERVO = 6\n\
00219 ";
00220 }
00221
00222 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> &) { return value(); }
00223 };
00224
00225 template<class ContainerAllocator> struct IsFixedSize< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> > : public TrueType {};
00226 }
00227 }
00228
00229 namespace ros
00230 {
00231 namespace serialization
00232 {
00233
00234 template<class ContainerAllocator> struct Serializer< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> >
00235 {
00236 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00237 {
00238 stream.next(m.data);
00239 }
00240
00241 ROS_DECLARE_ALLINONE_SERIALIZER;
00242 };
00243 }
00244 }
00245
00246 namespace ros
00247 {
00248 namespace message_operations
00249 {
00250
00251 template<class ContainerAllocator>
00252 struct Printer< ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> >
00253 {
00254 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_gripper_sensor_msgs::PR2GripperFindContactFeedback_<ContainerAllocator> & v)
00255 {
00256 s << indent << "data: ";
00257 s << std::endl;
00258 Printer< ::pr2_gripper_sensor_msgs::PR2GripperFindContactData_<ContainerAllocator> >::stream(s, indent + " ", v.data);
00259 }
00260 };
00261
00262
00263 }
00264 }
00265
00266 #endif // PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERFINDCONTACTFEEDBACK_H
00267