Go to the documentation of this file.00001
00002 #ifndef BRICS_ACTUATOR_MESSAGE_CARTESIANPOSE_H
00003 #define BRICS_ACTUATOR_MESSAGE_CARTESIANPOSE_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 "brics_actuator/Poison.h"
00018 #include "brics_actuator/CartesianVector.h"
00019 #include "geometry_msgs/Quaternion.h"
00020
00021 namespace brics_actuator
00022 {
00023 template <class ContainerAllocator>
00024 struct CartesianPose_ {
00025 typedef CartesianPose_<ContainerAllocator> Type;
00026
00027 CartesianPose_()
00028 : timeStamp()
00029 , poisonStamp()
00030 , base_frame_uri()
00031 , target_frame_uri()
00032 , position()
00033 , orientation()
00034 {
00035 }
00036
00037 CartesianPose_(const ContainerAllocator& _alloc)
00038 : timeStamp()
00039 , poisonStamp(_alloc)
00040 , base_frame_uri(_alloc)
00041 , target_frame_uri(_alloc)
00042 , position(_alloc)
00043 , orientation(_alloc)
00044 {
00045 }
00046
00047 typedef ros::Time _timeStamp_type;
00048 ros::Time timeStamp;
00049
00050 typedef ::brics_actuator::Poison_<ContainerAllocator> _poisonStamp_type;
00051 ::brics_actuator::Poison_<ContainerAllocator> poisonStamp;
00052
00053 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _base_frame_uri_type;
00054 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > base_frame_uri;
00055
00056 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _target_frame_uri_type;
00057 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > target_frame_uri;
00058
00059 typedef ::brics_actuator::CartesianVector_<ContainerAllocator> _position_type;
00060 ::brics_actuator::CartesianVector_<ContainerAllocator> position;
00061
00062 typedef ::geometry_msgs::Quaternion_<ContainerAllocator> _orientation_type;
00063 ::geometry_msgs::Quaternion_<ContainerAllocator> orientation;
00064
00065
00066 typedef boost::shared_ptr< ::brics_actuator::CartesianPose_<ContainerAllocator> > Ptr;
00067 typedef boost::shared_ptr< ::brics_actuator::CartesianPose_<ContainerAllocator> const> ConstPtr;
00068 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00069 };
00070 typedef ::brics_actuator::CartesianPose_<std::allocator<void> > CartesianPose;
00071
00072 typedef boost::shared_ptr< ::brics_actuator::CartesianPose> CartesianPosePtr;
00073 typedef boost::shared_ptr< ::brics_actuator::CartesianPose const> CartesianPoseConstPtr;
00074
00075
00076 template<typename ContainerAllocator>
00077 std::ostream& operator<<(std::ostream& s, const ::brics_actuator::CartesianPose_<ContainerAllocator> & v)
00078 {
00079 ros::message_operations::Printer< ::brics_actuator::CartesianPose_<ContainerAllocator> >::stream(s, "", v);
00080 return s;}
00081
00082 }
00083
00084 namespace ros
00085 {
00086 namespace message_traits
00087 {
00088 template<class ContainerAllocator> struct IsMessage< ::brics_actuator::CartesianPose_<ContainerAllocator> > : public TrueType {};
00089 template<class ContainerAllocator> struct IsMessage< ::brics_actuator::CartesianPose_<ContainerAllocator> const> : public TrueType {};
00090 template<class ContainerAllocator>
00091 struct MD5Sum< ::brics_actuator::CartesianPose_<ContainerAllocator> > {
00092 static const char* value()
00093 {
00094 return "0fe287468091771914ed98dea2d2a5a5";
00095 }
00096
00097 static const char* value(const ::brics_actuator::CartesianPose_<ContainerAllocator> &) { return value(); }
00098 static const uint64_t static_value1 = 0x0fe2874680917719ULL;
00099 static const uint64_t static_value2 = 0x14ed98dea2d2a5a5ULL;
00100 };
00101
00102 template<class ContainerAllocator>
00103 struct DataType< ::brics_actuator::CartesianPose_<ContainerAllocator> > {
00104 static const char* value()
00105 {
00106 return "brics_actuator/CartesianPose";
00107 }
00108
00109 static const char* value(const ::brics_actuator::CartesianPose_<ContainerAllocator> &) { return value(); }
00110 };
00111
00112 template<class ContainerAllocator>
00113 struct Definition< ::brics_actuator::CartesianPose_<ContainerAllocator> > {
00114 static const char* value()
00115 {
00116 return "time timeStamp\n\
00117 Poison poisonStamp\n\
00118 string base_frame_uri\n\
00119 string target_frame_uri\n\
00120 CartesianVector position\n\
00121 geometry_msgs/Quaternion orientation\n\
00122 \n\
00123 ================================================================================\n\
00124 MSG: brics_actuator/Poison\n\
00125 string originator # node id\n\
00126 string description # encoding still an issue\n\
00127 float32 qos # reliability of the channel\n\
00128 # 0..1 where 1 means healthy\n\
00129 \n\
00130 ================================================================================\n\
00131 MSG: brics_actuator/CartesianVector\n\
00132 string unit\n\
00133 float64 x\n\
00134 float64 y\n\
00135 float64 z\n\
00136 \n\
00137 ================================================================================\n\
00138 MSG: geometry_msgs/Quaternion\n\
00139 # This represents an orientation in free space in quaternion form.\n\
00140 \n\
00141 float64 x\n\
00142 float64 y\n\
00143 float64 z\n\
00144 float64 w\n\
00145 \n\
00146 ";
00147 }
00148
00149 static const char* value(const ::brics_actuator::CartesianPose_<ContainerAllocator> &) { return value(); }
00150 };
00151
00152 }
00153 }
00154
00155 namespace ros
00156 {
00157 namespace serialization
00158 {
00159
00160 template<class ContainerAllocator> struct Serializer< ::brics_actuator::CartesianPose_<ContainerAllocator> >
00161 {
00162 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00163 {
00164 stream.next(m.timeStamp);
00165 stream.next(m.poisonStamp);
00166 stream.next(m.base_frame_uri);
00167 stream.next(m.target_frame_uri);
00168 stream.next(m.position);
00169 stream.next(m.orientation);
00170 }
00171
00172 ROS_DECLARE_ALLINONE_SERIALIZER;
00173 };
00174 }
00175 }
00176
00177 namespace ros
00178 {
00179 namespace message_operations
00180 {
00181
00182 template<class ContainerAllocator>
00183 struct Printer< ::brics_actuator::CartesianPose_<ContainerAllocator> >
00184 {
00185 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::brics_actuator::CartesianPose_<ContainerAllocator> & v)
00186 {
00187 s << indent << "timeStamp: ";
00188 Printer<ros::Time>::stream(s, indent + " ", v.timeStamp);
00189 s << indent << "poisonStamp: ";
00190 s << std::endl;
00191 Printer< ::brics_actuator::Poison_<ContainerAllocator> >::stream(s, indent + " ", v.poisonStamp);
00192 s << indent << "base_frame_uri: ";
00193 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.base_frame_uri);
00194 s << indent << "target_frame_uri: ";
00195 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.target_frame_uri);
00196 s << indent << "position: ";
00197 s << std::endl;
00198 Printer< ::brics_actuator::CartesianVector_<ContainerAllocator> >::stream(s, indent + " ", v.position);
00199 s << indent << "orientation: ";
00200 s << std::endl;
00201 Printer< ::geometry_msgs::Quaternion_<ContainerAllocator> >::stream(s, indent + " ", v.orientation);
00202 }
00203 };
00204
00205
00206 }
00207 }
00208
00209 #endif // BRICS_ACTUATOR_MESSAGE_CARTESIANPOSE_H
00210