00001
00002 #ifndef PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERSENSORRAWDATA_H
00003 #define PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERSENSORRAWDATA_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 PR2GripperSensorRawData_ {
00022 typedef PR2GripperSensorRawData_<ContainerAllocator> Type;
00023
00024 PR2GripperSensorRawData_()
00025 : stamp()
00026 , left_finger_pad_force(0.0)
00027 , right_finger_pad_force(0.0)
00028 , left_finger_pad_force_filtered(0.0)
00029 , right_finger_pad_force_filtered(0.0)
00030 , left_finger_pad_forces()
00031 , right_finger_pad_forces()
00032 , left_finger_pad_forces_filtered()
00033 , right_finger_pad_forces_filtered()
00034 , acc_x_raw(0.0)
00035 , acc_y_raw(0.0)
00036 , acc_z_raw(0.0)
00037 , acc_x_filtered(0.0)
00038 , acc_y_filtered(0.0)
00039 , acc_z_filtered(0.0)
00040 , left_contact(false)
00041 , right_contact(false)
00042 {
00043 left_finger_pad_forces.assign(0.0);
00044 right_finger_pad_forces.assign(0.0);
00045 left_finger_pad_forces_filtered.assign(0.0);
00046 right_finger_pad_forces_filtered.assign(0.0);
00047 }
00048
00049 PR2GripperSensorRawData_(const ContainerAllocator& _alloc)
00050 : stamp()
00051 , left_finger_pad_force(0.0)
00052 , right_finger_pad_force(0.0)
00053 , left_finger_pad_force_filtered(0.0)
00054 , right_finger_pad_force_filtered(0.0)
00055 , left_finger_pad_forces()
00056 , right_finger_pad_forces()
00057 , left_finger_pad_forces_filtered()
00058 , right_finger_pad_forces_filtered()
00059 , acc_x_raw(0.0)
00060 , acc_y_raw(0.0)
00061 , acc_z_raw(0.0)
00062 , acc_x_filtered(0.0)
00063 , acc_y_filtered(0.0)
00064 , acc_z_filtered(0.0)
00065 , left_contact(false)
00066 , right_contact(false)
00067 {
00068 left_finger_pad_forces.assign(0.0);
00069 right_finger_pad_forces.assign(0.0);
00070 left_finger_pad_forces_filtered.assign(0.0);
00071 right_finger_pad_forces_filtered.assign(0.0);
00072 }
00073
00074 typedef ros::Time _stamp_type;
00075 ros::Time stamp;
00076
00077 typedef double _left_finger_pad_force_type;
00078 double left_finger_pad_force;
00079
00080 typedef double _right_finger_pad_force_type;
00081 double right_finger_pad_force;
00082
00083 typedef double _left_finger_pad_force_filtered_type;
00084 double left_finger_pad_force_filtered;
00085
00086 typedef double _right_finger_pad_force_filtered_type;
00087 double right_finger_pad_force_filtered;
00088
00089 typedef boost::array<double, 22> _left_finger_pad_forces_type;
00090 boost::array<double, 22> left_finger_pad_forces;
00091
00092 typedef boost::array<double, 22> _right_finger_pad_forces_type;
00093 boost::array<double, 22> right_finger_pad_forces;
00094
00095 typedef boost::array<double, 22> _left_finger_pad_forces_filtered_type;
00096 boost::array<double, 22> left_finger_pad_forces_filtered;
00097
00098 typedef boost::array<double, 22> _right_finger_pad_forces_filtered_type;
00099 boost::array<double, 22> right_finger_pad_forces_filtered;
00100
00101 typedef double _acc_x_raw_type;
00102 double acc_x_raw;
00103
00104 typedef double _acc_y_raw_type;
00105 double acc_y_raw;
00106
00107 typedef double _acc_z_raw_type;
00108 double acc_z_raw;
00109
00110 typedef double _acc_x_filtered_type;
00111 double acc_x_filtered;
00112
00113 typedef double _acc_y_filtered_type;
00114 double acc_y_filtered;
00115
00116 typedef double _acc_z_filtered_type;
00117 double acc_z_filtered;
00118
00119 typedef uint8_t _left_contact_type;
00120 uint8_t left_contact;
00121
00122 typedef uint8_t _right_contact_type;
00123 uint8_t right_contact;
00124
00125
00126 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > Ptr;
00127 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> const> ConstPtr;
00128 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00129 };
00130 typedef ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<std::allocator<void> > PR2GripperSensorRawData;
00131
00132 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData> PR2GripperSensorRawDataPtr;
00133 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData const> PR2GripperSensorRawDataConstPtr;
00134
00135
00136 template<typename ContainerAllocator>
00137 std::ostream& operator<<(std::ostream& s, const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> & v)
00138 {
00139 ros::message_operations::Printer< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> >::stream(s, "", v);
00140 return s;}
00141
00142 }
00143
00144 namespace ros
00145 {
00146 namespace message_traits
00147 {
00148 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > : public TrueType {};
00149 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> const> : public TrueType {};
00150 template<class ContainerAllocator>
00151 struct MD5Sum< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > {
00152 static const char* value()
00153 {
00154 return "696a1f2e6969deb0bc6998636ae1b17e";
00155 }
00156
00157 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> &) { return value(); }
00158 static const uint64_t static_value1 = 0x696a1f2e6969deb0ULL;
00159 static const uint64_t static_value2 = 0xbc6998636ae1b17eULL;
00160 };
00161
00162 template<class ContainerAllocator>
00163 struct DataType< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > {
00164 static const char* value()
00165 {
00166 return "pr2_gripper_sensor_msgs/PR2GripperSensorRawData";
00167 }
00168
00169 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> &) { return value(); }
00170 };
00171
00172 template<class ContainerAllocator>
00173 struct Definition< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > {
00174 static const char* value()
00175 {
00176 return "# NOTE: This message is only for debugging purposes. It is not intended for API usage - and is not published under release code.\n\
00177 \n\
00178 # Standard ROS header\n\
00179 time stamp\n\
00180 \n\
00181 # corrected for zero contact\n\
00182 float64 left_finger_pad_force\n\
00183 float64 right_finger_pad_force\n\
00184 \n\
00185 # filtered values : high pass filter at 5 Hz after correcting for zero contact\n\
00186 float64 left_finger_pad_force_filtered\n\
00187 float64 right_finger_pad_force_filtered\n\
00188 \n\
00189 # corrected for zero contact\n\
00190 float64[22] left_finger_pad_forces\n\
00191 float64[22] right_finger_pad_forces\n\
00192 \n\
00193 # filtered values : high pass filter at 5 Hz after correcting for zero contact\n\
00194 float64[22] left_finger_pad_forces_filtered\n\
00195 float64[22] right_finger_pad_forces_filtered\n\
00196 \n\
00197 # raw acceleration values\n\
00198 float64 acc_x_raw\n\
00199 float64 acc_y_raw\n\
00200 float64 acc_z_raw\n\
00201 \n\
00202 # filtered acceleration values\n\
00203 float64 acc_x_filtered\n\
00204 float64 acc_y_filtered\n\
00205 float64 acc_z_filtered\n\
00206 \n\
00207 # boolean variables indicating whether contact exists or not\n\
00208 bool left_contact\n\
00209 bool right_contact\n\
00210 ";
00211 }
00212
00213 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> &) { return value(); }
00214 };
00215
00216 template<class ContainerAllocator> struct IsFixedSize< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > : public TrueType {};
00217 }
00218 }
00219
00220 namespace ros
00221 {
00222 namespace serialization
00223 {
00224
00225 template<class ContainerAllocator> struct Serializer< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> >
00226 {
00227 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00228 {
00229 stream.next(m.stamp);
00230 stream.next(m.left_finger_pad_force);
00231 stream.next(m.right_finger_pad_force);
00232 stream.next(m.left_finger_pad_force_filtered);
00233 stream.next(m.right_finger_pad_force_filtered);
00234 stream.next(m.left_finger_pad_forces);
00235 stream.next(m.right_finger_pad_forces);
00236 stream.next(m.left_finger_pad_forces_filtered);
00237 stream.next(m.right_finger_pad_forces_filtered);
00238 stream.next(m.acc_x_raw);
00239 stream.next(m.acc_y_raw);
00240 stream.next(m.acc_z_raw);
00241 stream.next(m.acc_x_filtered);
00242 stream.next(m.acc_y_filtered);
00243 stream.next(m.acc_z_filtered);
00244 stream.next(m.left_contact);
00245 stream.next(m.right_contact);
00246 }
00247
00248 ROS_DECLARE_ALLINONE_SERIALIZER;
00249 };
00250 }
00251 }
00252
00253 namespace ros
00254 {
00255 namespace message_operations
00256 {
00257
00258 template<class ContainerAllocator>
00259 struct Printer< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> >
00260 {
00261 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> & v)
00262 {
00263 s << indent << "stamp: ";
00264 Printer<ros::Time>::stream(s, indent + " ", v.stamp);
00265 s << indent << "left_finger_pad_force: ";
00266 Printer<double>::stream(s, indent + " ", v.left_finger_pad_force);
00267 s << indent << "right_finger_pad_force: ";
00268 Printer<double>::stream(s, indent + " ", v.right_finger_pad_force);
00269 s << indent << "left_finger_pad_force_filtered: ";
00270 Printer<double>::stream(s, indent + " ", v.left_finger_pad_force_filtered);
00271 s << indent << "right_finger_pad_force_filtered: ";
00272 Printer<double>::stream(s, indent + " ", v.right_finger_pad_force_filtered);
00273 s << indent << "left_finger_pad_forces[]" << std::endl;
00274 for (size_t i = 0; i < v.left_finger_pad_forces.size(); ++i)
00275 {
00276 s << indent << " left_finger_pad_forces[" << i << "]: ";
00277 Printer<double>::stream(s, indent + " ", v.left_finger_pad_forces[i]);
00278 }
00279 s << indent << "right_finger_pad_forces[]" << std::endl;
00280 for (size_t i = 0; i < v.right_finger_pad_forces.size(); ++i)
00281 {
00282 s << indent << " right_finger_pad_forces[" << i << "]: ";
00283 Printer<double>::stream(s, indent + " ", v.right_finger_pad_forces[i]);
00284 }
00285 s << indent << "left_finger_pad_forces_filtered[]" << std::endl;
00286 for (size_t i = 0; i < v.left_finger_pad_forces_filtered.size(); ++i)
00287 {
00288 s << indent << " left_finger_pad_forces_filtered[" << i << "]: ";
00289 Printer<double>::stream(s, indent + " ", v.left_finger_pad_forces_filtered[i]);
00290 }
00291 s << indent << "right_finger_pad_forces_filtered[]" << std::endl;
00292 for (size_t i = 0; i < v.right_finger_pad_forces_filtered.size(); ++i)
00293 {
00294 s << indent << " right_finger_pad_forces_filtered[" << i << "]: ";
00295 Printer<double>::stream(s, indent + " ", v.right_finger_pad_forces_filtered[i]);
00296 }
00297 s << indent << "acc_x_raw: ";
00298 Printer<double>::stream(s, indent + " ", v.acc_x_raw);
00299 s << indent << "acc_y_raw: ";
00300 Printer<double>::stream(s, indent + " ", v.acc_y_raw);
00301 s << indent << "acc_z_raw: ";
00302 Printer<double>::stream(s, indent + " ", v.acc_z_raw);
00303 s << indent << "acc_x_filtered: ";
00304 Printer<double>::stream(s, indent + " ", v.acc_x_filtered);
00305 s << indent << "acc_y_filtered: ";
00306 Printer<double>::stream(s, indent + " ", v.acc_y_filtered);
00307 s << indent << "acc_z_filtered: ";
00308 Printer<double>::stream(s, indent + " ", v.acc_z_filtered);
00309 s << indent << "left_contact: ";
00310 Printer<uint8_t>::stream(s, indent + " ", v.left_contact);
00311 s << indent << "right_contact: ";
00312 Printer<uint8_t>::stream(s, indent + " ", v.right_contact);
00313 }
00314 };
00315
00316
00317 }
00318 }
00319
00320 #endif // PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERSENSORRAWDATA_H
00321