00001
00002 #ifndef SENSOR_MSGS_MESSAGE_JOINTSTATE_H
00003 #define SENSOR_MSGS_MESSAGE_JOINTSTATE_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 "std_msgs/Header.h"
00014
00015 namespace sensor_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct JointState_ : public ros::Message
00019 {
00020 typedef JointState_<ContainerAllocator> Type;
00021
00022 JointState_()
00023 : header()
00024 , name()
00025 , position()
00026 , velocity()
00027 , effort()
00028 {
00029 }
00030
00031 JointState_(const ContainerAllocator& _alloc)
00032 : header(_alloc)
00033 , name(_alloc)
00034 , position(_alloc)
00035 , velocity(_alloc)
00036 , effort(_alloc)
00037 {
00038 }
00039
00040 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00041 ::std_msgs::Header_<ContainerAllocator> header;
00042
00043 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;
00044 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;
00045
00046 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _position_type;
00047 std::vector<double, typename ContainerAllocator::template rebind<double>::other > position;
00048
00049 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _velocity_type;
00050 std::vector<double, typename ContainerAllocator::template rebind<double>::other > velocity;
00051
00052 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _effort_type;
00053 std::vector<double, typename ContainerAllocator::template rebind<double>::other > effort;
00054
00055
00056 ROS_DEPRECATED uint32_t get_name_size() const { return (uint32_t)name.size(); }
00057 ROS_DEPRECATED void set_name_size(uint32_t size) { name.resize((size_t)size); }
00058 ROS_DEPRECATED void get_name_vec(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 > & vec) const { vec = this->name; }
00059 ROS_DEPRECATED void set_name_vec(const 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 > & vec) { this->name = vec; }
00060 ROS_DEPRECATED uint32_t get_position_size() const { return (uint32_t)position.size(); }
00061 ROS_DEPRECATED void set_position_size(uint32_t size) { position.resize((size_t)size); }
00062 ROS_DEPRECATED void get_position_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->position; }
00063 ROS_DEPRECATED void set_position_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->position = vec; }
00064 ROS_DEPRECATED uint32_t get_velocity_size() const { return (uint32_t)velocity.size(); }
00065 ROS_DEPRECATED void set_velocity_size(uint32_t size) { velocity.resize((size_t)size); }
00066 ROS_DEPRECATED void get_velocity_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->velocity; }
00067 ROS_DEPRECATED void set_velocity_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->velocity = vec; }
00068 ROS_DEPRECATED uint32_t get_effort_size() const { return (uint32_t)effort.size(); }
00069 ROS_DEPRECATED void set_effort_size(uint32_t size) { effort.resize((size_t)size); }
00070 ROS_DEPRECATED void get_effort_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->effort; }
00071 ROS_DEPRECATED void set_effort_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->effort = vec; }
00072 private:
00073 static const char* __s_getDataType_() { return "sensor_msgs/JointState"; }
00074 public:
00075 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00076
00077 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00078
00079 private:
00080 static const char* __s_getMD5Sum_() { return "3066dcd76a6cfaef579bd0f34173e9fd"; }
00081 public:
00082 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00083
00084 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00085
00086 private:
00087 static const char* __s_getMessageDefinition_() { return "# This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00088 #\n\
00089 # The state of each joint (revolute or prismatic) is defined by:\n\
00090 # * the position of the joint (rad or m),\n\
00091 # * the velocity of the joint (rad/s or m/s) and \n\
00092 # * the effort that is applied in the joint (Nm or N).\n\
00093 #\n\
00094 # Each joint is uniquely identified by its name\n\
00095 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00096 # in one message have to be recorded at the same time.\n\
00097 #\n\
00098 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00099 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00100 # effort associated with them, you can leave the effort array empty. \n\
00101 #\n\
00102 # All arrays in this message should have the same size, or be empty.\n\
00103 # This is the only way to uniquely associate the joint name with the correct\n\
00104 # states.\n\
00105 \n\
00106 \n\
00107 Header header\n\
00108 \n\
00109 string[] name\n\
00110 float64[] position\n\
00111 float64[] velocity\n\
00112 float64[] effort\n\
00113 \n\
00114 ================================================================================\n\
00115 MSG: std_msgs/Header\n\
00116 # Standard metadata for higher-level stamped data types.\n\
00117 # This is generally used to communicate timestamped data \n\
00118 # in a particular coordinate frame.\n\
00119 # \n\
00120 # sequence ID: consecutively increasing ID \n\
00121 uint32 seq\n\
00122 #Two-integer timestamp that is expressed as:\n\
00123 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00124 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00125 # time-handling sugar is provided by the client library\n\
00126 time stamp\n\
00127 #Frame this data is associated with\n\
00128 # 0: no frame\n\
00129 # 1: global frame\n\
00130 string frame_id\n\
00131 \n\
00132 "; }
00133 public:
00134 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00135
00136 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00137
00138 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00139 {
00140 ros::serialization::OStream stream(write_ptr, 1000000000);
00141 ros::serialization::serialize(stream, header);
00142 ros::serialization::serialize(stream, name);
00143 ros::serialization::serialize(stream, position);
00144 ros::serialization::serialize(stream, velocity);
00145 ros::serialization::serialize(stream, effort);
00146 return stream.getData();
00147 }
00148
00149 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00150 {
00151 ros::serialization::IStream stream(read_ptr, 1000000000);
00152 ros::serialization::deserialize(stream, header);
00153 ros::serialization::deserialize(stream, name);
00154 ros::serialization::deserialize(stream, position);
00155 ros::serialization::deserialize(stream, velocity);
00156 ros::serialization::deserialize(stream, effort);
00157 return stream.getData();
00158 }
00159
00160 ROS_DEPRECATED virtual uint32_t serializationLength() const
00161 {
00162 uint32_t size = 0;
00163 size += ros::serialization::serializationLength(header);
00164 size += ros::serialization::serializationLength(name);
00165 size += ros::serialization::serializationLength(position);
00166 size += ros::serialization::serializationLength(velocity);
00167 size += ros::serialization::serializationLength(effort);
00168 return size;
00169 }
00170
00171 typedef boost::shared_ptr< ::sensor_msgs::JointState_<ContainerAllocator> > Ptr;
00172 typedef boost::shared_ptr< ::sensor_msgs::JointState_<ContainerAllocator> const> ConstPtr;
00173 };
00174 typedef ::sensor_msgs::JointState_<std::allocator<void> > JointState;
00175
00176 typedef boost::shared_ptr< ::sensor_msgs::JointState> JointStatePtr;
00177 typedef boost::shared_ptr< ::sensor_msgs::JointState const> JointStateConstPtr;
00178
00179
00180 template<typename ContainerAllocator>
00181 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::JointState_<ContainerAllocator> & v)
00182 {
00183 ros::message_operations::Printer< ::sensor_msgs::JointState_<ContainerAllocator> >::stream(s, "", v);
00184 return s;}
00185
00186 }
00187
00188 namespace ros
00189 {
00190 namespace message_traits
00191 {
00192 template<class ContainerAllocator>
00193 struct MD5Sum< ::sensor_msgs::JointState_<ContainerAllocator> > {
00194 static const char* value()
00195 {
00196 return "3066dcd76a6cfaef579bd0f34173e9fd";
00197 }
00198
00199 static const char* value(const ::sensor_msgs::JointState_<ContainerAllocator> &) { return value(); }
00200 static const uint64_t static_value1 = 0x3066dcd76a6cfaefULL;
00201 static const uint64_t static_value2 = 0x579bd0f34173e9fdULL;
00202 };
00203
00204 template<class ContainerAllocator>
00205 struct DataType< ::sensor_msgs::JointState_<ContainerAllocator> > {
00206 static const char* value()
00207 {
00208 return "sensor_msgs/JointState";
00209 }
00210
00211 static const char* value(const ::sensor_msgs::JointState_<ContainerAllocator> &) { return value(); }
00212 };
00213
00214 template<class ContainerAllocator>
00215 struct Definition< ::sensor_msgs::JointState_<ContainerAllocator> > {
00216 static const char* value()
00217 {
00218 return "# This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00219 #\n\
00220 # The state of each joint (revolute or prismatic) is defined by:\n\
00221 # * the position of the joint (rad or m),\n\
00222 # * the velocity of the joint (rad/s or m/s) and \n\
00223 # * the effort that is applied in the joint (Nm or N).\n\
00224 #\n\
00225 # Each joint is uniquely identified by its name\n\
00226 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00227 # in one message have to be recorded at the same time.\n\
00228 #\n\
00229 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00230 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00231 # effort associated with them, you can leave the effort array empty. \n\
00232 #\n\
00233 # All arrays in this message should have the same size, or be empty.\n\
00234 # This is the only way to uniquely associate the joint name with the correct\n\
00235 # states.\n\
00236 \n\
00237 \n\
00238 Header header\n\
00239 \n\
00240 string[] name\n\
00241 float64[] position\n\
00242 float64[] velocity\n\
00243 float64[] effort\n\
00244 \n\
00245 ================================================================================\n\
00246 MSG: std_msgs/Header\n\
00247 # Standard metadata for higher-level stamped data types.\n\
00248 # This is generally used to communicate timestamped data \n\
00249 # in a particular coordinate frame.\n\
00250 # \n\
00251 # sequence ID: consecutively increasing ID \n\
00252 uint32 seq\n\
00253 #Two-integer timestamp that is expressed as:\n\
00254 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00255 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00256 # time-handling sugar is provided by the client library\n\
00257 time stamp\n\
00258 #Frame this data is associated with\n\
00259 # 0: no frame\n\
00260 # 1: global frame\n\
00261 string frame_id\n\
00262 \n\
00263 ";
00264 }
00265
00266 static const char* value(const ::sensor_msgs::JointState_<ContainerAllocator> &) { return value(); }
00267 };
00268
00269 template<class ContainerAllocator> struct HasHeader< ::sensor_msgs::JointState_<ContainerAllocator> > : public TrueType {};
00270 template<class ContainerAllocator> struct HasHeader< const ::sensor_msgs::JointState_<ContainerAllocator> > : public TrueType {};
00271 }
00272 }
00273
00274 namespace ros
00275 {
00276 namespace serialization
00277 {
00278
00279 template<class ContainerAllocator> struct Serializer< ::sensor_msgs::JointState_<ContainerAllocator> >
00280 {
00281 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00282 {
00283 stream.next(m.header);
00284 stream.next(m.name);
00285 stream.next(m.position);
00286 stream.next(m.velocity);
00287 stream.next(m.effort);
00288 }
00289
00290 ROS_DECLARE_ALLINONE_SERIALIZER;
00291 };
00292 }
00293 }
00294
00295 namespace ros
00296 {
00297 namespace message_operations
00298 {
00299
00300 template<class ContainerAllocator>
00301 struct Printer< ::sensor_msgs::JointState_<ContainerAllocator> >
00302 {
00303 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::JointState_<ContainerAllocator> & v)
00304 {
00305 s << indent << "header: ";
00306 s << std::endl;
00307 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00308 s << indent << "name[]" << std::endl;
00309 for (size_t i = 0; i < v.name.size(); ++i)
00310 {
00311 s << indent << " name[" << i << "]: ";
00312 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.name[i]);
00313 }
00314 s << indent << "position[]" << std::endl;
00315 for (size_t i = 0; i < v.position.size(); ++i)
00316 {
00317 s << indent << " position[" << i << "]: ";
00318 Printer<double>::stream(s, indent + " ", v.position[i]);
00319 }
00320 s << indent << "velocity[]" << std::endl;
00321 for (size_t i = 0; i < v.velocity.size(); ++i)
00322 {
00323 s << indent << " velocity[" << i << "]: ";
00324 Printer<double>::stream(s, indent + " ", v.velocity[i]);
00325 }
00326 s << indent << "effort[]" << std::endl;
00327 for (size_t i = 0; i < v.effort.size(); ++i)
00328 {
00329 s << indent << " effort[" << i << "]: ";
00330 Printer<double>::stream(s, indent + " ", v.effort[i]);
00331 }
00332 }
00333 };
00334
00335
00336 }
00337 }
00338
00339 #endif // SENSOR_MSGS_MESSAGE_JOINTSTATE_H
00340