00001
00002 #ifndef PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPEREVENTDETECTORDATA_H
00003 #define PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPEREVENTDETECTORDATA_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
00018 namespace pr2_gripper_sensor_msgs
00019 {
00020 template <class ContainerAllocator>
00021 struct PR2GripperEventDetectorData_ {
00022 typedef PR2GripperEventDetectorData_<ContainerAllocator> Type;
00023
00024 PR2GripperEventDetectorData_()
00025 : stamp()
00026 , trigger_conditions_met(false)
00027 , slip_event(false)
00028 , acceleration_event(false)
00029 , acceleration_vector()
00030 {
00031 acceleration_vector.assign(0.0);
00032 }
00033
00034 PR2GripperEventDetectorData_(const ContainerAllocator& _alloc)
00035 : stamp()
00036 , trigger_conditions_met(false)
00037 , slip_event(false)
00038 , acceleration_event(false)
00039 , acceleration_vector()
00040 {
00041 acceleration_vector.assign(0.0);
00042 }
00043
00044 typedef ros::Time _stamp_type;
00045 ros::Time stamp;
00046
00047 typedef uint8_t _trigger_conditions_met_type;
00048 uint8_t trigger_conditions_met;
00049
00050 typedef uint8_t _slip_event_type;
00051 uint8_t slip_event;
00052
00053 typedef uint8_t _acceleration_event_type;
00054 uint8_t acceleration_event;
00055
00056 typedef boost::array<double, 3> _acceleration_vector_type;
00057 boost::array<double, 3> acceleration_vector;
00058
00059
00060 ROS_DEPRECATED uint32_t get_acceleration_vector_size() const { return (uint32_t)acceleration_vector.size(); }
00061 private:
00062 static const char* __s_getDataType_() { return "pr2_gripper_sensor_msgs/PR2GripperEventDetectorData"; }
00063 public:
00064 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00065
00066 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00067
00068 private:
00069 static const char* __s_getMD5Sum_() { return "9536d682ef6215440ecc47846d4117c2"; }
00070 public:
00071 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00072
00073 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00074
00075 private:
00076 static const char* __s_getMessageDefinition_() { return "# Time the data was recorded at\n\
00077 time stamp\n\
00078 \n\
00079 # true if the trigger conditions have been met \n\
00080 # (see PR2GripperEventDetectorCommand)\n\
00081 bool trigger_conditions_met\n\
00082 \n\
00083 # true if the pressure sensors detected a slip event\n\
00084 # slip events occur when the finger pressure sensors\n\
00085 # high-freq. content exceeds the slip_trigger_magnitude variable\n\
00086 # (see PR2GripperEventDetectorCommand)\n\
00087 bool slip_event\n\
00088 \n\
00089 # true if the hand-mounted accelerometer detected a contact acceleration\n\
00090 # acceleration events occur when the palm accelerometer\n\
00091 # high-freq. content exceeds the acc_trigger_magnitude variable\n\
00092 # (see PR2GripperEventDetectorCommand)\n\
00093 bool acceleration_event\n\
00094 \n\
00095 # the high-freq acceleration vector that was last seen (x,y,z)\n\
00096 float64[3] acceleration_vector\n\
00097 "; }
00098 public:
00099 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00100
00101 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00102
00103 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00104 {
00105 ros::serialization::OStream stream(write_ptr, 1000000000);
00106 ros::serialization::serialize(stream, stamp);
00107 ros::serialization::serialize(stream, trigger_conditions_met);
00108 ros::serialization::serialize(stream, slip_event);
00109 ros::serialization::serialize(stream, acceleration_event);
00110 ros::serialization::serialize(stream, acceleration_vector);
00111 return stream.getData();
00112 }
00113
00114 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00115 {
00116 ros::serialization::IStream stream(read_ptr, 1000000000);
00117 ros::serialization::deserialize(stream, stamp);
00118 ros::serialization::deserialize(stream, trigger_conditions_met);
00119 ros::serialization::deserialize(stream, slip_event);
00120 ros::serialization::deserialize(stream, acceleration_event);
00121 ros::serialization::deserialize(stream, acceleration_vector);
00122 return stream.getData();
00123 }
00124
00125 ROS_DEPRECATED virtual uint32_t serializationLength() const
00126 {
00127 uint32_t size = 0;
00128 size += ros::serialization::serializationLength(stamp);
00129 size += ros::serialization::serializationLength(trigger_conditions_met);
00130 size += ros::serialization::serializationLength(slip_event);
00131 size += ros::serialization::serializationLength(acceleration_event);
00132 size += ros::serialization::serializationLength(acceleration_vector);
00133 return size;
00134 }
00135
00136 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> > Ptr;
00137 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> const> ConstPtr;
00138 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00139 };
00140 typedef ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<std::allocator<void> > PR2GripperEventDetectorData;
00141
00142 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData> PR2GripperEventDetectorDataPtr;
00143 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData const> PR2GripperEventDetectorDataConstPtr;
00144
00145
00146 template<typename ContainerAllocator>
00147 std::ostream& operator<<(std::ostream& s, const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> & v)
00148 {
00149 ros::message_operations::Printer< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> >::stream(s, "", v);
00150 return s;}
00151
00152 }
00153
00154 namespace ros
00155 {
00156 namespace message_traits
00157 {
00158 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> > : public TrueType {};
00159 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> const> : public TrueType {};
00160 template<class ContainerAllocator>
00161 struct MD5Sum< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> > {
00162 static const char* value()
00163 {
00164 return "9536d682ef6215440ecc47846d4117c2";
00165 }
00166
00167 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> &) { return value(); }
00168 static const uint64_t static_value1 = 0x9536d682ef621544ULL;
00169 static const uint64_t static_value2 = 0x0ecc47846d4117c2ULL;
00170 };
00171
00172 template<class ContainerAllocator>
00173 struct DataType< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> > {
00174 static const char* value()
00175 {
00176 return "pr2_gripper_sensor_msgs/PR2GripperEventDetectorData";
00177 }
00178
00179 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> &) { return value(); }
00180 };
00181
00182 template<class ContainerAllocator>
00183 struct Definition< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> > {
00184 static const char* value()
00185 {
00186 return "# Time the data was recorded at\n\
00187 time stamp\n\
00188 \n\
00189 # true if the trigger conditions have been met \n\
00190 # (see PR2GripperEventDetectorCommand)\n\
00191 bool trigger_conditions_met\n\
00192 \n\
00193 # true if the pressure sensors detected a slip event\n\
00194 # slip events occur when the finger pressure sensors\n\
00195 # high-freq. content exceeds the slip_trigger_magnitude variable\n\
00196 # (see PR2GripperEventDetectorCommand)\n\
00197 bool slip_event\n\
00198 \n\
00199 # true if the hand-mounted accelerometer detected a contact acceleration\n\
00200 # acceleration events occur when the palm accelerometer\n\
00201 # high-freq. content exceeds the acc_trigger_magnitude variable\n\
00202 # (see PR2GripperEventDetectorCommand)\n\
00203 bool acceleration_event\n\
00204 \n\
00205 # the high-freq acceleration vector that was last seen (x,y,z)\n\
00206 float64[3] acceleration_vector\n\
00207 ";
00208 }
00209
00210 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> &) { return value(); }
00211 };
00212
00213 template<class ContainerAllocator> struct IsFixedSize< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> > : public TrueType {};
00214 }
00215 }
00216
00217 namespace ros
00218 {
00219 namespace serialization
00220 {
00221
00222 template<class ContainerAllocator> struct Serializer< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> >
00223 {
00224 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00225 {
00226 stream.next(m.stamp);
00227 stream.next(m.trigger_conditions_met);
00228 stream.next(m.slip_event);
00229 stream.next(m.acceleration_event);
00230 stream.next(m.acceleration_vector);
00231 }
00232
00233 ROS_DECLARE_ALLINONE_SERIALIZER;
00234 };
00235 }
00236 }
00237
00238 namespace ros
00239 {
00240 namespace message_operations
00241 {
00242
00243 template<class ContainerAllocator>
00244 struct Printer< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> >
00245 {
00246 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorData_<ContainerAllocator> & v)
00247 {
00248 s << indent << "stamp: ";
00249 Printer<ros::Time>::stream(s, indent + " ", v.stamp);
00250 s << indent << "trigger_conditions_met: ";
00251 Printer<uint8_t>::stream(s, indent + " ", v.trigger_conditions_met);
00252 s << indent << "slip_event: ";
00253 Printer<uint8_t>::stream(s, indent + " ", v.slip_event);
00254 s << indent << "acceleration_event: ";
00255 Printer<uint8_t>::stream(s, indent + " ", v.acceleration_event);
00256 s << indent << "acceleration_vector[]" << std::endl;
00257 for (size_t i = 0; i < v.acceleration_vector.size(); ++i)
00258 {
00259 s << indent << " acceleration_vector[" << i << "]: ";
00260 Printer<double>::stream(s, indent + " ", v.acceleration_vector[i]);
00261 }
00262 }
00263 };
00264
00265
00266 }
00267 }
00268
00269 #endif // PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPEREVENTDETECTORDATA_H
00270