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