00001
00002 #ifndef MOTION_PLANNING_MSGS_MESSAGE_DISPLAYPATH_H
00003 #define MOTION_PLANNING_MSGS_MESSAGE_DISPLAYPATH_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/JointPath.h"
00014 #include "motion_planning_msgs/RobotState.h"
00015
00016 namespace motion_planning_msgs
00017 {
00018 template <class ContainerAllocator>
00019 struct DisplayPath_ : public ros::Message
00020 {
00021 typedef DisplayPath_<ContainerAllocator> Type;
00022
00023 DisplayPath_()
00024 : model_id()
00025 , path()
00026 , robot_state()
00027 {
00028 }
00029
00030 DisplayPath_(const ContainerAllocator& _alloc)
00031 : model_id(_alloc)
00032 , path(_alloc)
00033 , robot_state(_alloc)
00034 {
00035 }
00036
00037 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _model_id_type;
00038 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > model_id;
00039
00040 typedef ::motion_planning_msgs::JointPath_<ContainerAllocator> _path_type;
00041 ::motion_planning_msgs::JointPath_<ContainerAllocator> path;
00042
00043 typedef ::motion_planning_msgs::RobotState_<ContainerAllocator> _robot_state_type;
00044 ::motion_planning_msgs::RobotState_<ContainerAllocator> robot_state;
00045
00046
00047 private:
00048 static const char* __s_getDataType_() { return "motion_planning_msgs/DisplayPath"; }
00049 public:
00050 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00051
00052 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00053
00054 private:
00055 static const char* __s_getMD5Sum_() { return "b8dfa63887ffce8861d5beaef6427319"; }
00056 public:
00057 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00058
00059 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00060
00061 private:
00062 static const char* __s_getMessageDefinition_() { return "# The model id for which this path has been generated\n\
00063 string model_id\n\
00064 # The representation of the path contains position values for all the joints that are moving along the path\n\
00065 JointPath path\n\
00066 # The robot state is used to obtain positions for all/some of the joints of the robot. \n\
00067 # It is used by the path display node to determine the positions of the joints that are not specified in the joint path message above. \n\
00068 # If the robot state message contains joint position information for joints that are also mentioned in the joint path message, the positions in the joint path message will overwrite the positions specified in the robot state message. \n\
00069 RobotState robot_state\n\
00070 ================================================================================\n\
00071 MSG: motion_planning_msgs/JointPath\n\
00072 # This message defines a joint path \n\
00073 \n\
00074 # The standard ROS header\n\
00075 Header header\n\
00076 \n\
00077 # Vector of joint names for which positions are specified. \n\
00078 # The size of this vector must match the size of each waypoint below\n\
00079 string[] joint_names\n\
00080 \n\
00081 # A vector of waypoints. \n\
00082 # Each waypoint is a vector of joint positions. \n\
00083 # Each waypoint must have the same size as the vector of joint names\n\
00084 JointPathPoint[] points\n\
00085 ================================================================================\n\
00086 MSG: std_msgs/Header\n\
00087 # Standard metadata for higher-level stamped data types.\n\
00088 # This is generally used to communicate timestamped data \n\
00089 # in a particular coordinate frame.\n\
00090 # \n\
00091 # sequence ID: consecutively increasing ID \n\
00092 uint32 seq\n\
00093 #Two-integer timestamp that is expressed as:\n\
00094 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00095 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00096 # time-handling sugar is provided by the client library\n\
00097 time stamp\n\
00098 #Frame this data is associated with\n\
00099 # 0: no frame\n\
00100 # 1: global frame\n\
00101 string frame_id\n\
00102 \n\
00103 ================================================================================\n\
00104 MSG: motion_planning_msgs/JointPathPoint\n\
00105 # The joint path point contains a vector of joint positions.\n\
00106 float64[] positions\n\
00107 \n\
00108 ================================================================================\n\
00109 MSG: motion_planning_msgs/RobotState\n\
00110 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00111 sensor_msgs/JointState joint_state\n\
00112 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00113 ================================================================================\n\
00114 MSG: sensor_msgs/JointState\n\
00115 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00116 #\n\
00117 # The state of each joint (revolute or prismatic) is defined by:\n\
00118 # * the position of the joint (rad or m),\n\
00119 # * the velocity of the joint (rad/s or m/s) and \n\
00120 # * the effort that is applied in the joint (Nm or N).\n\
00121 #\n\
00122 # Each joint is uniquely identified by its name\n\
00123 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00124 # in one message have to be recorded at the same time.\n\
00125 #\n\
00126 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00127 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00128 # effort associated with them, you can leave the effort array empty. \n\
00129 #\n\
00130 # All arrays in this message should have the same size, or be empty.\n\
00131 # This is the only way to uniquely associate the joint name with the correct\n\
00132 # states.\n\
00133 \n\
00134 \n\
00135 Header header\n\
00136 \n\
00137 string[] name\n\
00138 float64[] position\n\
00139 float64[] velocity\n\
00140 float64[] effort\n\
00141 \n\
00142 ================================================================================\n\
00143 MSG: motion_planning_msgs/MultiDOFJointState\n\
00144 #A representation of a multi-dof joint state\n\
00145 time stamp\n\
00146 string[] joint_names\n\
00147 string[] frame_ids\n\
00148 string[] child_frame_ids\n\
00149 geometry_msgs/Pose[] poses\n\
00150 \n\
00151 ================================================================================\n\
00152 MSG: geometry_msgs/Pose\n\
00153 # A representation of pose in free space, composed of postion and orientation. \n\
00154 Point position\n\
00155 Quaternion orientation\n\
00156 \n\
00157 ================================================================================\n\
00158 MSG: geometry_msgs/Point\n\
00159 # This contains the position of a point in free space\n\
00160 float64 x\n\
00161 float64 y\n\
00162 float64 z\n\
00163 \n\
00164 ================================================================================\n\
00165 MSG: geometry_msgs/Quaternion\n\
00166 # This represents an orientation in free space in quaternion form.\n\
00167 \n\
00168 float64 x\n\
00169 float64 y\n\
00170 float64 z\n\
00171 float64 w\n\
00172 \n\
00173 "; }
00174 public:
00175 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00176
00177 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00178
00179 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00180 {
00181 ros::serialization::OStream stream(write_ptr, 1000000000);
00182 ros::serialization::serialize(stream, model_id);
00183 ros::serialization::serialize(stream, path);
00184 ros::serialization::serialize(stream, robot_state);
00185 return stream.getData();
00186 }
00187
00188 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00189 {
00190 ros::serialization::IStream stream(read_ptr, 1000000000);
00191 ros::serialization::deserialize(stream, model_id);
00192 ros::serialization::deserialize(stream, path);
00193 ros::serialization::deserialize(stream, robot_state);
00194 return stream.getData();
00195 }
00196
00197 ROS_DEPRECATED virtual uint32_t serializationLength() const
00198 {
00199 uint32_t size = 0;
00200 size += ros::serialization::serializationLength(model_id);
00201 size += ros::serialization::serializationLength(path);
00202 size += ros::serialization::serializationLength(robot_state);
00203 return size;
00204 }
00205
00206 typedef boost::shared_ptr< ::motion_planning_msgs::DisplayPath_<ContainerAllocator> > Ptr;
00207 typedef boost::shared_ptr< ::motion_planning_msgs::DisplayPath_<ContainerAllocator> const> ConstPtr;
00208 };
00209 typedef ::motion_planning_msgs::DisplayPath_<std::allocator<void> > DisplayPath;
00210
00211 typedef boost::shared_ptr< ::motion_planning_msgs::DisplayPath> DisplayPathPtr;
00212 typedef boost::shared_ptr< ::motion_planning_msgs::DisplayPath const> DisplayPathConstPtr;
00213
00214
00215 template<typename ContainerAllocator>
00216 std::ostream& operator<<(std::ostream& s, const ::motion_planning_msgs::DisplayPath_<ContainerAllocator> & v)
00217 {
00218 ros::message_operations::Printer< ::motion_planning_msgs::DisplayPath_<ContainerAllocator> >::stream(s, "", v);
00219 return s;}
00220
00221 }
00222
00223 namespace ros
00224 {
00225 namespace message_traits
00226 {
00227 template<class ContainerAllocator>
00228 struct MD5Sum< ::motion_planning_msgs::DisplayPath_<ContainerAllocator> > {
00229 static const char* value()
00230 {
00231 return "b8dfa63887ffce8861d5beaef6427319";
00232 }
00233
00234 static const char* value(const ::motion_planning_msgs::DisplayPath_<ContainerAllocator> &) { return value(); }
00235 static const uint64_t static_value1 = 0xb8dfa63887ffce88ULL;
00236 static const uint64_t static_value2 = 0x61d5beaef6427319ULL;
00237 };
00238
00239 template<class ContainerAllocator>
00240 struct DataType< ::motion_planning_msgs::DisplayPath_<ContainerAllocator> > {
00241 static const char* value()
00242 {
00243 return "motion_planning_msgs/DisplayPath";
00244 }
00245
00246 static const char* value(const ::motion_planning_msgs::DisplayPath_<ContainerAllocator> &) { return value(); }
00247 };
00248
00249 template<class ContainerAllocator>
00250 struct Definition< ::motion_planning_msgs::DisplayPath_<ContainerAllocator> > {
00251 static const char* value()
00252 {
00253 return "# The model id for which this path has been generated\n\
00254 string model_id\n\
00255 # The representation of the path contains position values for all the joints that are moving along the path\n\
00256 JointPath path\n\
00257 # The robot state is used to obtain positions for all/some of the joints of the robot. \n\
00258 # It is used by the path display node to determine the positions of the joints that are not specified in the joint path message above. \n\
00259 # If the robot state message contains joint position information for joints that are also mentioned in the joint path message, the positions in the joint path message will overwrite the positions specified in the robot state message. \n\
00260 RobotState robot_state\n\
00261 ================================================================================\n\
00262 MSG: motion_planning_msgs/JointPath\n\
00263 # This message defines a joint path \n\
00264 \n\
00265 # The standard ROS header\n\
00266 Header header\n\
00267 \n\
00268 # Vector of joint names for which positions are specified. \n\
00269 # The size of this vector must match the size of each waypoint below\n\
00270 string[] joint_names\n\
00271 \n\
00272 # A vector of waypoints. \n\
00273 # Each waypoint is a vector of joint positions. \n\
00274 # Each waypoint must have the same size as the vector of joint names\n\
00275 JointPathPoint[] points\n\
00276 ================================================================================\n\
00277 MSG: std_msgs/Header\n\
00278 # Standard metadata for higher-level stamped data types.\n\
00279 # This is generally used to communicate timestamped data \n\
00280 # in a particular coordinate frame.\n\
00281 # \n\
00282 # sequence ID: consecutively increasing ID \n\
00283 uint32 seq\n\
00284 #Two-integer timestamp that is expressed as:\n\
00285 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00286 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00287 # time-handling sugar is provided by the client library\n\
00288 time stamp\n\
00289 #Frame this data is associated with\n\
00290 # 0: no frame\n\
00291 # 1: global frame\n\
00292 string frame_id\n\
00293 \n\
00294 ================================================================================\n\
00295 MSG: motion_planning_msgs/JointPathPoint\n\
00296 # The joint path point contains a vector of joint positions.\n\
00297 float64[] positions\n\
00298 \n\
00299 ================================================================================\n\
00300 MSG: motion_planning_msgs/RobotState\n\
00301 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00302 sensor_msgs/JointState joint_state\n\
00303 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00304 ================================================================================\n\
00305 MSG: sensor_msgs/JointState\n\
00306 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00307 #\n\
00308 # The state of each joint (revolute or prismatic) is defined by:\n\
00309 # * the position of the joint (rad or m),\n\
00310 # * the velocity of the joint (rad/s or m/s) and \n\
00311 # * the effort that is applied in the joint (Nm or N).\n\
00312 #\n\
00313 # Each joint is uniquely identified by its name\n\
00314 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00315 # in one message have to be recorded at the same time.\n\
00316 #\n\
00317 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00318 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00319 # effort associated with them, you can leave the effort array empty. \n\
00320 #\n\
00321 # All arrays in this message should have the same size, or be empty.\n\
00322 # This is the only way to uniquely associate the joint name with the correct\n\
00323 # states.\n\
00324 \n\
00325 \n\
00326 Header header\n\
00327 \n\
00328 string[] name\n\
00329 float64[] position\n\
00330 float64[] velocity\n\
00331 float64[] effort\n\
00332 \n\
00333 ================================================================================\n\
00334 MSG: motion_planning_msgs/MultiDOFJointState\n\
00335 #A representation of a multi-dof joint state\n\
00336 time stamp\n\
00337 string[] joint_names\n\
00338 string[] frame_ids\n\
00339 string[] child_frame_ids\n\
00340 geometry_msgs/Pose[] poses\n\
00341 \n\
00342 ================================================================================\n\
00343 MSG: geometry_msgs/Pose\n\
00344 # A representation of pose in free space, composed of postion and orientation. \n\
00345 Point position\n\
00346 Quaternion orientation\n\
00347 \n\
00348 ================================================================================\n\
00349 MSG: geometry_msgs/Point\n\
00350 # This contains the position of a point in free space\n\
00351 float64 x\n\
00352 float64 y\n\
00353 float64 z\n\
00354 \n\
00355 ================================================================================\n\
00356 MSG: geometry_msgs/Quaternion\n\
00357 # This represents an orientation in free space in quaternion form.\n\
00358 \n\
00359 float64 x\n\
00360 float64 y\n\
00361 float64 z\n\
00362 float64 w\n\
00363 \n\
00364 ";
00365 }
00366
00367 static const char* value(const ::motion_planning_msgs::DisplayPath_<ContainerAllocator> &) { return value(); }
00368 };
00369
00370 }
00371 }
00372
00373 namespace ros
00374 {
00375 namespace serialization
00376 {
00377
00378 template<class ContainerAllocator> struct Serializer< ::motion_planning_msgs::DisplayPath_<ContainerAllocator> >
00379 {
00380 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00381 {
00382 stream.next(m.model_id);
00383 stream.next(m.path);
00384 stream.next(m.robot_state);
00385 }
00386
00387 ROS_DECLARE_ALLINONE_SERIALIZER;
00388 };
00389 }
00390 }
00391
00392 namespace ros
00393 {
00394 namespace message_operations
00395 {
00396
00397 template<class ContainerAllocator>
00398 struct Printer< ::motion_planning_msgs::DisplayPath_<ContainerAllocator> >
00399 {
00400 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::motion_planning_msgs::DisplayPath_<ContainerAllocator> & v)
00401 {
00402 s << indent << "model_id: ";
00403 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.model_id);
00404 s << indent << "path: ";
00405 s << std::endl;
00406 Printer< ::motion_planning_msgs::JointPath_<ContainerAllocator> >::stream(s, indent + " ", v.path);
00407 s << indent << "robot_state: ";
00408 s << std::endl;
00409 Printer< ::motion_planning_msgs::RobotState_<ContainerAllocator> >::stream(s, indent + " ", v.robot_state);
00410 }
00411 };
00412
00413
00414 }
00415 }
00416
00417 #endif // MOTION_PLANNING_MSGS_MESSAGE_DISPLAYPATH_H
00418