$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/PR2GripperEventDetectorGoal.msg */ 00002 #ifndef PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPEREVENTDETECTORGOAL_H 00003 #define PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPEREVENTDETECTORGOAL_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/PR2GripperEventDetectorCommand.h" 00018 00019 namespace pr2_gripper_sensor_msgs 00020 { 00021 template <class ContainerAllocator> 00022 struct PR2GripperEventDetectorGoal_ { 00023 typedef PR2GripperEventDetectorGoal_<ContainerAllocator> Type; 00024 00025 PR2GripperEventDetectorGoal_() 00026 : command() 00027 { 00028 } 00029 00030 PR2GripperEventDetectorGoal_(const ContainerAllocator& _alloc) 00031 : command(_alloc) 00032 { 00033 } 00034 00035 typedef ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorCommand_<ContainerAllocator> _command_type; 00036 ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorCommand_<ContainerAllocator> command; 00037 00038 00039 private: 00040 static const char* __s_getDataType_() { return "pr2_gripper_sensor_msgs/PR2GripperEventDetectorGoal"; } 00041 public: 00042 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00043 00044 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00045 00046 private: 00047 static const char* __s_getMD5Sum_() { return "88b98e578eece7bef53cd48d37d3253b"; } 00048 public: 00049 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00050 00051 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00052 00053 private: 00054 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00055 # Event Detector action used to tell detect events happening on the \n\ 00056 # palm mounted accelerometer and finger pressure sensors\n\ 00057 \n\ 00058 #goal\n\ 00059 PR2GripperEventDetectorCommand command\n\ 00060 \n\ 00061 ================================================================================\n\ 00062 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand\n\ 00063 # state variable that defines what events we would like to trigger on\n\ 00064 # Leaving this field blank will result in the robot triggering when \n\ 00065 # anything touches the sides of the finger or an impact is detected\n\ 00066 # with the hand/arm.\n\ 00067 int8 trigger_conditions\n\ 00068 # definitions for our various trigger_conditions values\n\ 00069 # trigger on either acceleration contact or finger sensor side impact\n\ 00070 int8 FINGER_SIDE_IMPACT_OR_ACC = 0\n\ 00071 # tigger once both slip and acceleration signals occur\n\ 00072 int8 SLIP_AND_ACC = 1 \n\ 00073 # trigger on either slip, acceleration, or finger sensor side impact\n\ 00074 int8 FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC = 2\n\ 00075 # trigger only on slip information\n\ 00076 int8 SLIP = 3\n\ 00077 # trigger only on acceleration contact information\n\ 00078 int8 ACC = 4 \n\ 00079 \n\ 00080 \n\ 00081 # the amount of acceleration to trigger on (acceleration vector magnitude)\n\ 00082 # Units = m/s^2\n\ 00083 # The user needs to be concerned here about not setting the trigger too\n\ 00084 # low so that is set off by the robot's own motions.\n\ 00085 #\n\ 00086 # For large rapid motions, say by a motion planner, 5 m/s^2 is a good level\n\ 00087 # For small delicate controlled motions this can be set MUCH lower (try 2.0)\n\ 00088 #\n\ 00089 # NOTE: When moving the gripper joint (opening/closing the grippr)\n\ 00090 # the high gearing of the PR2 gripper causes large acceleration vibrations\n\ 00091 # which will cause triggering to occur. This is a known drawback of the PR2.\n\ 00092 #\n\ 00093 # NOTE: Leaving this value blank will result in a 0 m/s^2 trigger. If you\n\ 00094 # are using a trigger_conditions value that returns on acceleration contact\n\ 00095 # events then it will immediately exceed your trigger and return\n\ 00096 float64 acceleration_trigger_magnitude\n\ 00097 \n\ 00098 \n\ 00099 # the slip detector gain to trigger on (either finger) : try 0.01\n\ 00100 # higher values decrease slip sensitivty (to a point)\n\ 00101 # lower values increase sensitivity (to a point)\n\ 00102 #\n\ 00103 # NOTE: Leaving this value blank will result in the most sensitive slip level.\n\ 00104 float64 slip_trigger_magnitude\n\ 00105 "; } 00106 public: 00107 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00108 00109 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00110 00111 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00112 { 00113 ros::serialization::OStream stream(write_ptr, 1000000000); 00114 ros::serialization::serialize(stream, command); 00115 return stream.getData(); 00116 } 00117 00118 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00119 { 00120 ros::serialization::IStream stream(read_ptr, 1000000000); 00121 ros::serialization::deserialize(stream, command); 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(command); 00129 return size; 00130 } 00131 00132 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> > Ptr; 00133 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> const> ConstPtr; 00134 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00135 }; // struct PR2GripperEventDetectorGoal 00136 typedef ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<std::allocator<void> > PR2GripperEventDetectorGoal; 00137 00138 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal> PR2GripperEventDetectorGoalPtr; 00139 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal const> PR2GripperEventDetectorGoalConstPtr; 00140 00141 00142 template<typename ContainerAllocator> 00143 std::ostream& operator<<(std::ostream& s, const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> & v) 00144 { 00145 ros::message_operations::Printer< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> >::stream(s, "", v); 00146 return s;} 00147 00148 } // namespace pr2_gripper_sensor_msgs 00149 00150 namespace ros 00151 { 00152 namespace message_traits 00153 { 00154 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> > : public TrueType {}; 00155 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> const> : public TrueType {}; 00156 template<class ContainerAllocator> 00157 struct MD5Sum< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> > { 00158 static const char* value() 00159 { 00160 return "88b98e578eece7bef53cd48d37d3253b"; 00161 } 00162 00163 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> &) { return value(); } 00164 static const uint64_t static_value1 = 0x88b98e578eece7beULL; 00165 static const uint64_t static_value2 = 0xf53cd48d37d3253bULL; 00166 }; 00167 00168 template<class ContainerAllocator> 00169 struct DataType< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> > { 00170 static const char* value() 00171 { 00172 return "pr2_gripper_sensor_msgs/PR2GripperEventDetectorGoal"; 00173 } 00174 00175 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> &) { return value(); } 00176 }; 00177 00178 template<class ContainerAllocator> 00179 struct Definition< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> > { 00180 static const char* value() 00181 { 00182 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00183 # Event Detector action used to tell detect events happening on the \n\ 00184 # palm mounted accelerometer and finger pressure sensors\n\ 00185 \n\ 00186 #goal\n\ 00187 PR2GripperEventDetectorCommand command\n\ 00188 \n\ 00189 ================================================================================\n\ 00190 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand\n\ 00191 # state variable that defines what events we would like to trigger on\n\ 00192 # Leaving this field blank will result in the robot triggering when \n\ 00193 # anything touches the sides of the finger or an impact is detected\n\ 00194 # with the hand/arm.\n\ 00195 int8 trigger_conditions\n\ 00196 # definitions for our various trigger_conditions values\n\ 00197 # trigger on either acceleration contact or finger sensor side impact\n\ 00198 int8 FINGER_SIDE_IMPACT_OR_ACC = 0\n\ 00199 # tigger once both slip and acceleration signals occur\n\ 00200 int8 SLIP_AND_ACC = 1 \n\ 00201 # trigger on either slip, acceleration, or finger sensor side impact\n\ 00202 int8 FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC = 2\n\ 00203 # trigger only on slip information\n\ 00204 int8 SLIP = 3\n\ 00205 # trigger only on acceleration contact information\n\ 00206 int8 ACC = 4 \n\ 00207 \n\ 00208 \n\ 00209 # the amount of acceleration to trigger on (acceleration vector magnitude)\n\ 00210 # Units = m/s^2\n\ 00211 # The user needs to be concerned here about not setting the trigger too\n\ 00212 # low so that is set off by the robot's own motions.\n\ 00213 #\n\ 00214 # For large rapid motions, say by a motion planner, 5 m/s^2 is a good level\n\ 00215 # For small delicate controlled motions this can be set MUCH lower (try 2.0)\n\ 00216 #\n\ 00217 # NOTE: When moving the gripper joint (opening/closing the grippr)\n\ 00218 # the high gearing of the PR2 gripper causes large acceleration vibrations\n\ 00219 # which will cause triggering to occur. This is a known drawback of the PR2.\n\ 00220 #\n\ 00221 # NOTE: Leaving this value blank will result in a 0 m/s^2 trigger. If you\n\ 00222 # are using a trigger_conditions value that returns on acceleration contact\n\ 00223 # events then it will immediately exceed your trigger and return\n\ 00224 float64 acceleration_trigger_magnitude\n\ 00225 \n\ 00226 \n\ 00227 # the slip detector gain to trigger on (either finger) : try 0.01\n\ 00228 # higher values decrease slip sensitivty (to a point)\n\ 00229 # lower values increase sensitivity (to a point)\n\ 00230 #\n\ 00231 # NOTE: Leaving this value blank will result in the most sensitive slip level.\n\ 00232 float64 slip_trigger_magnitude\n\ 00233 "; 00234 } 00235 00236 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> &) { return value(); } 00237 }; 00238 00239 template<class ContainerAllocator> struct IsFixedSize< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> > : public TrueType {}; 00240 } // namespace message_traits 00241 } // namespace ros 00242 00243 namespace ros 00244 { 00245 namespace serialization 00246 { 00247 00248 template<class ContainerAllocator> struct Serializer< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> > 00249 { 00250 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00251 { 00252 stream.next(m.command); 00253 } 00254 00255 ROS_DECLARE_ALLINONE_SERIALIZER; 00256 }; // struct PR2GripperEventDetectorGoal_ 00257 } // namespace serialization 00258 } // namespace ros 00259 00260 namespace ros 00261 { 00262 namespace message_operations 00263 { 00264 00265 template<class ContainerAllocator> 00266 struct Printer< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> > 00267 { 00268 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal_<ContainerAllocator> & v) 00269 { 00270 s << indent << "command: "; 00271 s << std::endl; 00272 Printer< ::pr2_gripper_sensor_msgs::PR2GripperEventDetectorCommand_<ContainerAllocator> >::stream(s, indent + " ", v.command); 00273 } 00274 }; 00275 00276 00277 } // namespace message_operations 00278 } // namespace ros 00279 00280 #endif // PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPEREVENTDETECTORGOAL_H 00281