Go to the documentation of this file.00001
00002 #ifndef PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERFORCESERVOACTION_H
00003 #define PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERFORCESERVOACTION_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/PR2GripperForceServoActionGoal.h"
00018 #include "pr2_gripper_sensor_msgs/PR2GripperForceServoActionResult.h"
00019 #include "pr2_gripper_sensor_msgs/PR2GripperForceServoActionFeedback.h"
00020
00021 namespace pr2_gripper_sensor_msgs
00022 {
00023 template <class ContainerAllocator>
00024 struct PR2GripperForceServoAction_ {
00025 typedef PR2GripperForceServoAction_<ContainerAllocator> Type;
00026
00027 PR2GripperForceServoAction_()
00028 : action_goal()
00029 , action_result()
00030 , action_feedback()
00031 {
00032 }
00033
00034 PR2GripperForceServoAction_(const ContainerAllocator& _alloc)
00035 : action_goal(_alloc)
00036 , action_result(_alloc)
00037 , action_feedback(_alloc)
00038 {
00039 }
00040
00041 typedef ::pr2_gripper_sensor_msgs::PR2GripperForceServoActionGoal_<ContainerAllocator> _action_goal_type;
00042 ::pr2_gripper_sensor_msgs::PR2GripperForceServoActionGoal_<ContainerAllocator> action_goal;
00043
00044 typedef ::pr2_gripper_sensor_msgs::PR2GripperForceServoActionResult_<ContainerAllocator> _action_result_type;
00045 ::pr2_gripper_sensor_msgs::PR2GripperForceServoActionResult_<ContainerAllocator> action_result;
00046
00047 typedef ::pr2_gripper_sensor_msgs::PR2GripperForceServoActionFeedback_<ContainerAllocator> _action_feedback_type;
00048 ::pr2_gripper_sensor_msgs::PR2GripperForceServoActionFeedback_<ContainerAllocator> action_feedback;
00049
00050
00051 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> > Ptr;
00052 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> const> ConstPtr;
00053 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00054 };
00055 typedef ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<std::allocator<void> > PR2GripperForceServoAction;
00056
00057 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction> PR2GripperForceServoActionPtr;
00058 typedef boost::shared_ptr< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction const> PR2GripperForceServoActionConstPtr;
00059
00060
00061 template<typename ContainerAllocator>
00062 std::ostream& operator<<(std::ostream& s, const ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> & v)
00063 {
00064 ros::message_operations::Printer< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> >::stream(s, "", v);
00065 return s;}
00066
00067 }
00068
00069 namespace ros
00070 {
00071 namespace message_traits
00072 {
00073 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> > : public TrueType {};
00074 template<class ContainerAllocator> struct IsMessage< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> const> : public TrueType {};
00075 template<class ContainerAllocator>
00076 struct MD5Sum< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> > {
00077 static const char* value()
00078 {
00079 return "0540bb7603e65b3df5c9dc87b150e790";
00080 }
00081
00082 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> &) { return value(); }
00083 static const uint64_t static_value1 = 0x0540bb7603e65b3dULL;
00084 static const uint64_t static_value2 = 0xf5c9dc87b150e790ULL;
00085 };
00086
00087 template<class ContainerAllocator>
00088 struct DataType< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> > {
00089 static const char* value()
00090 {
00091 return "pr2_gripper_sensor_msgs/PR2GripperForceServoAction";
00092 }
00093
00094 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> &) { return value(); }
00095 };
00096
00097 template<class ContainerAllocator>
00098 struct Definition< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> > {
00099 static const char* value()
00100 {
00101 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00102 \n\
00103 PR2GripperForceServoActionGoal action_goal\n\
00104 PR2GripperForceServoActionResult action_result\n\
00105 PR2GripperForceServoActionFeedback action_feedback\n\
00106 \n\
00107 ================================================================================\n\
00108 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoActionGoal\n\
00109 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00110 \n\
00111 Header header\n\
00112 actionlib_msgs/GoalID goal_id\n\
00113 PR2GripperForceServoGoal goal\n\
00114 \n\
00115 ================================================================================\n\
00116 MSG: std_msgs/Header\n\
00117 # Standard metadata for higher-level stamped data types.\n\
00118 # This is generally used to communicate timestamped data \n\
00119 # in a particular coordinate frame.\n\
00120 # \n\
00121 # sequence ID: consecutively increasing ID \n\
00122 uint32 seq\n\
00123 #Two-integer timestamp that is expressed as:\n\
00124 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00125 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00126 # time-handling sugar is provided by the client library\n\
00127 time stamp\n\
00128 #Frame this data is associated with\n\
00129 # 0: no frame\n\
00130 # 1: global frame\n\
00131 string frame_id\n\
00132 \n\
00133 ================================================================================\n\
00134 MSG: actionlib_msgs/GoalID\n\
00135 # The stamp should store the time at which this goal was requested.\n\
00136 # It is used by an action server when it tries to preempt all\n\
00137 # goals that were requested before a certain time\n\
00138 time stamp\n\
00139 \n\
00140 # The id provides a way to associate feedback and\n\
00141 # result message with specific goal requests. The id\n\
00142 # specified must be unique.\n\
00143 string id\n\
00144 \n\
00145 \n\
00146 ================================================================================\n\
00147 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoGoal\n\
00148 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00149 # Action to launch the gripper into force servoing mode \n\
00150 \n\
00151 #goals\n\
00152 PR2GripperForceServoCommand command\n\
00153 \n\
00154 ================================================================================\n\
00155 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoCommand\n\
00156 # the amount of fingertip force (in Newtons) to apply.\n\
00157 # NOTE: the joint will squeeze until each finger reaches this level\n\
00158 # values < 0 (opening force) are ignored\n\
00159 #\n\
00160 # 10 N can crack an egg or crush a soda can.\n\
00161 # 15 N can firmly pick up a can of soup.\n\
00162 # Experiment on your own.\n\
00163 #\n\
00164 float64 fingertip_force\n\
00165 ================================================================================\n\
00166 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoActionResult\n\
00167 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00168 \n\
00169 Header header\n\
00170 actionlib_msgs/GoalStatus status\n\
00171 PR2GripperForceServoResult result\n\
00172 \n\
00173 ================================================================================\n\
00174 MSG: actionlib_msgs/GoalStatus\n\
00175 GoalID goal_id\n\
00176 uint8 status\n\
00177 uint8 PENDING = 0 # The goal has yet to be processed by the action server\n\
00178 uint8 ACTIVE = 1 # The goal is currently being processed by the action server\n\
00179 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing\n\
00180 # and has since completed its execution (Terminal State)\n\
00181 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)\n\
00182 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due\n\
00183 # to some failure (Terminal State)\n\
00184 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,\n\
00185 # because the goal was unattainable or invalid (Terminal State)\n\
00186 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing\n\
00187 # and has not yet completed execution\n\
00188 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,\n\
00189 # but the action server has not yet confirmed that the goal is canceled\n\
00190 uint8 RECALLED = 8 # The goal received a cancel request before it started executing\n\
00191 # and was successfully cancelled (Terminal State)\n\
00192 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be\n\
00193 # sent over the wire by an action server\n\
00194 \n\
00195 #Allow for the user to associate a string with GoalStatus for debugging\n\
00196 string text\n\
00197 \n\
00198 \n\
00199 ================================================================================\n\
00200 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoResult\n\
00201 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00202 \n\
00203 #result\n\
00204 PR2GripperForceServoData data\n\
00205 \n\
00206 \n\
00207 ================================================================================\n\
00208 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoData\n\
00209 # Time the data was recorded at\n\
00210 time stamp\n\
00211 \n\
00212 # the force experienced by the finger Pads (N)\n\
00213 # NOTE:this ignores data from the edges of the finger pressure\n\
00214 float64 left_fingertip_pad_force\n\
00215 float64 right_fingertip_pad_force\n\
00216 \n\
00217 # the current gripper virtual parallel joint effort (in N)\n\
00218 float64 joint_effort\n\
00219 \n\
00220 # true when the gripper is no longer moving\n\
00221 # and we have reached the desired force level\n\
00222 bool force_achieved\n\
00223 \n\
00224 \n\
00225 # the control state of our realtime controller\n\
00226 PR2GripperSensorRTState rtstate\n\
00227 \n\
00228 ================================================================================\n\
00229 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState\n\
00230 # the control state of our realtime controller\n\
00231 int8 realtime_controller_state\n\
00232 \n\
00233 # predefined values to indicate our realtime_controller_state\n\
00234 int8 DISABLED = 0\n\
00235 int8 POSITION_SERVO = 3\n\
00236 int8 FORCE_SERVO = 4\n\
00237 int8 FIND_CONTACT = 5\n\
00238 int8 SLIP_SERVO = 6\n\
00239 ================================================================================\n\
00240 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoActionFeedback\n\
00241 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00242 \n\
00243 Header header\n\
00244 actionlib_msgs/GoalStatus status\n\
00245 PR2GripperForceServoFeedback feedback\n\
00246 \n\
00247 ================================================================================\n\
00248 MSG: pr2_gripper_sensor_msgs/PR2GripperForceServoFeedback\n\
00249 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00250 \n\
00251 #feedback\n\
00252 PR2GripperForceServoData data\n\
00253 \n\
00254 ";
00255 }
00256
00257 static const char* value(const ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> &) { return value(); }
00258 };
00259
00260 }
00261 }
00262
00263 namespace ros
00264 {
00265 namespace serialization
00266 {
00267
00268 template<class ContainerAllocator> struct Serializer< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> >
00269 {
00270 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00271 {
00272 stream.next(m.action_goal);
00273 stream.next(m.action_result);
00274 stream.next(m.action_feedback);
00275 }
00276
00277 ROS_DECLARE_ALLINONE_SERIALIZER;
00278 };
00279 }
00280 }
00281
00282 namespace ros
00283 {
00284 namespace message_operations
00285 {
00286
00287 template<class ContainerAllocator>
00288 struct Printer< ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> >
00289 {
00290 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_gripper_sensor_msgs::PR2GripperForceServoAction_<ContainerAllocator> & v)
00291 {
00292 s << indent << "action_goal: ";
00293 s << std::endl;
00294 Printer< ::pr2_gripper_sensor_msgs::PR2GripperForceServoActionGoal_<ContainerAllocator> >::stream(s, indent + " ", v.action_goal);
00295 s << indent << "action_result: ";
00296 s << std::endl;
00297 Printer< ::pr2_gripper_sensor_msgs::PR2GripperForceServoActionResult_<ContainerAllocator> >::stream(s, indent + " ", v.action_result);
00298 s << indent << "action_feedback: ";
00299 s << std::endl;
00300 Printer< ::pr2_gripper_sensor_msgs::PR2GripperForceServoActionFeedback_<ContainerAllocator> >::stream(s, indent + " ", v.action_feedback);
00301 }
00302 };
00303
00304
00305 }
00306 }
00307
00308 #endif // PR2_GRIPPER_SENSOR_MSGS_MESSAGE_PR2GRIPPERFORCESERVOACTION_H
00309