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