$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-alufr-humanoid_stacks/doc_stacks/2013-03-05_11-28-06.315559/nao_robot/nao_msgs/msg/BlinkGoal.msg */ 00002 #ifndef NAO_MSGS_MESSAGE_BLINKGOAL_H 00003 #define NAO_MSGS_MESSAGE_BLINKGOAL_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/ColorRGBA.h" 00018 #include "std_msgs/ColorRGBA.h" 00019 00020 namespace nao_msgs 00021 { 00022 template <class ContainerAllocator> 00023 struct BlinkGoal_ { 00024 typedef BlinkGoal_<ContainerAllocator> Type; 00025 00026 BlinkGoal_() 00027 : colors() 00028 , bg_color() 00029 , blink_duration() 00030 , blink_rate_mean(0.0) 00031 , blink_rate_sd(0.0) 00032 { 00033 } 00034 00035 BlinkGoal_(const ContainerAllocator& _alloc) 00036 : colors(_alloc) 00037 , bg_color(_alloc) 00038 , blink_duration() 00039 , blink_rate_mean(0.0) 00040 , blink_rate_sd(0.0) 00041 { 00042 } 00043 00044 typedef std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > _colors_type; 00045 std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > colors; 00046 00047 typedef ::std_msgs::ColorRGBA_<ContainerAllocator> _bg_color_type; 00048 ::std_msgs::ColorRGBA_<ContainerAllocator> bg_color; 00049 00050 typedef ros::Duration _blink_duration_type; 00051 ros::Duration blink_duration; 00052 00053 typedef float _blink_rate_mean_type; 00054 float blink_rate_mean; 00055 00056 typedef float _blink_rate_sd_type; 00057 float blink_rate_sd; 00058 00059 00060 ROS_DEPRECATED uint32_t get_colors_size() const { return (uint32_t)colors.size(); } 00061 ROS_DEPRECATED void set_colors_size(uint32_t size) { colors.resize((size_t)size); } 00062 ROS_DEPRECATED void get_colors_vec(std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > & vec) const { vec = this->colors; } 00063 ROS_DEPRECATED void set_colors_vec(const std::vector< ::std_msgs::ColorRGBA_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ColorRGBA_<ContainerAllocator> >::other > & vec) { this->colors = vec; } 00064 private: 00065 static const char* __s_getDataType_() { return "nao_msgs/BlinkGoal"; } 00066 public: 00067 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00068 00069 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00070 00071 private: 00072 static const char* __s_getMD5Sum_() { return "5e5d3c2ba9976dc121a0bb6ef7c66d79"; } 00073 public: 00074 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00075 00076 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00077 00078 private: 00079 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00080 # Goal: colours to use for blinking, plus blinking rate mean and sd\n\ 00081 # Result: true if robot is still blinking (call was pre-empted by another user)\n\ 00082 # Feedback: last blinked colour\n\ 00083 std_msgs/ColorRGBA[] colors\n\ 00084 std_msgs/ColorRGBA bg_color\n\ 00085 duration blink_duration\n\ 00086 float32 blink_rate_mean\n\ 00087 float32 blink_rate_sd\n\ 00088 \n\ 00089 ================================================================================\n\ 00090 MSG: std_msgs/ColorRGBA\n\ 00091 float32 r\n\ 00092 float32 g\n\ 00093 float32 b\n\ 00094 float32 a\n\ 00095 \n\ 00096 "; } 00097 public: 00098 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00099 00100 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00101 00102 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00103 { 00104 ros::serialization::OStream stream(write_ptr, 1000000000); 00105 ros::serialization::serialize(stream, colors); 00106 ros::serialization::serialize(stream, bg_color); 00107 ros::serialization::serialize(stream, blink_duration); 00108 ros::serialization::serialize(stream, blink_rate_mean); 00109 ros::serialization::serialize(stream, blink_rate_sd); 00110 return stream.getData(); 00111 } 00112 00113 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00114 { 00115 ros::serialization::IStream stream(read_ptr, 1000000000); 00116 ros::serialization::deserialize(stream, colors); 00117 ros::serialization::deserialize(stream, bg_color); 00118 ros::serialization::deserialize(stream, blink_duration); 00119 ros::serialization::deserialize(stream, blink_rate_mean); 00120 ros::serialization::deserialize(stream, blink_rate_sd); 00121 return stream.getData(); 00122 } 00123 00124 ROS_DEPRECATED virtual uint32_t serializationLength() const 00125 { 00126 uint32_t size = 0; 00127 size += ros::serialization::serializationLength(colors); 00128 size += ros::serialization::serializationLength(bg_color); 00129 size += ros::serialization::serializationLength(blink_duration); 00130 size += ros::serialization::serializationLength(blink_rate_mean); 00131 size += ros::serialization::serializationLength(blink_rate_sd); 00132 return size; 00133 } 00134 00135 typedef boost::shared_ptr< ::nao_msgs::BlinkGoal_<ContainerAllocator> > Ptr; 00136 typedef boost::shared_ptr< ::nao_msgs::BlinkGoal_<ContainerAllocator> const> ConstPtr; 00137 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00138 }; // struct BlinkGoal 00139 typedef ::nao_msgs::BlinkGoal_<std::allocator<void> > BlinkGoal; 00140 00141 typedef boost::shared_ptr< ::nao_msgs::BlinkGoal> BlinkGoalPtr; 00142 typedef boost::shared_ptr< ::nao_msgs::BlinkGoal const> BlinkGoalConstPtr; 00143 00144 00145 template<typename ContainerAllocator> 00146 std::ostream& operator<<(std::ostream& s, const ::nao_msgs::BlinkGoal_<ContainerAllocator> & v) 00147 { 00148 ros::message_operations::Printer< ::nao_msgs::BlinkGoal_<ContainerAllocator> >::stream(s, "", v); 00149 return s;} 00150 00151 } // namespace nao_msgs 00152 00153 namespace ros 00154 { 00155 namespace message_traits 00156 { 00157 template<class ContainerAllocator> struct IsMessage< ::nao_msgs::BlinkGoal_<ContainerAllocator> > : public TrueType {}; 00158 template<class ContainerAllocator> struct IsMessage< ::nao_msgs::BlinkGoal_<ContainerAllocator> const> : public TrueType {}; 00159 template<class ContainerAllocator> 00160 struct MD5Sum< ::nao_msgs::BlinkGoal_<ContainerAllocator> > { 00161 static const char* value() 00162 { 00163 return "5e5d3c2ba9976dc121a0bb6ef7c66d79"; 00164 } 00165 00166 static const char* value(const ::nao_msgs::BlinkGoal_<ContainerAllocator> &) { return value(); } 00167 static const uint64_t static_value1 = 0x5e5d3c2ba9976dc1ULL; 00168 static const uint64_t static_value2 = 0x21a0bb6ef7c66d79ULL; 00169 }; 00170 00171 template<class ContainerAllocator> 00172 struct DataType< ::nao_msgs::BlinkGoal_<ContainerAllocator> > { 00173 static const char* value() 00174 { 00175 return "nao_msgs/BlinkGoal"; 00176 } 00177 00178 static const char* value(const ::nao_msgs::BlinkGoal_<ContainerAllocator> &) { return value(); } 00179 }; 00180 00181 template<class ContainerAllocator> 00182 struct Definition< ::nao_msgs::BlinkGoal_<ContainerAllocator> > { 00183 static const char* value() 00184 { 00185 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00186 # Goal: colours to use for blinking, plus blinking rate mean and sd\n\ 00187 # Result: true if robot is still blinking (call was pre-empted by another user)\n\ 00188 # Feedback: last blinked colour\n\ 00189 std_msgs/ColorRGBA[] colors\n\ 00190 std_msgs/ColorRGBA bg_color\n\ 00191 duration blink_duration\n\ 00192 float32 blink_rate_mean\n\ 00193 float32 blink_rate_sd\n\ 00194 \n\ 00195 ================================================================================\n\ 00196 MSG: std_msgs/ColorRGBA\n\ 00197 float32 r\n\ 00198 float32 g\n\ 00199 float32 b\n\ 00200 float32 a\n\ 00201 \n\ 00202 "; 00203 } 00204 00205 static const char* value(const ::nao_msgs::BlinkGoal_<ContainerAllocator> &) { return value(); } 00206 }; 00207 00208 } // namespace message_traits 00209 } // namespace ros 00210 00211 namespace ros 00212 { 00213 namespace serialization 00214 { 00215 00216 template<class ContainerAllocator> struct Serializer< ::nao_msgs::BlinkGoal_<ContainerAllocator> > 00217 { 00218 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00219 { 00220 stream.next(m.colors); 00221 stream.next(m.bg_color); 00222 stream.next(m.blink_duration); 00223 stream.next(m.blink_rate_mean); 00224 stream.next(m.blink_rate_sd); 00225 } 00226 00227 ROS_DECLARE_ALLINONE_SERIALIZER; 00228 }; // struct BlinkGoal_ 00229 } // namespace serialization 00230 } // namespace ros 00231 00232 namespace ros 00233 { 00234 namespace message_operations 00235 { 00236 00237 template<class ContainerAllocator> 00238 struct Printer< ::nao_msgs::BlinkGoal_<ContainerAllocator> > 00239 { 00240 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::nao_msgs::BlinkGoal_<ContainerAllocator> & v) 00241 { 00242 s << indent << "colors[]" << std::endl; 00243 for (size_t i = 0; i < v.colors.size(); ++i) 00244 { 00245 s << indent << " colors[" << i << "]: "; 00246 s << std::endl; 00247 s << indent; 00248 Printer< ::std_msgs::ColorRGBA_<ContainerAllocator> >::stream(s, indent + " ", v.colors[i]); 00249 } 00250 s << indent << "bg_color: "; 00251 s << std::endl; 00252 Printer< ::std_msgs::ColorRGBA_<ContainerAllocator> >::stream(s, indent + " ", v.bg_color); 00253 s << indent << "blink_duration: "; 00254 Printer<ros::Duration>::stream(s, indent + " ", v.blink_duration); 00255 s << indent << "blink_rate_mean: "; 00256 Printer<float>::stream(s, indent + " ", v.blink_rate_mean); 00257 s << indent << "blink_rate_sd: "; 00258 Printer<float>::stream(s, indent + " ", v.blink_rate_sd); 00259 } 00260 }; 00261 00262 00263 } // namespace message_operations 00264 } // namespace ros 00265 00266 #endif // NAO_MSGS_MESSAGE_BLINKGOAL_H 00267