$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_object_manipulation/doc_stacks/2013-03-05_12-10-38.333207/pr2_object_manipulation/manipulation/pr2_gripper_sensor_msgs/msg/PR2GripperSlipServoData.msg */ 00002 #ifndef PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERSLIPSERVODATA_H 00003 #define PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERSLIPSERVODATA_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 #include "pr2_gripper_sensor_msgs/PR2GripperSensorRTState.h" 00018 00019 namespace pr2_gripper_sensor_msgs 00020 { 00021 template <class ContainerAllocator> 00022 struct PR2GripperSlipServoData_ { 00023 typedef PR2GripperSlipServoData_<ContainerAllocator> Type; 00024 00025 PR2GripperSlipServoData_() 00026 : stamp() 00027 , deformation(0.0) 00028 , left_fingertip_pad_force(0.0) 00029 , right_fingertip_pad_force(0.0) 00030 , joint_effort(0.0) 00031 , slip_detected(false) 00032 , deformation_limit_reached(false) 00033 , fingertip_force_limit_reached(false) 00034 , gripper_empty(false) 00035 , rtstate() 00036 { 00037 } 00038 00039 PR2GripperSlipServoData_(const ContainerAllocator& _alloc) 00040 : stamp() 00041 , deformation(0.0) 00042 , left_fingertip_pad_force(0.0) 00043 , right_fingertip_pad_force(0.0) 00044 , joint_effort(0.0) 00045 , slip_detected(false) 00046 , deformation_limit_reached(false) 00047 , fingertip_force_limit_reached(false) 00048 , gripper_empty(false) 00049 , rtstate(_alloc) 00050 { 00051 } 00052 00053 typedef ros::Time _stamp_type; 00054 ros::Time stamp; 00055 00056 typedef double _deformation_type; 00057 double deformation; 00058 00059 typedef double _left_fingertip_pad_force_type; 00060 double left_fingertip_pad_force; 00061 00062 typedef double _right_fingertip_pad_force_type; 00063 double right_fingertip_pad_force; 00064 00065 typedef double _joint_effort_type; 00066 double joint_effort; 00067 00068 typedef uint8_t _slip_detected_type; 00069 uint8_t slip_detected; 00070 00071 typedef uint8_t _deformation_limit_reached_type; 00072 uint8_t deformation_limit_reached; 00073 00074 typedef uint8_t _fingertip_force_limit_reached_type; 00075 uint8_t fingertip_force_limit_reached; 00076 00077 typedef uint8_t _gripper_empty_type; 00078 uint8_t gripper_empty; 00079 00080 typedef ::pr2_gripper_sensor_msgs::PR2GripperSensorRTState_<ContainerAllocator> _rtstate_type; 00081 ::pr2_gripper_sensor_msgs::PR2GripperSensorRTState_<ContainerAllocator> rtstate; 00082 00083 00084 private: 00085 static const char* __s_getDataType_() { return "pr2_gripper_sensor_msgs/PR2GripperSlipServoData"; } 00086 public: 00087 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00088 00089 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00090 00091 private: 00092 static const char* __s_getMD5Sum_() { return "a49728a2e0c40706b3c9b74046f006aa"; } 00093 public: 00094 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00095 00096 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00097 00098 private: 00099 static const char* __s_getMessageDefinition_() { return "# time the data was recorded at\n\ 00100 time stamp\n\ 00101 \n\ 00102 # the amount of deformation from action start (in meters)\n\ 00103 float64 deformation\n\ 00104 \n\ 00105 # the force experinced by the finger Pads (N)\n\ 00106 # NOTE:this ignores data from the edges of the finger pressure\n\ 00107 float64 left_fingertip_pad_force\n\ 00108 float64 right_fingertip_pad_force\n\ 00109 \n\ 00110 # the current virtual parallel joint effort of the gripper (in N)\n\ 00111 float64 joint_effort\n\ 00112 \n\ 00113 # true if the object recently slipped\n\ 00114 bool slip_detected\n\ 00115 \n\ 00116 # true if we are at or exceeding the deformation limit\n\ 00117 # (see wiki page and param server for more info)\n\ 00118 bool deformation_limit_reached\n\ 00119 \n\ 00120 # true if we are at or exceeding our force \n\ 00121 # (see wiki page and param server for more info)\n\ 00122 bool fingertip_force_limit_reached\n\ 00123 \n\ 00124 # true if the controller thinks the gripper is empty\n\ 00125 # (see wiki page for more info)\n\ 00126 bool gripper_empty\n\ 00127 \n\ 00128 # the control state of our realtime controller\n\ 00129 PR2GripperSensorRTState rtstate\n\ 00130 ================================================================================\n\ 00131 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState\n\ 00132 # the control state of our realtime controller\n\ 00133 int8 realtime_controller_state\n\ 00134 \n\ 00135 # predefined values to indicate our realtime_controller_state\n\ 00136 int8 DISABLED = 0\n\ 00137 int8 POSITION_SERVO = 3\n\ 00138 int8 FORCE_SERVO = 4\n\ 00139 int8 FIND_CONTACT = 5\n\ 00140 int8 SLIP_SERVO = 6\n\ 00141 "; } 00142 public: 00143 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00144 00145 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00146 00147 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00148 { 00149 ros::serialization::OStream stream(write_ptr, 1000000000); 00150 ros::serialization::serialize(stream, stamp); 00151 ros::serialization::serialize(stream, deformation); 00152 ros::serialization::serialize(stream, left_fingertip_pad_force); 00153 ros::serialization::serialize(stream, right_fingertip_pad_force); 00154 ros::serialization::serialize(stream, joint_effort); 00155 ros::serialization::serialize(stream, slip_detected); 00156 ros::serialization::serialize(stream, deformation_limit_reached); 00157 ros::serialization::serialize(stream, fingertip_force_limit_reached); 00158 ros::serialization::serialize(stream, gripper_empty); 00159 ros::serialization::serialize(stream, rtstate); 00160 return stream.getData(); 00161 } 00162 00163 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00164 { 00165 ros::serialization::IStream stream(read_ptr, 1000000000); 00166 ros::serialization::deserialize(stream, stamp); 00167 ros::serialization::deserialize(stream, deformation); 00168 ros::serialization::deserialize(stream, left_fingertip_pad_force); 00169 ros::serialization::deserialize(stream, right_fingertip_pad_force); 00170 ros::serialization::deserialize(stream, joint_effort); 00171 ros::serialization::deserialize(stream, slip_detected); 00172 ros::serialization::deserialize(stream, deformation_limit_reached); 00173 ros::serialization::deserialize(stream, fingertip_force_limit_reached); 00174 ros::serialization::deserialize(stream, gripper_empty); 00175 ros::serialization::deserialize(stream, rtstate); 00176 return stream.getData(); 00177 } 00178 00179 ROS_DEPRECATED virtual uint32_t serializationLength() const 00180 { 00181 uint32_t size = 0; 00182 size += ros::serialization::serializationLength(stamp); 00183 size += ros::serialization::serializationLength(deformation); 00184 size += ros::serialization::serializationLength(left_fingertip_pad_force); 00185 size += ros::serialization::serializationLength(right_fingertip_pad_force); 00186 size += ros::serialization::serializationLength(joint_effort); 00187 size += ros::serialization::serializationLength(slip_detected); 00188 size += ros::serialization::serializationLength(deformation_limit_reached); 00189 size += ros::serialization::serializationLength(fingertip_force_limit_reached); 00190 size += ros::serialization::serializationLength(gripper_empty); 00191 size += ros::serialization::serializationLength(rtstate); 00192 return size; 00193 } 00194 00195 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> > Ptr; 00196 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> const> ConstPtr; 00197 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00198 }; // struct PR2GripperSlipServoData 00199 typedef ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<std::allocator<void> > PR2GripperSlipServoData; 00200 00201 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData> PR2GripperSlipServoDataPtr; 00202 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData const> PR2GripperSlipServoDataConstPtr; 00203 00204 00205 template<typename ContainerAllocator> 00206 std::ostream& operator<<(std::ostream& s, const ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> & v) 00207 { 00208 ros::message_operations::Printer< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> >::stream(s, "", v); 00209 return s;} 00210 00211 } // namespace pr2_gripper_sensor_msgs 00212 00213 namespace ros 00214 { 00215 namespace message_traits 00216 { 00217 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> > : public TrueType {}; 00218 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> const> : public TrueType {}; 00219 template<class ContainerAllocator> 00220 struct MD5Sum< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> > { 00221 static const char* value() 00222 { 00223 return "a49728a2e0c40706b3c9b74046f006aa"; 00224 } 00225 00226 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> &) { return value(); } 00227 static const uint64_t static_value1 = 0xa49728a2e0c40706ULL; 00228 static const uint64_t static_value2 = 0xb3c9b74046f006aaULL; 00229 }; 00230 00231 template<class ContainerAllocator> 00232 struct DataType< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> > { 00233 static const char* value() 00234 { 00235 return "pr2_gripper_sensor_msgs/PR2GripperSlipServoData"; 00236 } 00237 00238 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> &) { return value(); } 00239 }; 00240 00241 template<class ContainerAllocator> 00242 struct Definition< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> > { 00243 static const char* value() 00244 { 00245 return "# time the data was recorded at\n\ 00246 time stamp\n\ 00247 \n\ 00248 # the amount of deformation from action start (in meters)\n\ 00249 float64 deformation\n\ 00250 \n\ 00251 # the force experinced by the finger Pads (N)\n\ 00252 # NOTE:this ignores data from the edges of the finger pressure\n\ 00253 float64 left_fingertip_pad_force\n\ 00254 float64 right_fingertip_pad_force\n\ 00255 \n\ 00256 # the current virtual parallel joint effort of the gripper (in N)\n\ 00257 float64 joint_effort\n\ 00258 \n\ 00259 # true if the object recently slipped\n\ 00260 bool slip_detected\n\ 00261 \n\ 00262 # true if we are at or exceeding the deformation limit\n\ 00263 # (see wiki page and param server for more info)\n\ 00264 bool deformation_limit_reached\n\ 00265 \n\ 00266 # true if we are at or exceeding our force \n\ 00267 # (see wiki page and param server for more info)\n\ 00268 bool fingertip_force_limit_reached\n\ 00269 \n\ 00270 # true if the controller thinks the gripper is empty\n\ 00271 # (see wiki page for more info)\n\ 00272 bool gripper_empty\n\ 00273 \n\ 00274 # the control state of our realtime controller\n\ 00275 PR2GripperSensorRTState rtstate\n\ 00276 ================================================================================\n\ 00277 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState\n\ 00278 # the control state of our realtime controller\n\ 00279 int8 realtime_controller_state\n\ 00280 \n\ 00281 # predefined values to indicate our realtime_controller_state\n\ 00282 int8 DISABLED = 0\n\ 00283 int8 POSITION_SERVO = 3\n\ 00284 int8 FORCE_SERVO = 4\n\ 00285 int8 FIND_CONTACT = 5\n\ 00286 int8 SLIP_SERVO = 6\n\ 00287 "; 00288 } 00289 00290 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> &) { return value(); } 00291 }; 00292 00293 template<class ContainerAllocator> struct IsFixedSize< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> > : public TrueType {}; 00294 } // namespace message_traits 00295 } // namespace ros 00296 00297 namespace ros 00298 { 00299 namespace serialization 00300 { 00301 00302 template<class ContainerAllocator> struct Serializer< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> > 00303 { 00304 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00305 { 00306 stream.next(m.stamp); 00307 stream.next(m.deformation); 00308 stream.next(m.left_fingertip_pad_force); 00309 stream.next(m.right_fingertip_pad_force); 00310 stream.next(m.joint_effort); 00311 stream.next(m.slip_detected); 00312 stream.next(m.deformation_limit_reached); 00313 stream.next(m.fingertip_force_limit_reached); 00314 stream.next(m.gripper_empty); 00315 stream.next(m.rtstate); 00316 } 00317 00318 ROS_DECLARE_ALLINONE_SERIALIZER; 00319 }; // struct PR2GripperSlipServoData_ 00320 } // namespace serialization 00321 } // namespace ros 00322 00323 namespace ros 00324 { 00325 namespace message_operations 00326 { 00327 00328 template<class ContainerAllocator> 00329 struct Printer< ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> > 00330 { 00331 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_gripper_sensor_msgs::PR2GripperSlipServoData_<ContainerAllocator> & v) 00332 { 00333 s << indent << "stamp: "; 00334 Printer<ros::Time>::stream(s, indent + " ", v.stamp); 00335 s << indent << "deformation: "; 00336 Printer<double>::stream(s, indent + " ", v.deformation); 00337 s << indent << "left_fingertip_pad_force: "; 00338 Printer<double>::stream(s, indent + " ", v.left_fingertip_pad_force); 00339 s << indent << "right_fingertip_pad_force: "; 00340 Printer<double>::stream(s, indent + " ", v.right_fingertip_pad_force); 00341 s << indent << "joint_effort: "; 00342 Printer<double>::stream(s, indent + " ", v.joint_effort); 00343 s << indent << "slip_detected: "; 00344 Printer<uint8_t>::stream(s, indent + " ", v.slip_detected); 00345 s << indent << "deformation_limit_reached: "; 00346 Printer<uint8_t>::stream(s, indent + " ", v.deformation_limit_reached); 00347 s << indent << "fingertip_force_limit_reached: "; 00348 Printer<uint8_t>::stream(s, indent + " ", v.fingertip_force_limit_reached); 00349 s << indent << "gripper_empty: "; 00350 Printer<uint8_t>::stream(s, indent + " ", v.gripper_empty); 00351 s << indent << "rtstate: "; 00352 s << std::endl; 00353 Printer< ::pr2_gripper_sensor_msgs::PR2GripperSensorRTState_<ContainerAllocator> >::stream(s, indent + " ", v.rtstate); 00354 } 00355 }; 00356 00357 00358 } // namespace message_operations 00359 } // namespace ros 00360 00361 #endif // PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERSLIPSERVODATA_H 00362