00001
00002 #ifndef SBPL_LATTICE_PLANNER_MESSAGE_SBPLLATTICEPLANNERSTATS_H
00003 #define SBPL_LATTICE_PLANNER_MESSAGE_SBPLLATTICEPLANNERSTATS_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "geometry_msgs/PoseStamped.h"
00014 #include "geometry_msgs/PoseStamped.h"
00015
00016 namespace sbpl_lattice_planner
00017 {
00018 template <class ContainerAllocator>
00019 struct SBPLLatticePlannerStats_ : public ros::Message
00020 {
00021 typedef SBPLLatticePlannerStats_<ContainerAllocator> Type;
00022
00023 SBPLLatticePlannerStats_()
00024 : initial_epsilon(0.0)
00025 , final_epsilon(0.0)
00026 , plan_to_first_solution(false)
00027 , allocated_time(0.0)
00028 , actual_time(0.0)
00029 , time_to_first_solution(0.0)
00030 , solution_cost(0.0)
00031 , path_size(0.0)
00032 , final_number_of_expands(0)
00033 , number_of_expands_initial_solution(0)
00034 , start()
00035 , goal()
00036 {
00037 }
00038
00039 SBPLLatticePlannerStats_(const ContainerAllocator& _alloc)
00040 : initial_epsilon(0.0)
00041 , final_epsilon(0.0)
00042 , plan_to_first_solution(false)
00043 , allocated_time(0.0)
00044 , actual_time(0.0)
00045 , time_to_first_solution(0.0)
00046 , solution_cost(0.0)
00047 , path_size(0.0)
00048 , final_number_of_expands(0)
00049 , number_of_expands_initial_solution(0)
00050 , start(_alloc)
00051 , goal(_alloc)
00052 {
00053 }
00054
00055 typedef double _initial_epsilon_type;
00056 double initial_epsilon;
00057
00058 typedef double _final_epsilon_type;
00059 double final_epsilon;
00060
00061 typedef uint8_t _plan_to_first_solution_type;
00062 uint8_t plan_to_first_solution;
00063
00064 typedef double _allocated_time_type;
00065 double allocated_time;
00066
00067 typedef double _actual_time_type;
00068 double actual_time;
00069
00070 typedef double _time_to_first_solution_type;
00071 double time_to_first_solution;
00072
00073 typedef double _solution_cost_type;
00074 double solution_cost;
00075
00076 typedef double _path_size_type;
00077 double path_size;
00078
00079 typedef int64_t _final_number_of_expands_type;
00080 int64_t final_number_of_expands;
00081
00082 typedef int64_t _number_of_expands_initial_solution_type;
00083 int64_t number_of_expands_initial_solution;
00084
00085 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _start_type;
00086 ::geometry_msgs::PoseStamped_<ContainerAllocator> start;
00087
00088 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _goal_type;
00089 ::geometry_msgs::PoseStamped_<ContainerAllocator> goal;
00090
00091
00092 private:
00093 static const char* __s_getDataType_() { return "sbpl_lattice_planner/SBPLLatticePlannerStats"; }
00094 public:
00095 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00096
00097 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00098
00099 private:
00100 static const char* __s_getMD5Sum_() { return "b1c85b1cec5e7b196cc477ac1440bbf0"; }
00101 public:
00102 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00103
00104 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00105
00106 private:
00107 static const char* __s_getMessageDefinition_() { return "#planner stats\n\
00108 float64 initial_epsilon\n\
00109 float64 final_epsilon\n\
00110 bool plan_to_first_solution\n\
00111 float64 allocated_time\n\
00112 float64 actual_time\n\
00113 float64 time_to_first_solution\n\
00114 float64 solution_cost\n\
00115 float64 path_size\n\
00116 int64 final_number_of_expands\n\
00117 int64 number_of_expands_initial_solution\n\
00118 \n\
00119 #problem stats\n\
00120 geometry_msgs/PoseStamped start\n\
00121 geometry_msgs/PoseStamped goal\n\
00122 \n\
00123 ================================================================================\n\
00124 MSG: geometry_msgs/PoseStamped\n\
00125 # A Pose with reference coordinate frame and timestamp\n\
00126 Header header\n\
00127 Pose pose\n\
00128 \n\
00129 ================================================================================\n\
00130 MSG: std_msgs/Header\n\
00131 # Standard metadata for higher-level stamped data types.\n\
00132 # This is generally used to communicate timestamped data \n\
00133 # in a particular coordinate frame.\n\
00134 # \n\
00135 # sequence ID: consecutively increasing ID \n\
00136 uint32 seq\n\
00137 #Two-integer timestamp that is expressed as:\n\
00138 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00139 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00140 # time-handling sugar is provided by the client library\n\
00141 time stamp\n\
00142 #Frame this data is associated with\n\
00143 # 0: no frame\n\
00144 # 1: global frame\n\
00145 string frame_id\n\
00146 \n\
00147 ================================================================================\n\
00148 MSG: geometry_msgs/Pose\n\
00149 # A representation of pose in free space, composed of postion and orientation. \n\
00150 Point position\n\
00151 Quaternion orientation\n\
00152 \n\
00153 ================================================================================\n\
00154 MSG: geometry_msgs/Point\n\
00155 # This contains the position of a point in free space\n\
00156 float64 x\n\
00157 float64 y\n\
00158 float64 z\n\
00159 \n\
00160 ================================================================================\n\
00161 MSG: geometry_msgs/Quaternion\n\
00162 # This represents an orientation in free space in quaternion form.\n\
00163 \n\
00164 float64 x\n\
00165 float64 y\n\
00166 float64 z\n\
00167 float64 w\n\
00168 \n\
00169 "; }
00170 public:
00171 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00172
00173 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00174
00175 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00176 {
00177 ros::serialization::OStream stream(write_ptr, 1000000000);
00178 ros::serialization::serialize(stream, initial_epsilon);
00179 ros::serialization::serialize(stream, final_epsilon);
00180 ros::serialization::serialize(stream, plan_to_first_solution);
00181 ros::serialization::serialize(stream, allocated_time);
00182 ros::serialization::serialize(stream, actual_time);
00183 ros::serialization::serialize(stream, time_to_first_solution);
00184 ros::serialization::serialize(stream, solution_cost);
00185 ros::serialization::serialize(stream, path_size);
00186 ros::serialization::serialize(stream, final_number_of_expands);
00187 ros::serialization::serialize(stream, number_of_expands_initial_solution);
00188 ros::serialization::serialize(stream, start);
00189 ros::serialization::serialize(stream, goal);
00190 return stream.getData();
00191 }
00192
00193 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00194 {
00195 ros::serialization::IStream stream(read_ptr, 1000000000);
00196 ros::serialization::deserialize(stream, initial_epsilon);
00197 ros::serialization::deserialize(stream, final_epsilon);
00198 ros::serialization::deserialize(stream, plan_to_first_solution);
00199 ros::serialization::deserialize(stream, allocated_time);
00200 ros::serialization::deserialize(stream, actual_time);
00201 ros::serialization::deserialize(stream, time_to_first_solution);
00202 ros::serialization::deserialize(stream, solution_cost);
00203 ros::serialization::deserialize(stream, path_size);
00204 ros::serialization::deserialize(stream, final_number_of_expands);
00205 ros::serialization::deserialize(stream, number_of_expands_initial_solution);
00206 ros::serialization::deserialize(stream, start);
00207 ros::serialization::deserialize(stream, goal);
00208 return stream.getData();
00209 }
00210
00211 ROS_DEPRECATED virtual uint32_t serializationLength() const
00212 {
00213 uint32_t size = 0;
00214 size += ros::serialization::serializationLength(initial_epsilon);
00215 size += ros::serialization::serializationLength(final_epsilon);
00216 size += ros::serialization::serializationLength(plan_to_first_solution);
00217 size += ros::serialization::serializationLength(allocated_time);
00218 size += ros::serialization::serializationLength(actual_time);
00219 size += ros::serialization::serializationLength(time_to_first_solution);
00220 size += ros::serialization::serializationLength(solution_cost);
00221 size += ros::serialization::serializationLength(path_size);
00222 size += ros::serialization::serializationLength(final_number_of_expands);
00223 size += ros::serialization::serializationLength(number_of_expands_initial_solution);
00224 size += ros::serialization::serializationLength(start);
00225 size += ros::serialization::serializationLength(goal);
00226 return size;
00227 }
00228
00229 typedef boost::shared_ptr< ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> > Ptr;
00230 typedef boost::shared_ptr< ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> const> ConstPtr;
00231 };
00232 typedef ::sbpl_lattice_planner::SBPLLatticePlannerStats_<std::allocator<void> > SBPLLatticePlannerStats;
00233
00234 typedef boost::shared_ptr< ::sbpl_lattice_planner::SBPLLatticePlannerStats> SBPLLatticePlannerStatsPtr;
00235 typedef boost::shared_ptr< ::sbpl_lattice_planner::SBPLLatticePlannerStats const> SBPLLatticePlannerStatsConstPtr;
00236
00237
00238 template<typename ContainerAllocator>
00239 std::ostream& operator<<(std::ostream& s, const ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> & v)
00240 {
00241 ros::message_operations::Printer< ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> >::stream(s, "", v);
00242 return s;}
00243
00244 }
00245
00246 namespace ros
00247 {
00248 namespace message_traits
00249 {
00250 template<class ContainerAllocator>
00251 struct MD5Sum< ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> > {
00252 static const char* value()
00253 {
00254 return "b1c85b1cec5e7b196cc477ac1440bbf0";
00255 }
00256
00257 static const char* value(const ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> &) { return value(); }
00258 static const uint64_t static_value1 = 0xb1c85b1cec5e7b19ULL;
00259 static const uint64_t static_value2 = 0x6cc477ac1440bbf0ULL;
00260 };
00261
00262 template<class ContainerAllocator>
00263 struct DataType< ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> > {
00264 static const char* value()
00265 {
00266 return "sbpl_lattice_planner/SBPLLatticePlannerStats";
00267 }
00268
00269 static const char* value(const ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> &) { return value(); }
00270 };
00271
00272 template<class ContainerAllocator>
00273 struct Definition< ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> > {
00274 static const char* value()
00275 {
00276 return "#planner stats\n\
00277 float64 initial_epsilon\n\
00278 float64 final_epsilon\n\
00279 bool plan_to_first_solution\n\
00280 float64 allocated_time\n\
00281 float64 actual_time\n\
00282 float64 time_to_first_solution\n\
00283 float64 solution_cost\n\
00284 float64 path_size\n\
00285 int64 final_number_of_expands\n\
00286 int64 number_of_expands_initial_solution\n\
00287 \n\
00288 #problem stats\n\
00289 geometry_msgs/PoseStamped start\n\
00290 geometry_msgs/PoseStamped goal\n\
00291 \n\
00292 ================================================================================\n\
00293 MSG: geometry_msgs/PoseStamped\n\
00294 # A Pose with reference coordinate frame and timestamp\n\
00295 Header header\n\
00296 Pose pose\n\
00297 \n\
00298 ================================================================================\n\
00299 MSG: std_msgs/Header\n\
00300 # Standard metadata for higher-level stamped data types.\n\
00301 # This is generally used to communicate timestamped data \n\
00302 # in a particular coordinate frame.\n\
00303 # \n\
00304 # sequence ID: consecutively increasing ID \n\
00305 uint32 seq\n\
00306 #Two-integer timestamp that is expressed as:\n\
00307 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00308 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00309 # time-handling sugar is provided by the client library\n\
00310 time stamp\n\
00311 #Frame this data is associated with\n\
00312 # 0: no frame\n\
00313 # 1: global frame\n\
00314 string frame_id\n\
00315 \n\
00316 ================================================================================\n\
00317 MSG: geometry_msgs/Pose\n\
00318 # A representation of pose in free space, composed of postion and orientation. \n\
00319 Point position\n\
00320 Quaternion orientation\n\
00321 \n\
00322 ================================================================================\n\
00323 MSG: geometry_msgs/Point\n\
00324 # This contains the position of a point in free space\n\
00325 float64 x\n\
00326 float64 y\n\
00327 float64 z\n\
00328 \n\
00329 ================================================================================\n\
00330 MSG: geometry_msgs/Quaternion\n\
00331 # This represents an orientation in free space in quaternion form.\n\
00332 \n\
00333 float64 x\n\
00334 float64 y\n\
00335 float64 z\n\
00336 float64 w\n\
00337 \n\
00338 ";
00339 }
00340
00341 static const char* value(const ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> &) { return value(); }
00342 };
00343
00344 }
00345 }
00346
00347 namespace ros
00348 {
00349 namespace serialization
00350 {
00351
00352 template<class ContainerAllocator> struct Serializer< ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> >
00353 {
00354 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00355 {
00356 stream.next(m.initial_epsilon);
00357 stream.next(m.final_epsilon);
00358 stream.next(m.plan_to_first_solution);
00359 stream.next(m.allocated_time);
00360 stream.next(m.actual_time);
00361 stream.next(m.time_to_first_solution);
00362 stream.next(m.solution_cost);
00363 stream.next(m.path_size);
00364 stream.next(m.final_number_of_expands);
00365 stream.next(m.number_of_expands_initial_solution);
00366 stream.next(m.start);
00367 stream.next(m.goal);
00368 }
00369
00370 ROS_DECLARE_ALLINONE_SERIALIZER;
00371 };
00372 }
00373 }
00374
00375 namespace ros
00376 {
00377 namespace message_operations
00378 {
00379
00380 template<class ContainerAllocator>
00381 struct Printer< ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> >
00382 {
00383 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sbpl_lattice_planner::SBPLLatticePlannerStats_<ContainerAllocator> & v)
00384 {
00385 s << indent << "initial_epsilon: ";
00386 Printer<double>::stream(s, indent + " ", v.initial_epsilon);
00387 s << indent << "final_epsilon: ";
00388 Printer<double>::stream(s, indent + " ", v.final_epsilon);
00389 s << indent << "plan_to_first_solution: ";
00390 Printer<uint8_t>::stream(s, indent + " ", v.plan_to_first_solution);
00391 s << indent << "allocated_time: ";
00392 Printer<double>::stream(s, indent + " ", v.allocated_time);
00393 s << indent << "actual_time: ";
00394 Printer<double>::stream(s, indent + " ", v.actual_time);
00395 s << indent << "time_to_first_solution: ";
00396 Printer<double>::stream(s, indent + " ", v.time_to_first_solution);
00397 s << indent << "solution_cost: ";
00398 Printer<double>::stream(s, indent + " ", v.solution_cost);
00399 s << indent << "path_size: ";
00400 Printer<double>::stream(s, indent + " ", v.path_size);
00401 s << indent << "final_number_of_expands: ";
00402 Printer<int64_t>::stream(s, indent + " ", v.final_number_of_expands);
00403 s << indent << "number_of_expands_initial_solution: ";
00404 Printer<int64_t>::stream(s, indent + " ", v.number_of_expands_initial_solution);
00405 s << indent << "start: ";
00406 s << std::endl;
00407 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.start);
00408 s << indent << "goal: ";
00409 s << std::endl;
00410 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.goal);
00411 }
00412 };
00413
00414
00415 }
00416 }
00417
00418 #endif // SBPL_LATTICE_PLANNER_MESSAGE_SBPLLATTICEPLANNERSTATS_H
00419