00001
00002 #ifndef MOVE_ARM_MSGS_MESSAGE_MOVEARMSTATISTICS_H
00003 #define MOVE_ARM_MSGS_MESSAGE_MOVEARMSTATISTICS_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 "motion_planning_msgs/ArmNavigationErrorCodes.h"
00014
00015 namespace move_arm_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct MoveArmStatistics_ : public ros::Message
00019 {
00020 typedef MoveArmStatistics_<ContainerAllocator> Type;
00021
00022 MoveArmStatistics_()
00023 : request_id(0)
00024 , result()
00025 , error_code()
00026 , planning_time(0.0)
00027 , smoothing_time(0.0)
00028 , ik_time(0.0)
00029 , time_to_execution(0.0)
00030 , time_to_result(0.0)
00031 , preempted(false)
00032 , num_replans(0.0)
00033 , trajectory_duration(0.0)
00034 , planner_service_name()
00035 {
00036 }
00037
00038 MoveArmStatistics_(const ContainerAllocator& _alloc)
00039 : request_id(0)
00040 , result(_alloc)
00041 , error_code(_alloc)
00042 , planning_time(0.0)
00043 , smoothing_time(0.0)
00044 , ik_time(0.0)
00045 , time_to_execution(0.0)
00046 , time_to_result(0.0)
00047 , preempted(false)
00048 , num_replans(0.0)
00049 , trajectory_duration(0.0)
00050 , planner_service_name(_alloc)
00051 {
00052 }
00053
00054 typedef int32_t _request_id_type;
00055 int32_t request_id;
00056
00057 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _result_type;
00058 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > result;
00059
00060 typedef ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type;
00061 ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code;
00062
00063 typedef double _planning_time_type;
00064 double planning_time;
00065
00066 typedef double _smoothing_time_type;
00067 double smoothing_time;
00068
00069 typedef double _ik_time_type;
00070 double ik_time;
00071
00072 typedef double _time_to_execution_type;
00073 double time_to_execution;
00074
00075 typedef double _time_to_result_type;
00076 double time_to_result;
00077
00078 typedef uint8_t _preempted_type;
00079 uint8_t preempted;
00080
00081 typedef double _num_replans_type;
00082 double num_replans;
00083
00084 typedef double _trajectory_duration_type;
00085 double trajectory_duration;
00086
00087 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _planner_service_name_type;
00088 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > planner_service_name;
00089
00090
00091 private:
00092 static const char* __s_getDataType_() { return "move_arm_msgs/MoveArmStatistics"; }
00093 public:
00094 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00095
00096 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00097
00098 private:
00099 static const char* __s_getMD5Sum_() { return "d83dee1348791a0d1414257b41bc161f"; }
00100 public:
00101 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00102
00103 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00104
00105 private:
00106 static const char* __s_getMessageDefinition_() { return "int32 request_id\n\
00107 string result\n\
00108 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00109 \n\
00110 float64 planning_time\n\
00111 float64 smoothing_time\n\
00112 float64 ik_time\n\
00113 float64 time_to_execution\n\
00114 float64 time_to_result\n\
00115 \n\
00116 bool preempted\n\
00117 \n\
00118 float64 num_replans\n\
00119 float64 trajectory_duration\n\
00120 \n\
00121 string planner_service_name\n\
00122 ================================================================================\n\
00123 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00124 int32 val\n\
00125 \n\
00126 # overall behavior\n\
00127 int32 PLANNING_FAILED=-1\n\
00128 int32 SUCCESS=1\n\
00129 int32 TIMED_OUT=-2\n\
00130 \n\
00131 # start state errors\n\
00132 int32 START_STATE_IN_COLLISION=-3\n\
00133 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00134 \n\
00135 # goal errors\n\
00136 int32 GOAL_IN_COLLISION=-5\n\
00137 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00138 \n\
00139 # robot state\n\
00140 int32 INVALID_ROBOT_STATE=-7\n\
00141 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00142 \n\
00143 # planning request errors\n\
00144 int32 INVALID_PLANNER_ID=-9\n\
00145 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00146 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00147 int32 INVALID_GROUP_NAME=-12\n\
00148 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00149 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00150 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00151 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00152 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00153 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00154 \n\
00155 # state/trajectory monitor errors\n\
00156 int32 INVALID_TRAJECTORY=-19\n\
00157 int32 INVALID_INDEX=-20\n\
00158 int32 JOINT_LIMITS_VIOLATED=-21\n\
00159 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00160 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00161 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00162 int32 JOINTS_NOT_MOVING=-25\n\
00163 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00164 \n\
00165 # system errors\n\
00166 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00167 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00168 int32 ROBOT_STATE_STALE=-29\n\
00169 int32 SENSOR_INFO_STALE=-30\n\
00170 \n\
00171 # kinematics errors\n\
00172 int32 NO_IK_SOLUTION=-31\n\
00173 int32 INVALID_LINK_NAME=-32\n\
00174 int32 IK_LINK_IN_COLLISION=-33\n\
00175 int32 NO_FK_SOLUTION=-34\n\
00176 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00177 \n\
00178 # general errors\n\
00179 int32 INVALID_TIMEOUT=-36\n\
00180 \n\
00181 \n\
00182 "; }
00183 public:
00184 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00185
00186 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00187
00188 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00189 {
00190 ros::serialization::OStream stream(write_ptr, 1000000000);
00191 ros::serialization::serialize(stream, request_id);
00192 ros::serialization::serialize(stream, result);
00193 ros::serialization::serialize(stream, error_code);
00194 ros::serialization::serialize(stream, planning_time);
00195 ros::serialization::serialize(stream, smoothing_time);
00196 ros::serialization::serialize(stream, ik_time);
00197 ros::serialization::serialize(stream, time_to_execution);
00198 ros::serialization::serialize(stream, time_to_result);
00199 ros::serialization::serialize(stream, preempted);
00200 ros::serialization::serialize(stream, num_replans);
00201 ros::serialization::serialize(stream, trajectory_duration);
00202 ros::serialization::serialize(stream, planner_service_name);
00203 return stream.getData();
00204 }
00205
00206 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00207 {
00208 ros::serialization::IStream stream(read_ptr, 1000000000);
00209 ros::serialization::deserialize(stream, request_id);
00210 ros::serialization::deserialize(stream, result);
00211 ros::serialization::deserialize(stream, error_code);
00212 ros::serialization::deserialize(stream, planning_time);
00213 ros::serialization::deserialize(stream, smoothing_time);
00214 ros::serialization::deserialize(stream, ik_time);
00215 ros::serialization::deserialize(stream, time_to_execution);
00216 ros::serialization::deserialize(stream, time_to_result);
00217 ros::serialization::deserialize(stream, preempted);
00218 ros::serialization::deserialize(stream, num_replans);
00219 ros::serialization::deserialize(stream, trajectory_duration);
00220 ros::serialization::deserialize(stream, planner_service_name);
00221 return stream.getData();
00222 }
00223
00224 ROS_DEPRECATED virtual uint32_t serializationLength() const
00225 {
00226 uint32_t size = 0;
00227 size += ros::serialization::serializationLength(request_id);
00228 size += ros::serialization::serializationLength(result);
00229 size += ros::serialization::serializationLength(error_code);
00230 size += ros::serialization::serializationLength(planning_time);
00231 size += ros::serialization::serializationLength(smoothing_time);
00232 size += ros::serialization::serializationLength(ik_time);
00233 size += ros::serialization::serializationLength(time_to_execution);
00234 size += ros::serialization::serializationLength(time_to_result);
00235 size += ros::serialization::serializationLength(preempted);
00236 size += ros::serialization::serializationLength(num_replans);
00237 size += ros::serialization::serializationLength(trajectory_duration);
00238 size += ros::serialization::serializationLength(planner_service_name);
00239 return size;
00240 }
00241
00242 typedef boost::shared_ptr< ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> > Ptr;
00243 typedef boost::shared_ptr< ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> const> ConstPtr;
00244 };
00245 typedef ::move_arm_msgs::MoveArmStatistics_<std::allocator<void> > MoveArmStatistics;
00246
00247 typedef boost::shared_ptr< ::move_arm_msgs::MoveArmStatistics> MoveArmStatisticsPtr;
00248 typedef boost::shared_ptr< ::move_arm_msgs::MoveArmStatistics const> MoveArmStatisticsConstPtr;
00249
00250
00251 template<typename ContainerAllocator>
00252 std::ostream& operator<<(std::ostream& s, const ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> & v)
00253 {
00254 ros::message_operations::Printer< ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> >::stream(s, "", v);
00255 return s;}
00256
00257 }
00258
00259 namespace ros
00260 {
00261 namespace message_traits
00262 {
00263 template<class ContainerAllocator>
00264 struct MD5Sum< ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> > {
00265 static const char* value()
00266 {
00267 return "d83dee1348791a0d1414257b41bc161f";
00268 }
00269
00270 static const char* value(const ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> &) { return value(); }
00271 static const uint64_t static_value1 = 0xd83dee1348791a0dULL;
00272 static const uint64_t static_value2 = 0x1414257b41bc161fULL;
00273 };
00274
00275 template<class ContainerAllocator>
00276 struct DataType< ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> > {
00277 static const char* value()
00278 {
00279 return "move_arm_msgs/MoveArmStatistics";
00280 }
00281
00282 static const char* value(const ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> &) { return value(); }
00283 };
00284
00285 template<class ContainerAllocator>
00286 struct Definition< ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> > {
00287 static const char* value()
00288 {
00289 return "int32 request_id\n\
00290 string result\n\
00291 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00292 \n\
00293 float64 planning_time\n\
00294 float64 smoothing_time\n\
00295 float64 ik_time\n\
00296 float64 time_to_execution\n\
00297 float64 time_to_result\n\
00298 \n\
00299 bool preempted\n\
00300 \n\
00301 float64 num_replans\n\
00302 float64 trajectory_duration\n\
00303 \n\
00304 string planner_service_name\n\
00305 ================================================================================\n\
00306 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00307 int32 val\n\
00308 \n\
00309 # overall behavior\n\
00310 int32 PLANNING_FAILED=-1\n\
00311 int32 SUCCESS=1\n\
00312 int32 TIMED_OUT=-2\n\
00313 \n\
00314 # start state errors\n\
00315 int32 START_STATE_IN_COLLISION=-3\n\
00316 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00317 \n\
00318 # goal errors\n\
00319 int32 GOAL_IN_COLLISION=-5\n\
00320 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00321 \n\
00322 # robot state\n\
00323 int32 INVALID_ROBOT_STATE=-7\n\
00324 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00325 \n\
00326 # planning request errors\n\
00327 int32 INVALID_PLANNER_ID=-9\n\
00328 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00329 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00330 int32 INVALID_GROUP_NAME=-12\n\
00331 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00332 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00333 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00334 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00335 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00336 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00337 \n\
00338 # state/trajectory monitor errors\n\
00339 int32 INVALID_TRAJECTORY=-19\n\
00340 int32 INVALID_INDEX=-20\n\
00341 int32 JOINT_LIMITS_VIOLATED=-21\n\
00342 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00343 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00344 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00345 int32 JOINTS_NOT_MOVING=-25\n\
00346 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00347 \n\
00348 # system errors\n\
00349 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00350 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00351 int32 ROBOT_STATE_STALE=-29\n\
00352 int32 SENSOR_INFO_STALE=-30\n\
00353 \n\
00354 # kinematics errors\n\
00355 int32 NO_IK_SOLUTION=-31\n\
00356 int32 INVALID_LINK_NAME=-32\n\
00357 int32 IK_LINK_IN_COLLISION=-33\n\
00358 int32 NO_FK_SOLUTION=-34\n\
00359 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00360 \n\
00361 # general errors\n\
00362 int32 INVALID_TIMEOUT=-36\n\
00363 \n\
00364 \n\
00365 ";
00366 }
00367
00368 static const char* value(const ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> &) { return value(); }
00369 };
00370
00371 }
00372 }
00373
00374 namespace ros
00375 {
00376 namespace serialization
00377 {
00378
00379 template<class ContainerAllocator> struct Serializer< ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> >
00380 {
00381 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00382 {
00383 stream.next(m.request_id);
00384 stream.next(m.result);
00385 stream.next(m.error_code);
00386 stream.next(m.planning_time);
00387 stream.next(m.smoothing_time);
00388 stream.next(m.ik_time);
00389 stream.next(m.time_to_execution);
00390 stream.next(m.time_to_result);
00391 stream.next(m.preempted);
00392 stream.next(m.num_replans);
00393 stream.next(m.trajectory_duration);
00394 stream.next(m.planner_service_name);
00395 }
00396
00397 ROS_DECLARE_ALLINONE_SERIALIZER;
00398 };
00399 }
00400 }
00401
00402 namespace ros
00403 {
00404 namespace message_operations
00405 {
00406
00407 template<class ContainerAllocator>
00408 struct Printer< ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> >
00409 {
00410 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::move_arm_msgs::MoveArmStatistics_<ContainerAllocator> & v)
00411 {
00412 s << indent << "request_id: ";
00413 Printer<int32_t>::stream(s, indent + " ", v.request_id);
00414 s << indent << "result: ";
00415 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.result);
00416 s << indent << "error_code: ";
00417 s << std::endl;
00418 Printer< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> >::stream(s, indent + " ", v.error_code);
00419 s << indent << "planning_time: ";
00420 Printer<double>::stream(s, indent + " ", v.planning_time);
00421 s << indent << "smoothing_time: ";
00422 Printer<double>::stream(s, indent + " ", v.smoothing_time);
00423 s << indent << "ik_time: ";
00424 Printer<double>::stream(s, indent + " ", v.ik_time);
00425 s << indent << "time_to_execution: ";
00426 Printer<double>::stream(s, indent + " ", v.time_to_execution);
00427 s << indent << "time_to_result: ";
00428 Printer<double>::stream(s, indent + " ", v.time_to_result);
00429 s << indent << "preempted: ";
00430 Printer<uint8_t>::stream(s, indent + " ", v.preempted);
00431 s << indent << "num_replans: ";
00432 Printer<double>::stream(s, indent + " ", v.num_replans);
00433 s << indent << "trajectory_duration: ";
00434 Printer<double>::stream(s, indent + " ", v.trajectory_duration);
00435 s << indent << "planner_service_name: ";
00436 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.planner_service_name);
00437 }
00438 };
00439
00440
00441 }
00442 }
00443
00444 #endif // MOVE_ARM_MSGS_MESSAGE_MOVEARMSTATISTICS_H
00445