00001
00002 #ifndef MOTION_PLANNING_MSGS_SERVICE_FILTERJOINTTRAJECTORY_H
00003 #define MOTION_PLANNING_MSGS_SERVICE_FILTERJOINTTRAJECTORY_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 "ros/service_traits.h"
00014
00015 #include "trajectory_msgs/JointTrajectory.h"
00016 #include "motion_planning_msgs/JointLimits.h"
00017
00018
00019 #include "trajectory_msgs/JointTrajectory.h"
00020 #include "motion_planning_msgs/ArmNavigationErrorCodes.h"
00021
00022 namespace motion_planning_msgs
00023 {
00024 template <class ContainerAllocator>
00025 struct FilterJointTrajectoryRequest_ : public ros::Message
00026 {
00027 typedef FilterJointTrajectoryRequest_<ContainerAllocator> Type;
00028
00029 FilterJointTrajectoryRequest_()
00030 : trajectory()
00031 , limits()
00032 , allowed_time()
00033 {
00034 }
00035
00036 FilterJointTrajectoryRequest_(const ContainerAllocator& _alloc)
00037 : trajectory(_alloc)
00038 , limits(_alloc)
00039 , allowed_time()
00040 {
00041 }
00042
00043 typedef ::trajectory_msgs::JointTrajectory_<ContainerAllocator> _trajectory_type;
00044 ::trajectory_msgs::JointTrajectory_<ContainerAllocator> trajectory;
00045
00046 typedef std::vector< ::motion_planning_msgs::JointLimits_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::JointLimits_<ContainerAllocator> >::other > _limits_type;
00047 std::vector< ::motion_planning_msgs::JointLimits_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::JointLimits_<ContainerAllocator> >::other > limits;
00048
00049 typedef ros::Duration _allowed_time_type;
00050 ros::Duration allowed_time;
00051
00052
00053 ROS_DEPRECATED uint32_t get_limits_size() const { return (uint32_t)limits.size(); }
00054 ROS_DEPRECATED void set_limits_size(uint32_t size) { limits.resize((size_t)size); }
00055 ROS_DEPRECATED void get_limits_vec(std::vector< ::motion_planning_msgs::JointLimits_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::JointLimits_<ContainerAllocator> >::other > & vec) const { vec = this->limits; }
00056 ROS_DEPRECATED void set_limits_vec(const std::vector< ::motion_planning_msgs::JointLimits_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::JointLimits_<ContainerAllocator> >::other > & vec) { this->limits = vec; }
00057 private:
00058 static const char* __s_getDataType_() { return "motion_planning_msgs/FilterJointTrajectoryRequest"; }
00059 public:
00060 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00061
00062 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00063
00064 private:
00065 static const char* __s_getMD5Sum_() { return "e9d059896dc21ec7575231a5b0553f2c"; }
00066 public:
00067 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00068
00069 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00070
00071 private:
00072 static const char* __s_getServerMD5Sum_() { return "ca9260f17206fb6e1f0667bb6feb1521"; }
00073 public:
00074 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00075
00076 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00077
00078 private:
00079 static const char* __s_getMessageDefinition_() { return "\n\
00080 trajectory_msgs/JointTrajectory trajectory\n\
00081 \n\
00082 \n\
00083 motion_planning_msgs/JointLimits[] limits\n\
00084 \n\
00085 duration allowed_time\n\
00086 \n\
00087 ================================================================================\n\
00088 MSG: trajectory_msgs/JointTrajectory\n\
00089 Header header\n\
00090 string[] joint_names\n\
00091 JointTrajectoryPoint[] points\n\
00092 ================================================================================\n\
00093 MSG: std_msgs/Header\n\
00094 # Standard metadata for higher-level stamped data types.\n\
00095 # This is generally used to communicate timestamped data \n\
00096 # in a particular coordinate frame.\n\
00097 # \n\
00098 # sequence ID: consecutively increasing ID \n\
00099 uint32 seq\n\
00100 #Two-integer timestamp that is expressed as:\n\
00101 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00102 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00103 # time-handling sugar is provided by the client library\n\
00104 time stamp\n\
00105 #Frame this data is associated with\n\
00106 # 0: no frame\n\
00107 # 1: global frame\n\
00108 string frame_id\n\
00109 \n\
00110 ================================================================================\n\
00111 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00112 float64[] positions\n\
00113 float64[] velocities\n\
00114 float64[] accelerations\n\
00115 duration time_from_start\n\
00116 ================================================================================\n\
00117 MSG: motion_planning_msgs/JointLimits\n\
00118 # This message contains information about limits of a particular joint (or control dimension)\n\
00119 string joint_name\n\
00120 \n\
00121 # true if the joint has position limits\n\
00122 uint8 has_position_limits\n\
00123 \n\
00124 # min and max position limits\n\
00125 float64 min_position\n\
00126 float64 max_position\n\
00127 \n\
00128 # true if joint has velocity limits\n\
00129 uint8 has_velocity_limits\n\
00130 \n\
00131 # max velocity limit\n\
00132 float64 max_velocity\n\
00133 # min_velocity is assumed to be -max_velocity\n\
00134 \n\
00135 # true if joint has acceleration limits\n\
00136 uint8 has_acceleration_limits\n\
00137 # max acceleration limit\n\
00138 float64 max_acceleration\n\
00139 # min_acceleration is assumed to be -max_acceleration\n\
00140 \n\
00141 "; }
00142 public:
00143 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00144
00145 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00146
00147 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00148 {
00149 ros::serialization::OStream stream(write_ptr, 1000000000);
00150 ros::serialization::serialize(stream, trajectory);
00151 ros::serialization::serialize(stream, limits);
00152 ros::serialization::serialize(stream, allowed_time);
00153 return stream.getData();
00154 }
00155
00156 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00157 {
00158 ros::serialization::IStream stream(read_ptr, 1000000000);
00159 ros::serialization::deserialize(stream, trajectory);
00160 ros::serialization::deserialize(stream, limits);
00161 ros::serialization::deserialize(stream, allowed_time);
00162 return stream.getData();
00163 }
00164
00165 ROS_DEPRECATED virtual uint32_t serializationLength() const
00166 {
00167 uint32_t size = 0;
00168 size += ros::serialization::serializationLength(trajectory);
00169 size += ros::serialization::serializationLength(limits);
00170 size += ros::serialization::serializationLength(allowed_time);
00171 return size;
00172 }
00173
00174 typedef boost::shared_ptr< ::motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> > Ptr;
00175 typedef boost::shared_ptr< ::motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> const> ConstPtr;
00176 };
00177 typedef ::motion_planning_msgs::FilterJointTrajectoryRequest_<std::allocator<void> > FilterJointTrajectoryRequest;
00178
00179 typedef boost::shared_ptr< ::motion_planning_msgs::FilterJointTrajectoryRequest> FilterJointTrajectoryRequestPtr;
00180 typedef boost::shared_ptr< ::motion_planning_msgs::FilterJointTrajectoryRequest const> FilterJointTrajectoryRequestConstPtr;
00181
00182
00183 template <class ContainerAllocator>
00184 struct FilterJointTrajectoryResponse_ : public ros::Message
00185 {
00186 typedef FilterJointTrajectoryResponse_<ContainerAllocator> Type;
00187
00188 FilterJointTrajectoryResponse_()
00189 : trajectory()
00190 , error_code()
00191 {
00192 }
00193
00194 FilterJointTrajectoryResponse_(const ContainerAllocator& _alloc)
00195 : trajectory(_alloc)
00196 , error_code(_alloc)
00197 {
00198 }
00199
00200 typedef ::trajectory_msgs::JointTrajectory_<ContainerAllocator> _trajectory_type;
00201 ::trajectory_msgs::JointTrajectory_<ContainerAllocator> trajectory;
00202
00203 typedef ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type;
00204 ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code;
00205
00206
00207 private:
00208 static const char* __s_getDataType_() { return "motion_planning_msgs/FilterJointTrajectoryResponse"; }
00209 public:
00210 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00211
00212 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00213
00214 private:
00215 static const char* __s_getMD5Sum_() { return "5b4da90f4032f9ac3da9abfb05f766cc"; }
00216 public:
00217 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00218
00219 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00220
00221 private:
00222 static const char* __s_getServerMD5Sum_() { return "ca9260f17206fb6e1f0667bb6feb1521"; }
00223 public:
00224 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00225
00226 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00227
00228 private:
00229 static const char* __s_getMessageDefinition_() { return "trajectory_msgs/JointTrajectory trajectory\n\
00230 ArmNavigationErrorCodes error_code\n\
00231 \n\
00232 ================================================================================\n\
00233 MSG: trajectory_msgs/JointTrajectory\n\
00234 Header header\n\
00235 string[] joint_names\n\
00236 JointTrajectoryPoint[] points\n\
00237 ================================================================================\n\
00238 MSG: std_msgs/Header\n\
00239 # Standard metadata for higher-level stamped data types.\n\
00240 # This is generally used to communicate timestamped data \n\
00241 # in a particular coordinate frame.\n\
00242 # \n\
00243 # sequence ID: consecutively increasing ID \n\
00244 uint32 seq\n\
00245 #Two-integer timestamp that is expressed as:\n\
00246 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00247 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00248 # time-handling sugar is provided by the client library\n\
00249 time stamp\n\
00250 #Frame this data is associated with\n\
00251 # 0: no frame\n\
00252 # 1: global frame\n\
00253 string frame_id\n\
00254 \n\
00255 ================================================================================\n\
00256 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00257 float64[] positions\n\
00258 float64[] velocities\n\
00259 float64[] accelerations\n\
00260 duration time_from_start\n\
00261 ================================================================================\n\
00262 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00263 int32 val\n\
00264 \n\
00265 # overall behavior\n\
00266 int32 PLANNING_FAILED=-1\n\
00267 int32 SUCCESS=1\n\
00268 int32 TIMED_OUT=-2\n\
00269 \n\
00270 # start state errors\n\
00271 int32 START_STATE_IN_COLLISION=-3\n\
00272 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00273 \n\
00274 # goal errors\n\
00275 int32 GOAL_IN_COLLISION=-5\n\
00276 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00277 \n\
00278 # robot state\n\
00279 int32 INVALID_ROBOT_STATE=-7\n\
00280 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00281 \n\
00282 # planning request errors\n\
00283 int32 INVALID_PLANNER_ID=-9\n\
00284 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00285 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00286 int32 INVALID_GROUP_NAME=-12\n\
00287 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00288 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00289 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00290 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00291 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00292 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00293 \n\
00294 # state/trajectory monitor errors\n\
00295 int32 INVALID_TRAJECTORY=-19\n\
00296 int32 INVALID_INDEX=-20\n\
00297 int32 JOINT_LIMITS_VIOLATED=-21\n\
00298 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00299 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00300 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00301 int32 JOINTS_NOT_MOVING=-25\n\
00302 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00303 \n\
00304 # system errors\n\
00305 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00306 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00307 int32 ROBOT_STATE_STALE=-29\n\
00308 int32 SENSOR_INFO_STALE=-30\n\
00309 \n\
00310 # kinematics errors\n\
00311 int32 NO_IK_SOLUTION=-31\n\
00312 int32 INVALID_LINK_NAME=-32\n\
00313 int32 IK_LINK_IN_COLLISION=-33\n\
00314 int32 NO_FK_SOLUTION=-34\n\
00315 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00316 \n\
00317 # general errors\n\
00318 int32 INVALID_TIMEOUT=-36\n\
00319 \n\
00320 \n\
00321 "; }
00322 public:
00323 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00324
00325 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00326
00327 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00328 {
00329 ros::serialization::OStream stream(write_ptr, 1000000000);
00330 ros::serialization::serialize(stream, trajectory);
00331 ros::serialization::serialize(stream, error_code);
00332 return stream.getData();
00333 }
00334
00335 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00336 {
00337 ros::serialization::IStream stream(read_ptr, 1000000000);
00338 ros::serialization::deserialize(stream, trajectory);
00339 ros::serialization::deserialize(stream, error_code);
00340 return stream.getData();
00341 }
00342
00343 ROS_DEPRECATED virtual uint32_t serializationLength() const
00344 {
00345 uint32_t size = 0;
00346 size += ros::serialization::serializationLength(trajectory);
00347 size += ros::serialization::serializationLength(error_code);
00348 return size;
00349 }
00350
00351 typedef boost::shared_ptr< ::motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> > Ptr;
00352 typedef boost::shared_ptr< ::motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> const> ConstPtr;
00353 };
00354 typedef ::motion_planning_msgs::FilterJointTrajectoryResponse_<std::allocator<void> > FilterJointTrajectoryResponse;
00355
00356 typedef boost::shared_ptr< ::motion_planning_msgs::FilterJointTrajectoryResponse> FilterJointTrajectoryResponsePtr;
00357 typedef boost::shared_ptr< ::motion_planning_msgs::FilterJointTrajectoryResponse const> FilterJointTrajectoryResponseConstPtr;
00358
00359 struct FilterJointTrajectory
00360 {
00361
00362 typedef FilterJointTrajectoryRequest Request;
00363 typedef FilterJointTrajectoryResponse Response;
00364 Request request;
00365 Response response;
00366
00367 typedef Request RequestType;
00368 typedef Response ResponseType;
00369 };
00370 }
00371
00372 namespace ros
00373 {
00374 namespace message_traits
00375 {
00376 template<class ContainerAllocator>
00377 struct MD5Sum< ::motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> > {
00378 static const char* value()
00379 {
00380 return "e9d059896dc21ec7575231a5b0553f2c";
00381 }
00382
00383 static const char* value(const ::motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> &) { return value(); }
00384 static const uint64_t static_value1 = 0xe9d059896dc21ec7ULL;
00385 static const uint64_t static_value2 = 0x575231a5b0553f2cULL;
00386 };
00387
00388 template<class ContainerAllocator>
00389 struct DataType< ::motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> > {
00390 static const char* value()
00391 {
00392 return "motion_planning_msgs/FilterJointTrajectoryRequest";
00393 }
00394
00395 static const char* value(const ::motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> &) { return value(); }
00396 };
00397
00398 template<class ContainerAllocator>
00399 struct Definition< ::motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> > {
00400 static const char* value()
00401 {
00402 return "\n\
00403 trajectory_msgs/JointTrajectory trajectory\n\
00404 \n\
00405 \n\
00406 motion_planning_msgs/JointLimits[] limits\n\
00407 \n\
00408 duration allowed_time\n\
00409 \n\
00410 ================================================================================\n\
00411 MSG: trajectory_msgs/JointTrajectory\n\
00412 Header header\n\
00413 string[] joint_names\n\
00414 JointTrajectoryPoint[] points\n\
00415 ================================================================================\n\
00416 MSG: std_msgs/Header\n\
00417 # Standard metadata for higher-level stamped data types.\n\
00418 # This is generally used to communicate timestamped data \n\
00419 # in a particular coordinate frame.\n\
00420 # \n\
00421 # sequence ID: consecutively increasing ID \n\
00422 uint32 seq\n\
00423 #Two-integer timestamp that is expressed as:\n\
00424 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00425 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00426 # time-handling sugar is provided by the client library\n\
00427 time stamp\n\
00428 #Frame this data is associated with\n\
00429 # 0: no frame\n\
00430 # 1: global frame\n\
00431 string frame_id\n\
00432 \n\
00433 ================================================================================\n\
00434 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00435 float64[] positions\n\
00436 float64[] velocities\n\
00437 float64[] accelerations\n\
00438 duration time_from_start\n\
00439 ================================================================================\n\
00440 MSG: motion_planning_msgs/JointLimits\n\
00441 # This message contains information about limits of a particular joint (or control dimension)\n\
00442 string joint_name\n\
00443 \n\
00444 # true if the joint has position limits\n\
00445 uint8 has_position_limits\n\
00446 \n\
00447 # min and max position limits\n\
00448 float64 min_position\n\
00449 float64 max_position\n\
00450 \n\
00451 # true if joint has velocity limits\n\
00452 uint8 has_velocity_limits\n\
00453 \n\
00454 # max velocity limit\n\
00455 float64 max_velocity\n\
00456 # min_velocity is assumed to be -max_velocity\n\
00457 \n\
00458 # true if joint has acceleration limits\n\
00459 uint8 has_acceleration_limits\n\
00460 # max acceleration limit\n\
00461 float64 max_acceleration\n\
00462 # min_acceleration is assumed to be -max_acceleration\n\
00463 \n\
00464 ";
00465 }
00466
00467 static const char* value(const ::motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> &) { return value(); }
00468 };
00469
00470 }
00471 }
00472
00473
00474 namespace ros
00475 {
00476 namespace message_traits
00477 {
00478 template<class ContainerAllocator>
00479 struct MD5Sum< ::motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> > {
00480 static const char* value()
00481 {
00482 return "5b4da90f4032f9ac3da9abfb05f766cc";
00483 }
00484
00485 static const char* value(const ::motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> &) { return value(); }
00486 static const uint64_t static_value1 = 0x5b4da90f4032f9acULL;
00487 static const uint64_t static_value2 = 0x3da9abfb05f766ccULL;
00488 };
00489
00490 template<class ContainerAllocator>
00491 struct DataType< ::motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> > {
00492 static const char* value()
00493 {
00494 return "motion_planning_msgs/FilterJointTrajectoryResponse";
00495 }
00496
00497 static const char* value(const ::motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> &) { return value(); }
00498 };
00499
00500 template<class ContainerAllocator>
00501 struct Definition< ::motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> > {
00502 static const char* value()
00503 {
00504 return "trajectory_msgs/JointTrajectory trajectory\n\
00505 ArmNavigationErrorCodes error_code\n\
00506 \n\
00507 ================================================================================\n\
00508 MSG: trajectory_msgs/JointTrajectory\n\
00509 Header header\n\
00510 string[] joint_names\n\
00511 JointTrajectoryPoint[] points\n\
00512 ================================================================================\n\
00513 MSG: std_msgs/Header\n\
00514 # Standard metadata for higher-level stamped data types.\n\
00515 # This is generally used to communicate timestamped data \n\
00516 # in a particular coordinate frame.\n\
00517 # \n\
00518 # sequence ID: consecutively increasing ID \n\
00519 uint32 seq\n\
00520 #Two-integer timestamp that is expressed as:\n\
00521 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00522 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00523 # time-handling sugar is provided by the client library\n\
00524 time stamp\n\
00525 #Frame this data is associated with\n\
00526 # 0: no frame\n\
00527 # 1: global frame\n\
00528 string frame_id\n\
00529 \n\
00530 ================================================================================\n\
00531 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00532 float64[] positions\n\
00533 float64[] velocities\n\
00534 float64[] accelerations\n\
00535 duration time_from_start\n\
00536 ================================================================================\n\
00537 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00538 int32 val\n\
00539 \n\
00540 # overall behavior\n\
00541 int32 PLANNING_FAILED=-1\n\
00542 int32 SUCCESS=1\n\
00543 int32 TIMED_OUT=-2\n\
00544 \n\
00545 # start state errors\n\
00546 int32 START_STATE_IN_COLLISION=-3\n\
00547 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00548 \n\
00549 # goal errors\n\
00550 int32 GOAL_IN_COLLISION=-5\n\
00551 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00552 \n\
00553 # robot state\n\
00554 int32 INVALID_ROBOT_STATE=-7\n\
00555 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00556 \n\
00557 # planning request errors\n\
00558 int32 INVALID_PLANNER_ID=-9\n\
00559 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00560 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00561 int32 INVALID_GROUP_NAME=-12\n\
00562 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00563 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00564 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00565 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00566 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00567 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00568 \n\
00569 # state/trajectory monitor errors\n\
00570 int32 INVALID_TRAJECTORY=-19\n\
00571 int32 INVALID_INDEX=-20\n\
00572 int32 JOINT_LIMITS_VIOLATED=-21\n\
00573 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00574 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00575 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00576 int32 JOINTS_NOT_MOVING=-25\n\
00577 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00578 \n\
00579 # system errors\n\
00580 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00581 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00582 int32 ROBOT_STATE_STALE=-29\n\
00583 int32 SENSOR_INFO_STALE=-30\n\
00584 \n\
00585 # kinematics errors\n\
00586 int32 NO_IK_SOLUTION=-31\n\
00587 int32 INVALID_LINK_NAME=-32\n\
00588 int32 IK_LINK_IN_COLLISION=-33\n\
00589 int32 NO_FK_SOLUTION=-34\n\
00590 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00591 \n\
00592 # general errors\n\
00593 int32 INVALID_TIMEOUT=-36\n\
00594 \n\
00595 \n\
00596 ";
00597 }
00598
00599 static const char* value(const ::motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> &) { return value(); }
00600 };
00601
00602 }
00603 }
00604
00605 namespace ros
00606 {
00607 namespace serialization
00608 {
00609
00610 template<class ContainerAllocator> struct Serializer< ::motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> >
00611 {
00612 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00613 {
00614 stream.next(m.trajectory);
00615 stream.next(m.limits);
00616 stream.next(m.allowed_time);
00617 }
00618
00619 ROS_DECLARE_ALLINONE_SERIALIZER;
00620 };
00621 }
00622 }
00623
00624
00625 namespace ros
00626 {
00627 namespace serialization
00628 {
00629
00630 template<class ContainerAllocator> struct Serializer< ::motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> >
00631 {
00632 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00633 {
00634 stream.next(m.trajectory);
00635 stream.next(m.error_code);
00636 }
00637
00638 ROS_DECLARE_ALLINONE_SERIALIZER;
00639 };
00640 }
00641 }
00642
00643 namespace ros
00644 {
00645 namespace service_traits
00646 {
00647 template<>
00648 struct MD5Sum<motion_planning_msgs::FilterJointTrajectory> {
00649 static const char* value()
00650 {
00651 return "ca9260f17206fb6e1f0667bb6feb1521";
00652 }
00653
00654 static const char* value(const motion_planning_msgs::FilterJointTrajectory&) { return value(); }
00655 };
00656
00657 template<>
00658 struct DataType<motion_planning_msgs::FilterJointTrajectory> {
00659 static const char* value()
00660 {
00661 return "motion_planning_msgs/FilterJointTrajectory";
00662 }
00663
00664 static const char* value(const motion_planning_msgs::FilterJointTrajectory&) { return value(); }
00665 };
00666
00667 template<class ContainerAllocator>
00668 struct MD5Sum<motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> > {
00669 static const char* value()
00670 {
00671 return "ca9260f17206fb6e1f0667bb6feb1521";
00672 }
00673
00674 static const char* value(const motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> &) { return value(); }
00675 };
00676
00677 template<class ContainerAllocator>
00678 struct DataType<motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> > {
00679 static const char* value()
00680 {
00681 return "motion_planning_msgs/FilterJointTrajectory";
00682 }
00683
00684 static const char* value(const motion_planning_msgs::FilterJointTrajectoryRequest_<ContainerAllocator> &) { return value(); }
00685 };
00686
00687 template<class ContainerAllocator>
00688 struct MD5Sum<motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> > {
00689 static const char* value()
00690 {
00691 return "ca9260f17206fb6e1f0667bb6feb1521";
00692 }
00693
00694 static const char* value(const motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> &) { return value(); }
00695 };
00696
00697 template<class ContainerAllocator>
00698 struct DataType<motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> > {
00699 static const char* value()
00700 {
00701 return "motion_planning_msgs/FilterJointTrajectory";
00702 }
00703
00704 static const char* value(const motion_planning_msgs::FilterJointTrajectoryResponse_<ContainerAllocator> &) { return value(); }
00705 };
00706
00707 }
00708 }
00709
00710 #endif // MOTION_PLANNING_MSGS_SERVICE_FILTERJOINTTRAJECTORY_H
00711