00001
00002 #ifndef NASA_R2_COMMON_MSGS_MESSAGE_LABELEDJOINTSTATE_H
00003 #define NASA_R2_COMMON_MSGS_MESSAGE_LABELEDJOINTSTATE_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/macros.h"
00014
00015 #include "ros/assert.h"
00016
00017 #include "std_msgs/Header.h"
00018
00019 namespace nasa_r2_common_msgs
00020 {
00021 template <class ContainerAllocator>
00022 struct LabeledJointState_ {
00023 typedef LabeledJointState_<ContainerAllocator> Type;
00024
00025 LabeledJointState_()
00026 : header()
00027 , originator()
00028 , name()
00029 , position()
00030 , velocity()
00031 , effort()
00032 {
00033 }
00034
00035 LabeledJointState_(const ContainerAllocator& _alloc)
00036 : header(_alloc)
00037 , originator(_alloc)
00038 , name(_alloc)
00039 , position(_alloc)
00040 , velocity(_alloc)
00041 , effort(_alloc)
00042 {
00043 }
00044
00045 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00046 ::std_msgs::Header_<ContainerAllocator> header;
00047
00048 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _originator_type;
00049 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > originator;
00050
00051 typedef std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > _name_type;
00052 std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other > name;
00053
00054 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _position_type;
00055 std::vector<double, typename ContainerAllocator::template rebind<double>::other > position;
00056
00057 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _velocity_type;
00058 std::vector<double, typename ContainerAllocator::template rebind<double>::other > velocity;
00059
00060 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _effort_type;
00061 std::vector<double, typename ContainerAllocator::template rebind<double>::other > effort;
00062
00063
00064 typedef boost::shared_ptr< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> > Ptr;
00065 typedef boost::shared_ptr< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> const> ConstPtr;
00066 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00067 };
00068 typedef ::nasa_r2_common_msgs::LabeledJointState_<std::allocator<void> > LabeledJointState;
00069
00070 typedef boost::shared_ptr< ::nasa_r2_common_msgs::LabeledJointState> LabeledJointStatePtr;
00071 typedef boost::shared_ptr< ::nasa_r2_common_msgs::LabeledJointState const> LabeledJointStateConstPtr;
00072
00073
00074 template<typename ContainerAllocator>
00075 std::ostream& operator<<(std::ostream& s, const ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> & v)
00076 {
00077 ros::message_operations::Printer< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> >::stream(s, "", v);
00078 return s;}
00079
00080 }
00081
00082 namespace ros
00083 {
00084 namespace message_traits
00085 {
00086 template<class ContainerAllocator> struct IsMessage< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> > : public TrueType {};
00087 template<class ContainerAllocator> struct IsMessage< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> const> : public TrueType {};
00088 template<class ContainerAllocator>
00089 struct MD5Sum< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> > {
00090 static const char* value()
00091 {
00092 return "dcbf606d25a558e3de2e3c95fa2eaca9";
00093 }
00094
00095 static const char* value(const ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> &) { return value(); }
00096 static const uint64_t static_value1 = 0xdcbf606d25a558e3ULL;
00097 static const uint64_t static_value2 = 0xde2e3c95fa2eaca9ULL;
00098 };
00099
00100 template<class ContainerAllocator>
00101 struct DataType< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> > {
00102 static const char* value()
00103 {
00104 return "nasa_r2_common_msgs/LabeledJointState";
00105 }
00106
00107 static const char* value(const ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> &) { return value(); }
00108 };
00109
00110 template<class ContainerAllocator>
00111 struct Definition< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> > {
00112 static const char* value()
00113 {
00114 return "# This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00115 #\n\
00116 # The state of each joint (revolute or prismatic) is defined by:\n\
00117 # * the position of the joint (rad or m),\n\
00118 # * the velocity of the joint (rad/s or m/s) and \n\
00119 # * the effort that is applied in the joint (Nm or N).\n\
00120 #\n\
00121 # Each joint is uniquely identified by its name\n\
00122 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00123 # in one message have to be recorded at the same time.\n\
00124 #\n\
00125 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00126 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00127 # effort associated with them, you can leave the effort array empty. \n\
00128 #\n\
00129 # All arrays in this message should have the same size, or be empty.\n\
00130 # This is the only way to uniquely associate the joint name with the correct\n\
00131 # states.\n\
00132 \n\
00133 \n\
00134 Header header\n\
00135 string originator\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: std_msgs/Header\n\
00144 # Standard metadata for higher-level stamped data types.\n\
00145 # This is generally used to communicate timestamped data \n\
00146 # in a particular coordinate frame.\n\
00147 # \n\
00148 # sequence ID: consecutively increasing ID \n\
00149 uint32 seq\n\
00150 #Two-integer timestamp that is expressed as:\n\
00151 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00152 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00153 # time-handling sugar is provided by the client library\n\
00154 time stamp\n\
00155 #Frame this data is associated with\n\
00156 # 0: no frame\n\
00157 # 1: global frame\n\
00158 string frame_id\n\
00159 \n\
00160 ";
00161 }
00162
00163 static const char* value(const ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> &) { return value(); }
00164 };
00165
00166 template<class ContainerAllocator> struct HasHeader< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> > : public TrueType {};
00167 template<class ContainerAllocator> struct HasHeader< const ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> > : public TrueType {};
00168 }
00169 }
00170
00171 namespace ros
00172 {
00173 namespace serialization
00174 {
00175
00176 template<class ContainerAllocator> struct Serializer< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> >
00177 {
00178 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00179 {
00180 stream.next(m.header);
00181 stream.next(m.originator);
00182 stream.next(m.name);
00183 stream.next(m.position);
00184 stream.next(m.velocity);
00185 stream.next(m.effort);
00186 }
00187
00188 ROS_DECLARE_ALLINONE_SERIALIZER;
00189 };
00190 }
00191 }
00192
00193 namespace ros
00194 {
00195 namespace message_operations
00196 {
00197
00198 template<class ContainerAllocator>
00199 struct Printer< ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> >
00200 {
00201 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::nasa_r2_common_msgs::LabeledJointState_<ContainerAllocator> & v)
00202 {
00203 s << indent << "header: ";
00204 s << std::endl;
00205 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00206 s << indent << "originator: ";
00207 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.originator);
00208 s << indent << "name[]" << std::endl;
00209 for (size_t i = 0; i < v.name.size(); ++i)
00210 {
00211 s << indent << " name[" << i << "]: ";
00212 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.name[i]);
00213 }
00214 s << indent << "position[]" << std::endl;
00215 for (size_t i = 0; i < v.position.size(); ++i)
00216 {
00217 s << indent << " position[" << i << "]: ";
00218 Printer<double>::stream(s, indent + " ", v.position[i]);
00219 }
00220 s << indent << "velocity[]" << std::endl;
00221 for (size_t i = 0; i < v.velocity.size(); ++i)
00222 {
00223 s << indent << " velocity[" << i << "]: ";
00224 Printer<double>::stream(s, indent + " ", v.velocity[i]);
00225 }
00226 s << indent << "effort[]" << std::endl;
00227 for (size_t i = 0; i < v.effort.size(); ++i)
00228 {
00229 s << indent << " effort[" << i << "]: ";
00230 Printer<double>::stream(s, indent + " ", v.effort[i]);
00231 }
00232 }
00233 };
00234
00235
00236 }
00237 }
00238
00239 #endif // NASA_R2_COMMON_MSGS_MESSAGE_LABELEDJOINTSTATE_H
00240