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 ROS_DEPRECATED uint32_t get_left_finger_pad_forces_size() const { return (uint32_t)left_finger_pad_forces.size(); }
00127 ROS_DEPRECATED uint32_t get_right_finger_pad_forces_size() const { return (uint32_t)right_finger_pad_forces.size(); }
00128 ROS_DEPRECATED uint32_t get_left_finger_pad_forces_filtered_size() const { return (uint32_t)left_finger_pad_forces_filtered.size(); }
00129 ROS_DEPRECATED uint32_t get_right_finger_pad_forces_filtered_size() const { return (uint32_t)right_finger_pad_forces_filtered.size(); }
00130 private:
00131 static const char* __s_getDataType_() { return "pr2_gripper_sensor_msgs/PR2GripperSensorRawData"; }
00132 public:
00133 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00134
00135 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00136
00137 private:
00138 static const char* __s_getMD5Sum_() { return "696a1f2e6969deb0bc6998636ae1b17e"; }
00139 public:
00140 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00141
00142 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00143
00144 private:
00145 static const char* __s_getMessageDefinition_() { return "# NOTE: This message is only for debugging purposes. It is not intended for API usage - and is not published under release code.\n\
00146 \n\
00147 # Standard ROS header\n\
00148 time stamp\n\
00149 \n\
00150 # corrected for zero contact\n\
00151 float64 left_finger_pad_force\n\
00152 float64 right_finger_pad_force\n\
00153 \n\
00154 # filtered values : high pass filter at 5 Hz after correcting for zero contact\n\
00155 float64 left_finger_pad_force_filtered\n\
00156 float64 right_finger_pad_force_filtered\n\
00157 \n\
00158 # corrected for zero contact\n\
00159 float64[22] left_finger_pad_forces\n\
00160 float64[22] right_finger_pad_forces\n\
00161 \n\
00162 # filtered values : high pass filter at 5 Hz after correcting for zero contact\n\
00163 float64[22] left_finger_pad_forces_filtered\n\
00164 float64[22] right_finger_pad_forces_filtered\n\
00165 \n\
00166 # raw acceleration values\n\
00167 float64 acc_x_raw\n\
00168 float64 acc_y_raw\n\
00169 float64 acc_z_raw\n\
00170 \n\
00171 # filtered acceleration values\n\
00172 float64 acc_x_filtered\n\
00173 float64 acc_y_filtered\n\
00174 float64 acc_z_filtered\n\
00175 \n\
00176 # boolean variables indicating whether contact exists or not\n\
00177 bool left_contact\n\
00178 bool right_contact\n\
00179 "; }
00180 public:
00181 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00182
00183 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00184
00185 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00186 {
00187 ros::serialization::OStream stream(write_ptr, 1000000000);
00188 ros::serialization::serialize(stream, stamp);
00189 ros::serialization::serialize(stream, left_finger_pad_force);
00190 ros::serialization::serialize(stream, right_finger_pad_force);
00191 ros::serialization::serialize(stream, left_finger_pad_force_filtered);
00192 ros::serialization::serialize(stream, right_finger_pad_force_filtered);
00193 ros::serialization::serialize(stream, left_finger_pad_forces);
00194 ros::serialization::serialize(stream, right_finger_pad_forces);
00195 ros::serialization::serialize(stream, left_finger_pad_forces_filtered);
00196 ros::serialization::serialize(stream, right_finger_pad_forces_filtered);
00197 ros::serialization::serialize(stream, acc_x_raw);
00198 ros::serialization::serialize(stream, acc_y_raw);
00199 ros::serialization::serialize(stream, acc_z_raw);
00200 ros::serialization::serialize(stream, acc_x_filtered);
00201 ros::serialization::serialize(stream, acc_y_filtered);
00202 ros::serialization::serialize(stream, acc_z_filtered);
00203 ros::serialization::serialize(stream, left_contact);
00204 ros::serialization::serialize(stream, right_contact);
00205 return stream.getData();
00206 }
00207
00208 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00209 {
00210 ros::serialization::IStream stream(read_ptr, 1000000000);
00211 ros::serialization::deserialize(stream, stamp);
00212 ros::serialization::deserialize(stream, left_finger_pad_force);
00213 ros::serialization::deserialize(stream, right_finger_pad_force);
00214 ros::serialization::deserialize(stream, left_finger_pad_force_filtered);
00215 ros::serialization::deserialize(stream, right_finger_pad_force_filtered);
00216 ros::serialization::deserialize(stream, left_finger_pad_forces);
00217 ros::serialization::deserialize(stream, right_finger_pad_forces);
00218 ros::serialization::deserialize(stream, left_finger_pad_forces_filtered);
00219 ros::serialization::deserialize(stream, right_finger_pad_forces_filtered);
00220 ros::serialization::deserialize(stream, acc_x_raw);
00221 ros::serialization::deserialize(stream, acc_y_raw);
00222 ros::serialization::deserialize(stream, acc_z_raw);
00223 ros::serialization::deserialize(stream, acc_x_filtered);
00224 ros::serialization::deserialize(stream, acc_y_filtered);
00225 ros::serialization::deserialize(stream, acc_z_filtered);
00226 ros::serialization::deserialize(stream, left_contact);
00227 ros::serialization::deserialize(stream, right_contact);
00228 return stream.getData();
00229 }
00230
00231 ROS_DEPRECATED virtual uint32_t serializationLength() const
00232 {
00233 uint32_t size = 0;
00234 size += ros::serialization::serializationLength(stamp);
00235 size += ros::serialization::serializationLength(left_finger_pad_force);
00236 size += ros::serialization::serializationLength(right_finger_pad_force);
00237 size += ros::serialization::serializationLength(left_finger_pad_force_filtered);
00238 size += ros::serialization::serializationLength(right_finger_pad_force_filtered);
00239 size += ros::serialization::serializationLength(left_finger_pad_forces);
00240 size += ros::serialization::serializationLength(right_finger_pad_forces);
00241 size += ros::serialization::serializationLength(left_finger_pad_forces_filtered);
00242 size += ros::serialization::serializationLength(right_finger_pad_forces_filtered);
00243 size += ros::serialization::serializationLength(acc_x_raw);
00244 size += ros::serialization::serializationLength(acc_y_raw);
00245 size += ros::serialization::serializationLength(acc_z_raw);
00246 size += ros::serialization::serializationLength(acc_x_filtered);
00247 size += ros::serialization::serializationLength(acc_y_filtered);
00248 size += ros::serialization::serializationLength(acc_z_filtered);
00249 size += ros::serialization::serializationLength(left_contact);
00250 size += ros::serialization::serializationLength(right_contact);
00251 return size;
00252 }
00253
00254 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > Ptr;
00255 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> const> ConstPtr;
00256 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00257 };
00258 typedef ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<std::allocator<void> > PR2GripperSensorRawData;
00259
00260 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData> PR2GripperSensorRawDataPtr;
00261 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData const> PR2GripperSensorRawDataConstPtr;
00262
00263
00264 template<typename ContainerAllocator>
00265 std::ostream& operator<<(std::ostream& s, const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> & v)
00266 {
00267 ros::message_operations::Printer< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> >::stream(s, "", v);
00268 return s;}
00269
00270 }
00271
00272 namespace ros
00273 {
00274 namespace message_traits
00275 {
00276 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > : public TrueType {};
00277 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> const> : public TrueType {};
00278 template<class ContainerAllocator>
00279 struct MD5Sum< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > {
00280 static const char* value()
00281 {
00282 return "696a1f2e6969deb0bc6998636ae1b17e";
00283 }
00284
00285 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> &) { return value(); }
00286 static const uint64_t static_value1 = 0x696a1f2e6969deb0ULL;
00287 static const uint64_t static_value2 = 0xbc6998636ae1b17eULL;
00288 };
00289
00290 template<class ContainerAllocator>
00291 struct DataType< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > {
00292 static const char* value()
00293 {
00294 return "pr2_gripper_sensor_msgs/PR2GripperSensorRawData";
00295 }
00296
00297 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> &) { return value(); }
00298 };
00299
00300 template<class ContainerAllocator>
00301 struct Definition< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > {
00302 static const char* value()
00303 {
00304 return "# NOTE: This message is only for debugging purposes. It is not intended for API usage - and is not published under release code.\n\
00305 \n\
00306 # Standard ROS header\n\
00307 time stamp\n\
00308 \n\
00309 # corrected for zero contact\n\
00310 float64 left_finger_pad_force\n\
00311 float64 right_finger_pad_force\n\
00312 \n\
00313 # filtered values : high pass filter at 5 Hz after correcting for zero contact\n\
00314 float64 left_finger_pad_force_filtered\n\
00315 float64 right_finger_pad_force_filtered\n\
00316 \n\
00317 # corrected for zero contact\n\
00318 float64[22] left_finger_pad_forces\n\
00319 float64[22] right_finger_pad_forces\n\
00320 \n\
00321 # filtered values : high pass filter at 5 Hz after correcting for zero contact\n\
00322 float64[22] left_finger_pad_forces_filtered\n\
00323 float64[22] right_finger_pad_forces_filtered\n\
00324 \n\
00325 # raw acceleration values\n\
00326 float64 acc_x_raw\n\
00327 float64 acc_y_raw\n\
00328 float64 acc_z_raw\n\
00329 \n\
00330 # filtered acceleration values\n\
00331 float64 acc_x_filtered\n\
00332 float64 acc_y_filtered\n\
00333 float64 acc_z_filtered\n\
00334 \n\
00335 # boolean variables indicating whether contact exists or not\n\
00336 bool left_contact\n\
00337 bool right_contact\n\
00338 ";
00339 }
00340
00341 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> &) { return value(); }
00342 };
00343
00344 template<class ContainerAllocator> struct IsFixedSize< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> > : public TrueType {};
00345 }
00346 }
00347
00348 namespace ros
00349 {
00350 namespace serialization
00351 {
00352
00353 template<class ContainerAllocator> struct Serializer< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> >
00354 {
00355 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00356 {
00357 stream.next(m.stamp);
00358 stream.next(m.left_finger_pad_force);
00359 stream.next(m.right_finger_pad_force);
00360 stream.next(m.left_finger_pad_force_filtered);
00361 stream.next(m.right_finger_pad_force_filtered);
00362 stream.next(m.left_finger_pad_forces);
00363 stream.next(m.right_finger_pad_forces);
00364 stream.next(m.left_finger_pad_forces_filtered);
00365 stream.next(m.right_finger_pad_forces_filtered);
00366 stream.next(m.acc_x_raw);
00367 stream.next(m.acc_y_raw);
00368 stream.next(m.acc_z_raw);
00369 stream.next(m.acc_x_filtered);
00370 stream.next(m.acc_y_filtered);
00371 stream.next(m.acc_z_filtered);
00372 stream.next(m.left_contact);
00373 stream.next(m.right_contact);
00374 }
00375
00376 ROS_DECLARE_ALLINONE_SERIALIZER;
00377 };
00378 }
00379 }
00380
00381 namespace ros
00382 {
00383 namespace message_operations
00384 {
00385
00386 template<class ContainerAllocator>
00387 struct Printer< ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> >
00388 {
00389 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_gripper_sensor_msgs::PR2GripperSensorRawData_<ContainerAllocator> & v)
00390 {
00391 s << indent << "stamp: ";
00392 Printer<ros::Time>::stream(s, indent + " ", v.stamp);
00393 s << indent << "left_finger_pad_force: ";
00394 Printer<double>::stream(s, indent + " ", v.left_finger_pad_force);
00395 s << indent << "right_finger_pad_force: ";
00396 Printer<double>::stream(s, indent + " ", v.right_finger_pad_force);
00397 s << indent << "left_finger_pad_force_filtered: ";
00398 Printer<double>::stream(s, indent + " ", v.left_finger_pad_force_filtered);
00399 s << indent << "right_finger_pad_force_filtered: ";
00400 Printer<double>::stream(s, indent + " ", v.right_finger_pad_force_filtered);
00401 s << indent << "left_finger_pad_forces[]" << std::endl;
00402 for (size_t i = 0; i < v.left_finger_pad_forces.size(); ++i)
00403 {
00404 s << indent << " left_finger_pad_forces[" << i << "]: ";
00405 Printer<double>::stream(s, indent + " ", v.left_finger_pad_forces[i]);
00406 }
00407 s << indent << "right_finger_pad_forces[]" << std::endl;
00408 for (size_t i = 0; i < v.right_finger_pad_forces.size(); ++i)
00409 {
00410 s << indent << " right_finger_pad_forces[" << i << "]: ";
00411 Printer<double>::stream(s, indent + " ", v.right_finger_pad_forces[i]);
00412 }
00413 s << indent << "left_finger_pad_forces_filtered[]" << std::endl;
00414 for (size_t i = 0; i < v.left_finger_pad_forces_filtered.size(); ++i)
00415 {
00416 s << indent << " left_finger_pad_forces_filtered[" << i << "]: ";
00417 Printer<double>::stream(s, indent + " ", v.left_finger_pad_forces_filtered[i]);
00418 }
00419 s << indent << "right_finger_pad_forces_filtered[]" << std::endl;
00420 for (size_t i = 0; i < v.right_finger_pad_forces_filtered.size(); ++i)
00421 {
00422 s << indent << " right_finger_pad_forces_filtered[" << i << "]: ";
00423 Printer<double>::stream(s, indent + " ", v.right_finger_pad_forces_filtered[i]);
00424 }
00425 s << indent << "acc_x_raw: ";
00426 Printer<double>::stream(s, indent + " ", v.acc_x_raw);
00427 s << indent << "acc_y_raw: ";
00428 Printer<double>::stream(s, indent + " ", v.acc_y_raw);
00429 s << indent << "acc_z_raw: ";
00430 Printer<double>::stream(s, indent + " ", v.acc_z_raw);
00431 s << indent << "acc_x_filtered: ";
00432 Printer<double>::stream(s, indent + " ", v.acc_x_filtered);
00433 s << indent << "acc_y_filtered: ";
00434 Printer<double>::stream(s, indent + " ", v.acc_y_filtered);
00435 s << indent << "acc_z_filtered: ";
00436 Printer<double>::stream(s, indent + " ", v.acc_z_filtered);
00437 s << indent << "left_contact: ";
00438 Printer<uint8_t>::stream(s, indent + " ", v.left_contact);
00439 s << indent << "right_contact: ";
00440 Printer<uint8_t>::stream(s, indent + " ", v.right_contact);
00441 }
00442 };
00443
00444
00445 }
00446 }
00447
00448 #endif // PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERSENSORRAWDATA_H
00449