$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-cart_pushing/doc_stacks/2013-03-01_14-28-04.885134/cart_pushing/sbpl_cart_planner/msg/SBPLCartPlannerStats.msg */ 00002 #ifndef SBPL_CART_PLANNER_MESSAGE_SBPLCARTPLANNERSTATS_H 00003 #define SBPL_CART_PLANNER_MESSAGE_SBPLCARTPLANNERSTATS_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 "geometry_msgs/PoseStamped.h" 00018 #include "geometry_msgs/PoseStamped.h" 00019 #include "cart_pushing_msgs/RobotCartPath.h" 00020 00021 namespace sbpl_cart_planner 00022 { 00023 template <class ContainerAllocator> 00024 struct SBPLCartPlannerStats_ { 00025 typedef SBPLCartPlannerStats_<ContainerAllocator> Type; 00026 00027 SBPLCartPlannerStats_() 00028 : initial_epsilon(0.0) 00029 , final_epsilon(0.0) 00030 , plan_to_first_solution(false) 00031 , allocated_time(0.0) 00032 , actual_time(0.0) 00033 , time_to_first_solution(0.0) 00034 , solution_cost(0.0) 00035 , path_size(0.0) 00036 , final_number_of_expands(0) 00037 , number_of_expands_initial_solution(0) 00038 , start() 00039 , start_cart_angle(0.0) 00040 , goal() 00041 , goal_cart_angle(0.0) 00042 , solution() 00043 { 00044 } 00045 00046 SBPLCartPlannerStats_(const ContainerAllocator& _alloc) 00047 : initial_epsilon(0.0) 00048 , final_epsilon(0.0) 00049 , plan_to_first_solution(false) 00050 , allocated_time(0.0) 00051 , actual_time(0.0) 00052 , time_to_first_solution(0.0) 00053 , solution_cost(0.0) 00054 , path_size(0.0) 00055 , final_number_of_expands(0) 00056 , number_of_expands_initial_solution(0) 00057 , start(_alloc) 00058 , start_cart_angle(0.0) 00059 , goal(_alloc) 00060 , goal_cart_angle(0.0) 00061 , solution(_alloc) 00062 { 00063 } 00064 00065 typedef double _initial_epsilon_type; 00066 double initial_epsilon; 00067 00068 typedef double _final_epsilon_type; 00069 double final_epsilon; 00070 00071 typedef uint8_t _plan_to_first_solution_type; 00072 uint8_t plan_to_first_solution; 00073 00074 typedef double _allocated_time_type; 00075 double allocated_time; 00076 00077 typedef double _actual_time_type; 00078 double actual_time; 00079 00080 typedef double _time_to_first_solution_type; 00081 double time_to_first_solution; 00082 00083 typedef double _solution_cost_type; 00084 double solution_cost; 00085 00086 typedef double _path_size_type; 00087 double path_size; 00088 00089 typedef int64_t _final_number_of_expands_type; 00090 int64_t final_number_of_expands; 00091 00092 typedef int64_t _number_of_expands_initial_solution_type; 00093 int64_t number_of_expands_initial_solution; 00094 00095 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _start_type; 00096 ::geometry_msgs::PoseStamped_<ContainerAllocator> start; 00097 00098 typedef double _start_cart_angle_type; 00099 double start_cart_angle; 00100 00101 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _goal_type; 00102 ::geometry_msgs::PoseStamped_<ContainerAllocator> goal; 00103 00104 typedef double _goal_cart_angle_type; 00105 double goal_cart_angle; 00106 00107 typedef ::cart_pushing_msgs::RobotCartPath_<ContainerAllocator> _solution_type; 00108 ::cart_pushing_msgs::RobotCartPath_<ContainerAllocator> solution; 00109 00110 00111 private: 00112 static const char* __s_getDataType_() { return "sbpl_cart_planner/SBPLCartPlannerStats"; } 00113 public: 00114 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00115 00116 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00117 00118 private: 00119 static const char* __s_getMD5Sum_() { return "59dcf49825e7e59499a38ffdd0daa999"; } 00120 public: 00121 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00122 00123 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00124 00125 private: 00126 static const char* __s_getMessageDefinition_() { return "#planner stats\n\ 00127 float64 initial_epsilon\n\ 00128 float64 final_epsilon\n\ 00129 bool plan_to_first_solution\n\ 00130 float64 allocated_time\n\ 00131 float64 actual_time\n\ 00132 float64 time_to_first_solution\n\ 00133 float64 solution_cost\n\ 00134 float64 path_size\n\ 00135 int64 final_number_of_expands\n\ 00136 int64 number_of_expands_initial_solution\n\ 00137 \n\ 00138 #problem stats\n\ 00139 geometry_msgs/PoseStamped start\n\ 00140 float64 start_cart_angle\n\ 00141 geometry_msgs/PoseStamped goal\n\ 00142 float64 goal_cart_angle\n\ 00143 \n\ 00144 #solution\n\ 00145 cart_pushing_msgs/RobotCartPath solution\n\ 00146 ================================================================================\n\ 00147 MSG: geometry_msgs/PoseStamped\n\ 00148 # A Pose with reference coordinate frame and timestamp\n\ 00149 Header header\n\ 00150 Pose pose\n\ 00151 \n\ 00152 ================================================================================\n\ 00153 MSG: std_msgs/Header\n\ 00154 # Standard metadata for higher-level stamped data types.\n\ 00155 # This is generally used to communicate timestamped data \n\ 00156 # in a particular coordinate frame.\n\ 00157 # \n\ 00158 # sequence ID: consecutively increasing ID \n\ 00159 uint32 seq\n\ 00160 #Two-integer timestamp that is expressed as:\n\ 00161 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00162 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00163 # time-handling sugar is provided by the client library\n\ 00164 time stamp\n\ 00165 #Frame this data is associated with\n\ 00166 # 0: no frame\n\ 00167 # 1: global frame\n\ 00168 string frame_id\n\ 00169 \n\ 00170 ================================================================================\n\ 00171 MSG: geometry_msgs/Pose\n\ 00172 # A representation of pose in free space, composed of postion and orientation. \n\ 00173 Point position\n\ 00174 Quaternion orientation\n\ 00175 \n\ 00176 ================================================================================\n\ 00177 MSG: geometry_msgs/Point\n\ 00178 # This contains the position of a point in free space\n\ 00179 float64 x\n\ 00180 float64 y\n\ 00181 float64 z\n\ 00182 \n\ 00183 ================================================================================\n\ 00184 MSG: geometry_msgs/Quaternion\n\ 00185 # This represents an orientation in free space in quaternion form.\n\ 00186 \n\ 00187 float64 x\n\ 00188 float64 y\n\ 00189 float64 z\n\ 00190 float64 w\n\ 00191 \n\ 00192 ================================================================================\n\ 00193 MSG: cart_pushing_msgs/RobotCartPath\n\ 00194 Header header\n\ 00195 RobotCartConfiguration[] path\n\ 00196 ================================================================================\n\ 00197 MSG: cart_pushing_msgs/RobotCartConfiguration\n\ 00198 # Robot's pose in reference frame\n\ 00199 geometry_msgs/Pose robot_pose\n\ 00200 \n\ 00201 # Cart's pose in base frame\n\ 00202 geometry_msgs/Pose cart_pose\n\ 00203 "; } 00204 public: 00205 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00206 00207 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00208 00209 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00210 { 00211 ros::serialization::OStream stream(write_ptr, 1000000000); 00212 ros::serialization::serialize(stream, initial_epsilon); 00213 ros::serialization::serialize(stream, final_epsilon); 00214 ros::serialization::serialize(stream, plan_to_first_solution); 00215 ros::serialization::serialize(stream, allocated_time); 00216 ros::serialization::serialize(stream, actual_time); 00217 ros::serialization::serialize(stream, time_to_first_solution); 00218 ros::serialization::serialize(stream, solution_cost); 00219 ros::serialization::serialize(stream, path_size); 00220 ros::serialization::serialize(stream, final_number_of_expands); 00221 ros::serialization::serialize(stream, number_of_expands_initial_solution); 00222 ros::serialization::serialize(stream, start); 00223 ros::serialization::serialize(stream, start_cart_angle); 00224 ros::serialization::serialize(stream, goal); 00225 ros::serialization::serialize(stream, goal_cart_angle); 00226 ros::serialization::serialize(stream, solution); 00227 return stream.getData(); 00228 } 00229 00230 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00231 { 00232 ros::serialization::IStream stream(read_ptr, 1000000000); 00233 ros::serialization::deserialize(stream, initial_epsilon); 00234 ros::serialization::deserialize(stream, final_epsilon); 00235 ros::serialization::deserialize(stream, plan_to_first_solution); 00236 ros::serialization::deserialize(stream, allocated_time); 00237 ros::serialization::deserialize(stream, actual_time); 00238 ros::serialization::deserialize(stream, time_to_first_solution); 00239 ros::serialization::deserialize(stream, solution_cost); 00240 ros::serialization::deserialize(stream, path_size); 00241 ros::serialization::deserialize(stream, final_number_of_expands); 00242 ros::serialization::deserialize(stream, number_of_expands_initial_solution); 00243 ros::serialization::deserialize(stream, start); 00244 ros::serialization::deserialize(stream, start_cart_angle); 00245 ros::serialization::deserialize(stream, goal); 00246 ros::serialization::deserialize(stream, goal_cart_angle); 00247 ros::serialization::deserialize(stream, solution); 00248 return stream.getData(); 00249 } 00250 00251 ROS_DEPRECATED virtual uint32_t serializationLength() const 00252 { 00253 uint32_t size = 0; 00254 size += ros::serialization::serializationLength(initial_epsilon); 00255 size += ros::serialization::serializationLength(final_epsilon); 00256 size += ros::serialization::serializationLength(plan_to_first_solution); 00257 size += ros::serialization::serializationLength(allocated_time); 00258 size += ros::serialization::serializationLength(actual_time); 00259 size += ros::serialization::serializationLength(time_to_first_solution); 00260 size += ros::serialization::serializationLength(solution_cost); 00261 size += ros::serialization::serializationLength(path_size); 00262 size += ros::serialization::serializationLength(final_number_of_expands); 00263 size += ros::serialization::serializationLength(number_of_expands_initial_solution); 00264 size += ros::serialization::serializationLength(start); 00265 size += ros::serialization::serializationLength(start_cart_angle); 00266 size += ros::serialization::serializationLength(goal); 00267 size += ros::serialization::serializationLength(goal_cart_angle); 00268 size += ros::serialization::serializationLength(solution); 00269 return size; 00270 } 00271 00272 typedef boost::shared_ptr< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> > Ptr; 00273 typedef boost::shared_ptr< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> const> ConstPtr; 00274 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00275 }; // struct SBPLCartPlannerStats 00276 typedef ::sbpl_cart_planner::SBPLCartPlannerStats_<std::allocator<void> > SBPLCartPlannerStats; 00277 00278 typedef boost::shared_ptr< ::sbpl_cart_planner::SBPLCartPlannerStats> SBPLCartPlannerStatsPtr; 00279 typedef boost::shared_ptr< ::sbpl_cart_planner::SBPLCartPlannerStats const> SBPLCartPlannerStatsConstPtr; 00280 00281 00282 template<typename ContainerAllocator> 00283 std::ostream& operator<<(std::ostream& s, const ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> & v) 00284 { 00285 ros::message_operations::Printer< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> >::stream(s, "", v); 00286 return s;} 00287 00288 } // namespace sbpl_cart_planner 00289 00290 namespace ros 00291 { 00292 namespace message_traits 00293 { 00294 template<class ContainerAllocator> struct IsMessage< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> > : public TrueType {}; 00295 template<class ContainerAllocator> struct IsMessage< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> const> : public TrueType {}; 00296 template<class ContainerAllocator> 00297 struct MD5Sum< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> > { 00298 static const char* value() 00299 { 00300 return "59dcf49825e7e59499a38ffdd0daa999"; 00301 } 00302 00303 static const char* value(const ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> &) { return value(); } 00304 static const uint64_t static_value1 = 0x59dcf49825e7e594ULL; 00305 static const uint64_t static_value2 = 0x99a38ffdd0daa999ULL; 00306 }; 00307 00308 template<class ContainerAllocator> 00309 struct DataType< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> > { 00310 static const char* value() 00311 { 00312 return "sbpl_cart_planner/SBPLCartPlannerStats"; 00313 } 00314 00315 static const char* value(const ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> &) { return value(); } 00316 }; 00317 00318 template<class ContainerAllocator> 00319 struct Definition< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> > { 00320 static const char* value() 00321 { 00322 return "#planner stats\n\ 00323 float64 initial_epsilon\n\ 00324 float64 final_epsilon\n\ 00325 bool plan_to_first_solution\n\ 00326 float64 allocated_time\n\ 00327 float64 actual_time\n\ 00328 float64 time_to_first_solution\n\ 00329 float64 solution_cost\n\ 00330 float64 path_size\n\ 00331 int64 final_number_of_expands\n\ 00332 int64 number_of_expands_initial_solution\n\ 00333 \n\ 00334 #problem stats\n\ 00335 geometry_msgs/PoseStamped start\n\ 00336 float64 start_cart_angle\n\ 00337 geometry_msgs/PoseStamped goal\n\ 00338 float64 goal_cart_angle\n\ 00339 \n\ 00340 #solution\n\ 00341 cart_pushing_msgs/RobotCartPath solution\n\ 00342 ================================================================================\n\ 00343 MSG: geometry_msgs/PoseStamped\n\ 00344 # A Pose with reference coordinate frame and timestamp\n\ 00345 Header header\n\ 00346 Pose pose\n\ 00347 \n\ 00348 ================================================================================\n\ 00349 MSG: std_msgs/Header\n\ 00350 # Standard metadata for higher-level stamped data types.\n\ 00351 # This is generally used to communicate timestamped data \n\ 00352 # in a particular coordinate frame.\n\ 00353 # \n\ 00354 # sequence ID: consecutively increasing ID \n\ 00355 uint32 seq\n\ 00356 #Two-integer timestamp that is expressed as:\n\ 00357 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00358 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00359 # time-handling sugar is provided by the client library\n\ 00360 time stamp\n\ 00361 #Frame this data is associated with\n\ 00362 # 0: no frame\n\ 00363 # 1: global frame\n\ 00364 string frame_id\n\ 00365 \n\ 00366 ================================================================================\n\ 00367 MSG: geometry_msgs/Pose\n\ 00368 # A representation of pose in free space, composed of postion and orientation. \n\ 00369 Point position\n\ 00370 Quaternion orientation\n\ 00371 \n\ 00372 ================================================================================\n\ 00373 MSG: geometry_msgs/Point\n\ 00374 # This contains the position of a point in free space\n\ 00375 float64 x\n\ 00376 float64 y\n\ 00377 float64 z\n\ 00378 \n\ 00379 ================================================================================\n\ 00380 MSG: geometry_msgs/Quaternion\n\ 00381 # This represents an orientation in free space in quaternion form.\n\ 00382 \n\ 00383 float64 x\n\ 00384 float64 y\n\ 00385 float64 z\n\ 00386 float64 w\n\ 00387 \n\ 00388 ================================================================================\n\ 00389 MSG: cart_pushing_msgs/RobotCartPath\n\ 00390 Header header\n\ 00391 RobotCartConfiguration[] path\n\ 00392 ================================================================================\n\ 00393 MSG: cart_pushing_msgs/RobotCartConfiguration\n\ 00394 # Robot's pose in reference frame\n\ 00395 geometry_msgs/Pose robot_pose\n\ 00396 \n\ 00397 # Cart's pose in base frame\n\ 00398 geometry_msgs/Pose cart_pose\n\ 00399 "; 00400 } 00401 00402 static const char* value(const ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> &) { return value(); } 00403 }; 00404 00405 } // namespace message_traits 00406 } // namespace ros 00407 00408 namespace ros 00409 { 00410 namespace serialization 00411 { 00412 00413 template<class ContainerAllocator> struct Serializer< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> > 00414 { 00415 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00416 { 00417 stream.next(m.initial_epsilon); 00418 stream.next(m.final_epsilon); 00419 stream.next(m.plan_to_first_solution); 00420 stream.next(m.allocated_time); 00421 stream.next(m.actual_time); 00422 stream.next(m.time_to_first_solution); 00423 stream.next(m.solution_cost); 00424 stream.next(m.path_size); 00425 stream.next(m.final_number_of_expands); 00426 stream.next(m.number_of_expands_initial_solution); 00427 stream.next(m.start); 00428 stream.next(m.start_cart_angle); 00429 stream.next(m.goal); 00430 stream.next(m.goal_cart_angle); 00431 stream.next(m.solution); 00432 } 00433 00434 ROS_DECLARE_ALLINONE_SERIALIZER; 00435 }; // struct SBPLCartPlannerStats_ 00436 } // namespace serialization 00437 } // namespace ros 00438 00439 namespace ros 00440 { 00441 namespace message_operations 00442 { 00443 00444 template<class ContainerAllocator> 00445 struct Printer< ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> > 00446 { 00447 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sbpl_cart_planner::SBPLCartPlannerStats_<ContainerAllocator> & v) 00448 { 00449 s << indent << "initial_epsilon: "; 00450 Printer<double>::stream(s, indent + " ", v.initial_epsilon); 00451 s << indent << "final_epsilon: "; 00452 Printer<double>::stream(s, indent + " ", v.final_epsilon); 00453 s << indent << "plan_to_first_solution: "; 00454 Printer<uint8_t>::stream(s, indent + " ", v.plan_to_first_solution); 00455 s << indent << "allocated_time: "; 00456 Printer<double>::stream(s, indent + " ", v.allocated_time); 00457 s << indent << "actual_time: "; 00458 Printer<double>::stream(s, indent + " ", v.actual_time); 00459 s << indent << "time_to_first_solution: "; 00460 Printer<double>::stream(s, indent + " ", v.time_to_first_solution); 00461 s << indent << "solution_cost: "; 00462 Printer<double>::stream(s, indent + " ", v.solution_cost); 00463 s << indent << "path_size: "; 00464 Printer<double>::stream(s, indent + " ", v.path_size); 00465 s << indent << "final_number_of_expands: "; 00466 Printer<int64_t>::stream(s, indent + " ", v.final_number_of_expands); 00467 s << indent << "number_of_expands_initial_solution: "; 00468 Printer<int64_t>::stream(s, indent + " ", v.number_of_expands_initial_solution); 00469 s << indent << "start: "; 00470 s << std::endl; 00471 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.start); 00472 s << indent << "start_cart_angle: "; 00473 Printer<double>::stream(s, indent + " ", v.start_cart_angle); 00474 s << indent << "goal: "; 00475 s << std::endl; 00476 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.goal); 00477 s << indent << "goal_cart_angle: "; 00478 Printer<double>::stream(s, indent + " ", v.goal_cart_angle); 00479 s << indent << "solution: "; 00480 s << std::endl; 00481 Printer< ::cart_pushing_msgs::RobotCartPath_<ContainerAllocator> >::stream(s, indent + " ", v.solution); 00482 } 00483 }; 00484 00485 00486 } // namespace message_operations 00487 } // namespace ros 00488 00489 #endif // SBPL_CART_PLANNER_MESSAGE_SBPLCARTPLANNERSTATS_H 00490