$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-common_msgs/doc_stacks/2013-03-01_14-58-52.505545/common_msgs/sensor_msgs/msg/Joy.msg */ 00002 #ifndef SENSOR_MSGS_MESSAGE_JOY_H 00003 #define SENSOR_MSGS_MESSAGE_JOY_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 sensor_msgs 00020 { 00021 template <class ContainerAllocator> 00022 struct Joy_ { 00023 typedef Joy_<ContainerAllocator> Type; 00024 00025 Joy_() 00026 : header() 00027 , axes() 00028 , buttons() 00029 { 00030 } 00031 00032 Joy_(const ContainerAllocator& _alloc) 00033 : header(_alloc) 00034 , axes(_alloc) 00035 , buttons(_alloc) 00036 { 00037 } 00038 00039 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00040 ::std_msgs::Header_<ContainerAllocator> header; 00041 00042 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _axes_type; 00043 std::vector<float, typename ContainerAllocator::template rebind<float>::other > axes; 00044 00045 typedef std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > _buttons_type; 00046 std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > buttons; 00047 00048 00049 ROS_DEPRECATED uint32_t get_axes_size() const { return (uint32_t)axes.size(); } 00050 ROS_DEPRECATED void set_axes_size(uint32_t size) { axes.resize((size_t)size); } 00051 ROS_DEPRECATED void get_axes_vec(std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) const { vec = this->axes; } 00052 ROS_DEPRECATED void set_axes_vec(const std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) { this->axes = vec; } 00053 ROS_DEPRECATED uint32_t get_buttons_size() const { return (uint32_t)buttons.size(); } 00054 ROS_DEPRECATED void set_buttons_size(uint32_t size) { buttons.resize((size_t)size); } 00055 ROS_DEPRECATED void get_buttons_vec(std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > & vec) const { vec = this->buttons; } 00056 ROS_DEPRECATED void set_buttons_vec(const std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > & vec) { this->buttons = vec; } 00057 private: 00058 static const char* __s_getDataType_() { return "sensor_msgs/Joy"; } 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 "5a9ea5f83505693b71e785041e67a8bb"; } 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_getMessageDefinition_() { return "# Reports the state of a joysticks axes and buttons.\n\ 00073 Header header # timestamp in the header is the time the data is received from the joystick\n\ 00074 float32[] axes # the axes measurements from a joystick\n\ 00075 int32[] buttons # the buttons measurements from a joystick \n\ 00076 \n\ 00077 ================================================================================\n\ 00078 MSG: std_msgs/Header\n\ 00079 # Standard metadata for higher-level stamped data types.\n\ 00080 # This is generally used to communicate timestamped data \n\ 00081 # in a particular coordinate frame.\n\ 00082 # \n\ 00083 # sequence ID: consecutively increasing ID \n\ 00084 uint32 seq\n\ 00085 #Two-integer timestamp that is expressed as:\n\ 00086 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00087 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00088 # time-handling sugar is provided by the client library\n\ 00089 time stamp\n\ 00090 #Frame this data is associated with\n\ 00091 # 0: no frame\n\ 00092 # 1: global frame\n\ 00093 string frame_id\n\ 00094 \n\ 00095 "; } 00096 public: 00097 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00098 00099 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00100 00101 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00102 { 00103 ros::serialization::OStream stream(write_ptr, 1000000000); 00104 ros::serialization::serialize(stream, header); 00105 ros::serialization::serialize(stream, axes); 00106 ros::serialization::serialize(stream, buttons); 00107 return stream.getData(); 00108 } 00109 00110 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00111 { 00112 ros::serialization::IStream stream(read_ptr, 1000000000); 00113 ros::serialization::deserialize(stream, header); 00114 ros::serialization::deserialize(stream, axes); 00115 ros::serialization::deserialize(stream, buttons); 00116 return stream.getData(); 00117 } 00118 00119 ROS_DEPRECATED virtual uint32_t serializationLength() const 00120 { 00121 uint32_t size = 0; 00122 size += ros::serialization::serializationLength(header); 00123 size += ros::serialization::serializationLength(axes); 00124 size += ros::serialization::serializationLength(buttons); 00125 return size; 00126 } 00127 00128 typedef boost::shared_ptr< ::sensor_msgs::Joy_<ContainerAllocator> > Ptr; 00129 typedef boost::shared_ptr< ::sensor_msgs::Joy_<ContainerAllocator> const> ConstPtr; 00130 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00131 }; // struct Joy 00132 typedef ::sensor_msgs::Joy_<std::allocator<void> > Joy; 00133 00134 typedef boost::shared_ptr< ::sensor_msgs::Joy> JoyPtr; 00135 typedef boost::shared_ptr< ::sensor_msgs::Joy const> JoyConstPtr; 00136 00137 00138 template<typename ContainerAllocator> 00139 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Joy_<ContainerAllocator> & v) 00140 { 00141 ros::message_operations::Printer< ::sensor_msgs::Joy_<ContainerAllocator> >::stream(s, "", v); 00142 return s;} 00143 00144 } // namespace sensor_msgs 00145 00146 namespace ros 00147 { 00148 namespace message_traits 00149 { 00150 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::Joy_<ContainerAllocator> > : public TrueType {}; 00151 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::Joy_<ContainerAllocator> const> : public TrueType {}; 00152 template<class ContainerAllocator> 00153 struct MD5Sum< ::sensor_msgs::Joy_<ContainerAllocator> > { 00154 static const char* value() 00155 { 00156 return "5a9ea5f83505693b71e785041e67a8bb"; 00157 } 00158 00159 static const char* value(const ::sensor_msgs::Joy_<ContainerAllocator> &) { return value(); } 00160 static const uint64_t static_value1 = 0x5a9ea5f83505693bULL; 00161 static const uint64_t static_value2 = 0x71e785041e67a8bbULL; 00162 }; 00163 00164 template<class ContainerAllocator> 00165 struct DataType< ::sensor_msgs::Joy_<ContainerAllocator> > { 00166 static const char* value() 00167 { 00168 return "sensor_msgs/Joy"; 00169 } 00170 00171 static const char* value(const ::sensor_msgs::Joy_<ContainerAllocator> &) { return value(); } 00172 }; 00173 00174 template<class ContainerAllocator> 00175 struct Definition< ::sensor_msgs::Joy_<ContainerAllocator> > { 00176 static const char* value() 00177 { 00178 return "# Reports the state of a joysticks axes and buttons.\n\ 00179 Header header # timestamp in the header is the time the data is received from the joystick\n\ 00180 float32[] axes # the axes measurements from a joystick\n\ 00181 int32[] buttons # the buttons measurements from a joystick \n\ 00182 \n\ 00183 ================================================================================\n\ 00184 MSG: std_msgs/Header\n\ 00185 # Standard metadata for higher-level stamped data types.\n\ 00186 # This is generally used to communicate timestamped data \n\ 00187 # in a particular coordinate frame.\n\ 00188 # \n\ 00189 # sequence ID: consecutively increasing ID \n\ 00190 uint32 seq\n\ 00191 #Two-integer timestamp that is expressed as:\n\ 00192 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00193 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00194 # time-handling sugar is provided by the client library\n\ 00195 time stamp\n\ 00196 #Frame this data is associated with\n\ 00197 # 0: no frame\n\ 00198 # 1: global frame\n\ 00199 string frame_id\n\ 00200 \n\ 00201 "; 00202 } 00203 00204 static const char* value(const ::sensor_msgs::Joy_<ContainerAllocator> &) { return value(); } 00205 }; 00206 00207 template<class ContainerAllocator> struct HasHeader< ::sensor_msgs::Joy_<ContainerAllocator> > : public TrueType {}; 00208 template<class ContainerAllocator> struct HasHeader< const ::sensor_msgs::Joy_<ContainerAllocator> > : public TrueType {}; 00209 } // namespace message_traits 00210 } // namespace ros 00211 00212 namespace ros 00213 { 00214 namespace serialization 00215 { 00216 00217 template<class ContainerAllocator> struct Serializer< ::sensor_msgs::Joy_<ContainerAllocator> > 00218 { 00219 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00220 { 00221 stream.next(m.header); 00222 stream.next(m.axes); 00223 stream.next(m.buttons); 00224 } 00225 00226 ROS_DECLARE_ALLINONE_SERIALIZER; 00227 }; // struct Joy_ 00228 } // namespace serialization 00229 } // namespace ros 00230 00231 namespace ros 00232 { 00233 namespace message_operations 00234 { 00235 00236 template<class ContainerAllocator> 00237 struct Printer< ::sensor_msgs::Joy_<ContainerAllocator> > 00238 { 00239 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::Joy_<ContainerAllocator> & v) 00240 { 00241 s << indent << "header: "; 00242 s << std::endl; 00243 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00244 s << indent << "axes[]" << std::endl; 00245 for (size_t i = 0; i < v.axes.size(); ++i) 00246 { 00247 s << indent << " axes[" << i << "]: "; 00248 Printer<float>::stream(s, indent + " ", v.axes[i]); 00249 } 00250 s << indent << "buttons[]" << std::endl; 00251 for (size_t i = 0; i < v.buttons.size(); ++i) 00252 { 00253 s << indent << " buttons[" << i << "]: "; 00254 Printer<int32_t>::stream(s, indent + " ", v.buttons[i]); 00255 } 00256 } 00257 }; 00258 00259 00260 } // namespace message_operations 00261 } // namespace ros 00262 00263 #endif // SENSOR_MSGS_MESSAGE_JOY_H 00264