00001
00002 #ifndef PR2_MECHANISM_CONTROLLERS_MESSAGE_BASECONTROLLERSTATE_H
00003 #define PR2_MECHANISM_CONTROLLERS_MESSAGE_BASECONTROLLERSTATE_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 "geometry_msgs/Twist.h"
00018
00019 namespace pr2_mechanism_controllers
00020 {
00021 template <class ContainerAllocator>
00022 struct BaseControllerState_ {
00023 typedef BaseControllerState_<ContainerAllocator> Type;
00024
00025 BaseControllerState_()
00026 : command()
00027 , joint_velocity_measured()
00028 , joint_velocity_commanded()
00029 , joint_velocity_error()
00030 , joint_effort_measured()
00031 , joint_effort_commanded()
00032 , joint_effort_error()
00033 , joint_names()
00034 {
00035 }
00036
00037 BaseControllerState_(const ContainerAllocator& _alloc)
00038 : command(_alloc)
00039 , joint_velocity_measured(_alloc)
00040 , joint_velocity_commanded(_alloc)
00041 , joint_velocity_error(_alloc)
00042 , joint_effort_measured(_alloc)
00043 , joint_effort_commanded(_alloc)
00044 , joint_effort_error(_alloc)
00045 , joint_names(_alloc)
00046 {
00047 }
00048
00049 typedef ::geometry_msgs::Twist_<ContainerAllocator> _command_type;
00050 ::geometry_msgs::Twist_<ContainerAllocator> command;
00051
00052 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_velocity_measured_type;
00053 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_velocity_measured;
00054
00055 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_velocity_commanded_type;
00056 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_velocity_commanded;
00057
00058 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_velocity_error_type;
00059 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_velocity_error;
00060
00061 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_effort_measured_type;
00062 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_effort_measured;
00063
00064 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_effort_commanded_type;
00065 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_effort_commanded;
00066
00067 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _joint_effort_error_type;
00068 std::vector<double, typename ContainerAllocator::template rebind<double>::other > joint_effort_error;
00069
00070 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 > _joint_names_type;
00071 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 > joint_names;
00072
00073
00074 typedef boost::shared_ptr< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> > Ptr;
00075 typedef boost::shared_ptr< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> const> ConstPtr;
00076 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00077 };
00078 typedef ::pr2_mechanism_controllers::BaseControllerState_<std::allocator<void> > BaseControllerState;
00079
00080 typedef boost::shared_ptr< ::pr2_mechanism_controllers::BaseControllerState> BaseControllerStatePtr;
00081 typedef boost::shared_ptr< ::pr2_mechanism_controllers::BaseControllerState const> BaseControllerStateConstPtr;
00082
00083
00084 template<typename ContainerAllocator>
00085 std::ostream& operator<<(std::ostream& s, const ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> & v)
00086 {
00087 ros::message_operations::Printer< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> >::stream(s, "", v);
00088 return s;}
00089
00090 }
00091
00092 namespace ros
00093 {
00094 namespace message_traits
00095 {
00096 template<class ContainerAllocator> struct IsMessage< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> > : public TrueType {};
00097 template<class ContainerAllocator> struct IsMessage< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> const> : public TrueType {};
00098 template<class ContainerAllocator>
00099 struct MD5Sum< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> > {
00100 static const char* value()
00101 {
00102 return "7a488aa492f9175d5fa35e22e56c4b28";
00103 }
00104
00105 static const char* value(const ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> &) { return value(); }
00106 static const uint64_t static_value1 = 0x7a488aa492f9175dULL;
00107 static const uint64_t static_value2 = 0x5fa35e22e56c4b28ULL;
00108 };
00109
00110 template<class ContainerAllocator>
00111 struct DataType< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> > {
00112 static const char* value()
00113 {
00114 return "pr2_mechanism_controllers/BaseControllerState";
00115 }
00116
00117 static const char* value(const ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> &) { return value(); }
00118 };
00119
00120 template<class ContainerAllocator>
00121 struct Definition< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> > {
00122 static const char* value()
00123 {
00124 return "geometry_msgs/Twist command\n\
00125 float64[] joint_velocity_measured\n\
00126 float64[] joint_velocity_commanded\n\
00127 float64[] joint_velocity_error\n\
00128 float64[] joint_effort_measured\n\
00129 float64[] joint_effort_commanded\n\
00130 float64[] joint_effort_error\n\
00131 string[] joint_names\n\
00132 \n\
00133 \n\
00134 ================================================================================\n\
00135 MSG: geometry_msgs/Twist\n\
00136 # This expresses velocity in free space broken into its linear and angular parts.\n\
00137 Vector3 linear\n\
00138 Vector3 angular\n\
00139 \n\
00140 ================================================================================\n\
00141 MSG: geometry_msgs/Vector3\n\
00142 # This represents a vector in free space. \n\
00143 \n\
00144 float64 x\n\
00145 float64 y\n\
00146 float64 z\n\
00147 ";
00148 }
00149
00150 static const char* value(const ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> &) { return value(); }
00151 };
00152
00153 }
00154 }
00155
00156 namespace ros
00157 {
00158 namespace serialization
00159 {
00160
00161 template<class ContainerAllocator> struct Serializer< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> >
00162 {
00163 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00164 {
00165 stream.next(m.command);
00166 stream.next(m.joint_velocity_measured);
00167 stream.next(m.joint_velocity_commanded);
00168 stream.next(m.joint_velocity_error);
00169 stream.next(m.joint_effort_measured);
00170 stream.next(m.joint_effort_commanded);
00171 stream.next(m.joint_effort_error);
00172 stream.next(m.joint_names);
00173 }
00174
00175 ROS_DECLARE_ALLINONE_SERIALIZER;
00176 };
00177 }
00178 }
00179
00180 namespace ros
00181 {
00182 namespace message_operations
00183 {
00184
00185 template<class ContainerAllocator>
00186 struct Printer< ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> >
00187 {
00188 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_mechanism_controllers::BaseControllerState_<ContainerAllocator> & v)
00189 {
00190 s << indent << "command: ";
00191 s << std::endl;
00192 Printer< ::geometry_msgs::Twist_<ContainerAllocator> >::stream(s, indent + " ", v.command);
00193 s << indent << "joint_velocity_measured[]" << std::endl;
00194 for (size_t i = 0; i < v.joint_velocity_measured.size(); ++i)
00195 {
00196 s << indent << " joint_velocity_measured[" << i << "]: ";
00197 Printer<double>::stream(s, indent + " ", v.joint_velocity_measured[i]);
00198 }
00199 s << indent << "joint_velocity_commanded[]" << std::endl;
00200 for (size_t i = 0; i < v.joint_velocity_commanded.size(); ++i)
00201 {
00202 s << indent << " joint_velocity_commanded[" << i << "]: ";
00203 Printer<double>::stream(s, indent + " ", v.joint_velocity_commanded[i]);
00204 }
00205 s << indent << "joint_velocity_error[]" << std::endl;
00206 for (size_t i = 0; i < v.joint_velocity_error.size(); ++i)
00207 {
00208 s << indent << " joint_velocity_error[" << i << "]: ";
00209 Printer<double>::stream(s, indent + " ", v.joint_velocity_error[i]);
00210 }
00211 s << indent << "joint_effort_measured[]" << std::endl;
00212 for (size_t i = 0; i < v.joint_effort_measured.size(); ++i)
00213 {
00214 s << indent << " joint_effort_measured[" << i << "]: ";
00215 Printer<double>::stream(s, indent + " ", v.joint_effort_measured[i]);
00216 }
00217 s << indent << "joint_effort_commanded[]" << std::endl;
00218 for (size_t i = 0; i < v.joint_effort_commanded.size(); ++i)
00219 {
00220 s << indent << " joint_effort_commanded[" << i << "]: ";
00221 Printer<double>::stream(s, indent + " ", v.joint_effort_commanded[i]);
00222 }
00223 s << indent << "joint_effort_error[]" << std::endl;
00224 for (size_t i = 0; i < v.joint_effort_error.size(); ++i)
00225 {
00226 s << indent << " joint_effort_error[" << i << "]: ";
00227 Printer<double>::stream(s, indent + " ", v.joint_effort_error[i]);
00228 }
00229 s << indent << "joint_names[]" << std::endl;
00230 for (size_t i = 0; i < v.joint_names.size(); ++i)
00231 {
00232 s << indent << " joint_names[" << i << "]: ";
00233 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.joint_names[i]);
00234 }
00235 }
00236 };
00237
00238
00239 }
00240 }
00241
00242 #endif // PR2_MECHANISM_CONTROLLERS_MESSAGE_BASECONTROLLERSTATE_H
00243