$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-mit-ros-pkg/doc_stacks/2013-03-03_11-36-56.162166/mit-ros-pkg/ee_cart_imped/ee_cart_imped_msgs/msg/EECartImpedFeedback.msg */ 00002 #ifndef EE_CART_IMPED_MSGS_MESSAGE_EECARTIMPEDFEEDBACK_H 00003 #define EE_CART_IMPED_MSGS_MESSAGE_EECARTIMPEDFEEDBACK_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 "std_msgs/Header.h" 00018 #include "ee_cart_imped_msgs/StiffPoint.h" 00019 #include "ee_cart_imped_msgs/StiffPoint.h" 00020 #include "ee_cart_imped_msgs/StiffPoint.h" 00021 #include "ee_cart_imped_msgs/StiffPoint.h" 00022 00023 namespace ee_cart_imped_msgs 00024 { 00025 template <class ContainerAllocator> 00026 struct EECartImpedFeedback_ { 00027 typedef EECartImpedFeedback_<ContainerAllocator> Type; 00028 00029 EECartImpedFeedback_() 00030 : header() 00031 , goal() 00032 , initial_point() 00033 , desired() 00034 , actual_pose() 00035 , effort_sq_error(0.0) 00036 , requested_joint_efforts() 00037 , actual_joint_efforts() 00038 , running_time() 00039 { 00040 } 00041 00042 EECartImpedFeedback_(const ContainerAllocator& _alloc) 00043 : header(_alloc) 00044 , goal(_alloc) 00045 , initial_point(_alloc) 00046 , desired(_alloc) 00047 , actual_pose(_alloc) 00048 , effort_sq_error(0.0) 00049 , requested_joint_efforts(_alloc) 00050 , actual_joint_efforts(_alloc) 00051 , running_time() 00052 { 00053 } 00054 00055 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00056 ::std_msgs::Header_<ContainerAllocator> header; 00057 00058 typedef std::vector< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> >::other > _goal_type; 00059 std::vector< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> >::other > goal; 00060 00061 typedef ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> _initial_point_type; 00062 ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> initial_point; 00063 00064 typedef ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> _desired_type; 00065 ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> desired; 00066 00067 typedef ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> _actual_pose_type; 00068 ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> actual_pose; 00069 00070 typedef double _effort_sq_error_type; 00071 double effort_sq_error; 00072 00073 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _requested_joint_efforts_type; 00074 std::vector<double, typename ContainerAllocator::template rebind<double>::other > requested_joint_efforts; 00075 00076 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _actual_joint_efforts_type; 00077 std::vector<double, typename ContainerAllocator::template rebind<double>::other > actual_joint_efforts; 00078 00079 typedef ros::Duration _running_time_type; 00080 ros::Duration running_time; 00081 00082 00083 ROS_DEPRECATED uint32_t get_goal_size() const { return (uint32_t)goal.size(); } 00084 ROS_DEPRECATED void set_goal_size(uint32_t size) { goal.resize((size_t)size); } 00085 ROS_DEPRECATED void get_goal_vec(std::vector< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> >::other > & vec) const { vec = this->goal; } 00086 ROS_DEPRECATED void set_goal_vec(const std::vector< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> >::other > & vec) { this->goal = vec; } 00087 ROS_DEPRECATED uint32_t get_requested_joint_efforts_size() const { return (uint32_t)requested_joint_efforts.size(); } 00088 ROS_DEPRECATED void set_requested_joint_efforts_size(uint32_t size) { requested_joint_efforts.resize((size_t)size); } 00089 ROS_DEPRECATED void get_requested_joint_efforts_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->requested_joint_efforts; } 00090 ROS_DEPRECATED void set_requested_joint_efforts_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->requested_joint_efforts = vec; } 00091 ROS_DEPRECATED uint32_t get_actual_joint_efforts_size() const { return (uint32_t)actual_joint_efforts.size(); } 00092 ROS_DEPRECATED void set_actual_joint_efforts_size(uint32_t size) { actual_joint_efforts.resize((size_t)size); } 00093 ROS_DEPRECATED void get_actual_joint_efforts_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->actual_joint_efforts; } 00094 ROS_DEPRECATED void set_actual_joint_efforts_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->actual_joint_efforts = vec; } 00095 private: 00096 static const char* __s_getDataType_() { return "ee_cart_imped_msgs/EECartImpedFeedback"; } 00097 public: 00098 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00099 00100 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00101 00102 private: 00103 static const char* __s_getMD5Sum_() { return "4106b02683301dac2003809bdf610591"; } 00104 public: 00105 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00106 00107 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00108 00109 private: 00110 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00111 #feedback\n\ 00112 #current pose and squared error in force \n\ 00113 #and the running time of this goal so far\n\ 00114 Header header\n\ 00115 ee_cart_imped_msgs/StiffPoint[] goal\n\ 00116 ee_cart_imped_msgs/StiffPoint initial_point\n\ 00117 ee_cart_imped_msgs/StiffPoint desired\n\ 00118 ee_cart_imped_msgs/StiffPoint actual_pose\n\ 00119 float64 effort_sq_error\n\ 00120 float64[] requested_joint_efforts\n\ 00121 float64[] actual_joint_efforts\n\ 00122 duration running_time\n\ 00123 \n\ 00124 \n\ 00125 \n\ 00126 ================================================================================\n\ 00127 MSG: std_msgs/Header\n\ 00128 # Standard metadata for higher-level stamped data types.\n\ 00129 # This is generally used to communicate timestamped data \n\ 00130 # in a particular coordinate frame.\n\ 00131 # \n\ 00132 # sequence ID: consecutively increasing ID \n\ 00133 uint32 seq\n\ 00134 #Two-integer timestamp that is expressed as:\n\ 00135 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00136 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00137 # time-handling sugar is provided by the client library\n\ 00138 time stamp\n\ 00139 #Frame this data is associated with\n\ 00140 # 0: no frame\n\ 00141 # 1: global frame\n\ 00142 string frame_id\n\ 00143 \n\ 00144 ================================================================================\n\ 00145 MSG: ee_cart_imped_msgs/StiffPoint\n\ 00146 Header header\n\ 00147 #The pose to achieve in the stiffness directions\n\ 00148 geometry_msgs/Pose pose\n\ 00149 #Wrench or stiffness for each dimension\n\ 00150 geometry_msgs/Wrench wrench_or_stiffness\n\ 00151 #The following are True if a force/torque should\n\ 00152 #be exerted and False if a stiffness should be used.\n\ 00153 bool isForceX\n\ 00154 bool isForceY\n\ 00155 bool isForceZ\n\ 00156 bool isTorqueX\n\ 00157 bool isTorqueY\n\ 00158 bool isTorqueZ\n\ 00159 #The time from the start of the trajectory that this\n\ 00160 #point should be achieved.\n\ 00161 duration time_from_start\n\ 00162 ================================================================================\n\ 00163 MSG: geometry_msgs/Pose\n\ 00164 # A representation of pose in free space, composed of postion and orientation. \n\ 00165 Point position\n\ 00166 Quaternion orientation\n\ 00167 \n\ 00168 ================================================================================\n\ 00169 MSG: geometry_msgs/Point\n\ 00170 # This contains the position of a point in free space\n\ 00171 float64 x\n\ 00172 float64 y\n\ 00173 float64 z\n\ 00174 \n\ 00175 ================================================================================\n\ 00176 MSG: geometry_msgs/Quaternion\n\ 00177 # This represents an orientation in free space in quaternion form.\n\ 00178 \n\ 00179 float64 x\n\ 00180 float64 y\n\ 00181 float64 z\n\ 00182 float64 w\n\ 00183 \n\ 00184 ================================================================================\n\ 00185 MSG: geometry_msgs/Wrench\n\ 00186 # This represents force in free space, seperated into \n\ 00187 # it's linear and angular parts. \n\ 00188 Vector3 force\n\ 00189 Vector3 torque\n\ 00190 \n\ 00191 ================================================================================\n\ 00192 MSG: geometry_msgs/Vector3\n\ 00193 # This represents a vector in free space. \n\ 00194 \n\ 00195 float64 x\n\ 00196 float64 y\n\ 00197 float64 z\n\ 00198 "; } 00199 public: 00200 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00201 00202 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00203 00204 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00205 { 00206 ros::serialization::OStream stream(write_ptr, 1000000000); 00207 ros::serialization::serialize(stream, header); 00208 ros::serialization::serialize(stream, goal); 00209 ros::serialization::serialize(stream, initial_point); 00210 ros::serialization::serialize(stream, desired); 00211 ros::serialization::serialize(stream, actual_pose); 00212 ros::serialization::serialize(stream, effort_sq_error); 00213 ros::serialization::serialize(stream, requested_joint_efforts); 00214 ros::serialization::serialize(stream, actual_joint_efforts); 00215 ros::serialization::serialize(stream, running_time); 00216 return stream.getData(); 00217 } 00218 00219 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00220 { 00221 ros::serialization::IStream stream(read_ptr, 1000000000); 00222 ros::serialization::deserialize(stream, header); 00223 ros::serialization::deserialize(stream, goal); 00224 ros::serialization::deserialize(stream, initial_point); 00225 ros::serialization::deserialize(stream, desired); 00226 ros::serialization::deserialize(stream, actual_pose); 00227 ros::serialization::deserialize(stream, effort_sq_error); 00228 ros::serialization::deserialize(stream, requested_joint_efforts); 00229 ros::serialization::deserialize(stream, actual_joint_efforts); 00230 ros::serialization::deserialize(stream, running_time); 00231 return stream.getData(); 00232 } 00233 00234 ROS_DEPRECATED virtual uint32_t serializationLength() const 00235 { 00236 uint32_t size = 0; 00237 size += ros::serialization::serializationLength(header); 00238 size += ros::serialization::serializationLength(goal); 00239 size += ros::serialization::serializationLength(initial_point); 00240 size += ros::serialization::serializationLength(desired); 00241 size += ros::serialization::serializationLength(actual_pose); 00242 size += ros::serialization::serializationLength(effort_sq_error); 00243 size += ros::serialization::serializationLength(requested_joint_efforts); 00244 size += ros::serialization::serializationLength(actual_joint_efforts); 00245 size += ros::serialization::serializationLength(running_time); 00246 return size; 00247 } 00248 00249 typedef boost::shared_ptr< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> > Ptr; 00250 typedef boost::shared_ptr< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> const> ConstPtr; 00251 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00252 }; // struct EECartImpedFeedback 00253 typedef ::ee_cart_imped_msgs::EECartImpedFeedback_<std::allocator<void> > EECartImpedFeedback; 00254 00255 typedef boost::shared_ptr< ::ee_cart_imped_msgs::EECartImpedFeedback> EECartImpedFeedbackPtr; 00256 typedef boost::shared_ptr< ::ee_cart_imped_msgs::EECartImpedFeedback const> EECartImpedFeedbackConstPtr; 00257 00258 00259 template<typename ContainerAllocator> 00260 std::ostream& operator<<(std::ostream& s, const ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> & v) 00261 { 00262 ros::message_operations::Printer< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> >::stream(s, "", v); 00263 return s;} 00264 00265 } // namespace ee_cart_imped_msgs 00266 00267 namespace ros 00268 { 00269 namespace message_traits 00270 { 00271 template<class ContainerAllocator> struct IsMessage< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> > : public TrueType {}; 00272 template<class ContainerAllocator> struct IsMessage< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> const> : public TrueType {}; 00273 template<class ContainerAllocator> 00274 struct MD5Sum< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> > { 00275 static const char* value() 00276 { 00277 return "4106b02683301dac2003809bdf610591"; 00278 } 00279 00280 static const char* value(const ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> &) { return value(); } 00281 static const uint64_t static_value1 = 0x4106b02683301dacULL; 00282 static const uint64_t static_value2 = 0x2003809bdf610591ULL; 00283 }; 00284 00285 template<class ContainerAllocator> 00286 struct DataType< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> > { 00287 static const char* value() 00288 { 00289 return "ee_cart_imped_msgs/EECartImpedFeedback"; 00290 } 00291 00292 static const char* value(const ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> &) { return value(); } 00293 }; 00294 00295 template<class ContainerAllocator> 00296 struct Definition< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> > { 00297 static const char* value() 00298 { 00299 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00300 #feedback\n\ 00301 #current pose and squared error in force \n\ 00302 #and the running time of this goal so far\n\ 00303 Header header\n\ 00304 ee_cart_imped_msgs/StiffPoint[] goal\n\ 00305 ee_cart_imped_msgs/StiffPoint initial_point\n\ 00306 ee_cart_imped_msgs/StiffPoint desired\n\ 00307 ee_cart_imped_msgs/StiffPoint actual_pose\n\ 00308 float64 effort_sq_error\n\ 00309 float64[] requested_joint_efforts\n\ 00310 float64[] actual_joint_efforts\n\ 00311 duration running_time\n\ 00312 \n\ 00313 \n\ 00314 \n\ 00315 ================================================================================\n\ 00316 MSG: std_msgs/Header\n\ 00317 # Standard metadata for higher-level stamped data types.\n\ 00318 # This is generally used to communicate timestamped data \n\ 00319 # in a particular coordinate frame.\n\ 00320 # \n\ 00321 # sequence ID: consecutively increasing ID \n\ 00322 uint32 seq\n\ 00323 #Two-integer timestamp that is expressed as:\n\ 00324 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00325 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00326 # time-handling sugar is provided by the client library\n\ 00327 time stamp\n\ 00328 #Frame this data is associated with\n\ 00329 # 0: no frame\n\ 00330 # 1: global frame\n\ 00331 string frame_id\n\ 00332 \n\ 00333 ================================================================================\n\ 00334 MSG: ee_cart_imped_msgs/StiffPoint\n\ 00335 Header header\n\ 00336 #The pose to achieve in the stiffness directions\n\ 00337 geometry_msgs/Pose pose\n\ 00338 #Wrench or stiffness for each dimension\n\ 00339 geometry_msgs/Wrench wrench_or_stiffness\n\ 00340 #The following are True if a force/torque should\n\ 00341 #be exerted and False if a stiffness should be used.\n\ 00342 bool isForceX\n\ 00343 bool isForceY\n\ 00344 bool isForceZ\n\ 00345 bool isTorqueX\n\ 00346 bool isTorqueY\n\ 00347 bool isTorqueZ\n\ 00348 #The time from the start of the trajectory that this\n\ 00349 #point should be achieved.\n\ 00350 duration time_from_start\n\ 00351 ================================================================================\n\ 00352 MSG: geometry_msgs/Pose\n\ 00353 # A representation of pose in free space, composed of postion and orientation. \n\ 00354 Point position\n\ 00355 Quaternion orientation\n\ 00356 \n\ 00357 ================================================================================\n\ 00358 MSG: geometry_msgs/Point\n\ 00359 # This contains the position of a point in free space\n\ 00360 float64 x\n\ 00361 float64 y\n\ 00362 float64 z\n\ 00363 \n\ 00364 ================================================================================\n\ 00365 MSG: geometry_msgs/Quaternion\n\ 00366 # This represents an orientation in free space in quaternion form.\n\ 00367 \n\ 00368 float64 x\n\ 00369 float64 y\n\ 00370 float64 z\n\ 00371 float64 w\n\ 00372 \n\ 00373 ================================================================================\n\ 00374 MSG: geometry_msgs/Wrench\n\ 00375 # This represents force in free space, seperated into \n\ 00376 # it's linear and angular parts. \n\ 00377 Vector3 force\n\ 00378 Vector3 torque\n\ 00379 \n\ 00380 ================================================================================\n\ 00381 MSG: geometry_msgs/Vector3\n\ 00382 # This represents a vector in free space. \n\ 00383 \n\ 00384 float64 x\n\ 00385 float64 y\n\ 00386 float64 z\n\ 00387 "; 00388 } 00389 00390 static const char* value(const ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> &) { return value(); } 00391 }; 00392 00393 template<class ContainerAllocator> struct HasHeader< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> > : public TrueType {}; 00394 template<class ContainerAllocator> struct HasHeader< const ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> > : public TrueType {}; 00395 } // namespace message_traits 00396 } // namespace ros 00397 00398 namespace ros 00399 { 00400 namespace serialization 00401 { 00402 00403 template<class ContainerAllocator> struct Serializer< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> > 00404 { 00405 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00406 { 00407 stream.next(m.header); 00408 stream.next(m.goal); 00409 stream.next(m.initial_point); 00410 stream.next(m.desired); 00411 stream.next(m.actual_pose); 00412 stream.next(m.effort_sq_error); 00413 stream.next(m.requested_joint_efforts); 00414 stream.next(m.actual_joint_efforts); 00415 stream.next(m.running_time); 00416 } 00417 00418 ROS_DECLARE_ALLINONE_SERIALIZER; 00419 }; // struct EECartImpedFeedback_ 00420 } // namespace serialization 00421 } // namespace ros 00422 00423 namespace ros 00424 { 00425 namespace message_operations 00426 { 00427 00428 template<class ContainerAllocator> 00429 struct Printer< ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> > 00430 { 00431 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::ee_cart_imped_msgs::EECartImpedFeedback_<ContainerAllocator> & v) 00432 { 00433 s << indent << "header: "; 00434 s << std::endl; 00435 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00436 s << indent << "goal[]" << std::endl; 00437 for (size_t i = 0; i < v.goal.size(); ++i) 00438 { 00439 s << indent << " goal[" << i << "]: "; 00440 s << std::endl; 00441 s << indent; 00442 Printer< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> >::stream(s, indent + " ", v.goal[i]); 00443 } 00444 s << indent << "initial_point: "; 00445 s << std::endl; 00446 Printer< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> >::stream(s, indent + " ", v.initial_point); 00447 s << indent << "desired: "; 00448 s << std::endl; 00449 Printer< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> >::stream(s, indent + " ", v.desired); 00450 s << indent << "actual_pose: "; 00451 s << std::endl; 00452 Printer< ::ee_cart_imped_msgs::StiffPoint_<ContainerAllocator> >::stream(s, indent + " ", v.actual_pose); 00453 s << indent << "effort_sq_error: "; 00454 Printer<double>::stream(s, indent + " ", v.effort_sq_error); 00455 s << indent << "requested_joint_efforts[]" << std::endl; 00456 for (size_t i = 0; i < v.requested_joint_efforts.size(); ++i) 00457 { 00458 s << indent << " requested_joint_efforts[" << i << "]: "; 00459 Printer<double>::stream(s, indent + " ", v.requested_joint_efforts[i]); 00460 } 00461 s << indent << "actual_joint_efforts[]" << std::endl; 00462 for (size_t i = 0; i < v.actual_joint_efforts.size(); ++i) 00463 { 00464 s << indent << " actual_joint_efforts[" << i << "]: "; 00465 Printer<double>::stream(s, indent + " ", v.actual_joint_efforts[i]); 00466 } 00467 s << indent << "running_time: "; 00468 Printer<ros::Duration>::stream(s, indent + " ", v.running_time); 00469 } 00470 }; 00471 00472 00473 } // namespace message_operations 00474 } // namespace ros 00475 00476 #endif // EE_CART_IMPED_MSGS_MESSAGE_EECARTIMPEDFEEDBACK_H 00477