#include <message_template.h>
Public Types | |
typedef T | MessageType |
Public Types inherited from cpp_introspection::Message | |
typedef V_Field::const_iterator | const_iterator |
typedef V_Field::iterator | iterator |
Public Member Functions | |
VoidPtr | createInstance () const |
VoidPtr | deserialize (ros::serialization::IStream &stream, const VoidPtr &instance=VoidPtr()) const |
const char * | getDataType () const |
const char * | getDefinition () const |
std::string * | getFrameId (const VoidPtr &instance) const |
const std::string * | getFrameId (const VoidConstPtr &instance) const |
::std_msgs::Header * | getHeader (const VoidPtr &instance) const |
const ::std_msgs::Header * | getHeader (const VoidConstPtr &instance) const |
const char * | getMD5Sum () const |
ros::Time * | getTimeStamp (const VoidPtr &instance) const |
const ros::Time * | getTimeStamp (const VoidConstPtr &instance) const |
const std::type_info & | getTypeId () const |
bool | hasHeader () const |
MessagePtr | introspect (const VoidPtr &instance) const |
MessagePtr | introspect (void *instance) const |
MessagePtr | introspect (const VoidConstPtr &instance) const |
MessagePtr | introspect (void const *instance) const |
bool | isFixedSize () const |
bool | isSimple () const |
std::size_t | serializationLength (const VoidConstPtr &instance=VoidConstPtr()) const |
void | serialize (ros::serialization::OStream &stream, const VoidConstPtr &instance=VoidConstPtr()) const |
ros::SerializedMessage | serialize (const VoidConstPtr &instance=VoidConstPtr()) const |
virtual | ~MessageTemplate () |
Public Member Functions inherited from cpp_introspection::Message | |
const_iterator | begin () const |
const_iterator | end () const |
virtual FieldWPtr | field (const std::string &name) const =0 |
virtual const V_Field & | fields () const =0 |
virtual VoidConstPtr | getConstInstance () const |
template<typename T > | |
boost::shared_ptr< T const > | getConstInstanceAs () const |
virtual const V_FieldName & | getFieldNames () const =0 |
V_string | getFields (bool expand=false, const std::string &separator=".", const std::string &prefix=std::string()) const |
V_string & | getFields (V_string &fields, bool expand=false, const std::string &separator=".", const std::string &prefix=std::string()) const |
virtual VoidPtr | getInstance () const |
template<typename T > | |
boost::shared_ptr< T > | getInstanceAs () const |
virtual const char * | getName () const =0 |
virtual const char * | getPackageName () const =0 |
V_string | getTypes (bool expand=false) const |
V_string & | getTypes (V_string &types, bool expand=false) const |
std::vector< boost::any > | getValues (bool expand=false) const |
std::vector< boost::any > & | getValues (std::vector< boost::any > &values, bool expand=false) const |
virtual bool | hasInstance () const |
template<typename T > | |
bool | hasType () const |
virtual MessagePtr | introspect () const |
virtual bool | isMessage () const |
template<typename T > | |
T::Ptr | narrow (const VoidPtr &instance) const |
template<typename T > | |
T::ConstPtr | narrow (const VoidConstPtr &instance) const |
virtual PackagePtr | package () const =0 |
std::size_t | size () const |
virtual | ~Message () |
Definition at line 40 of file message_template.h.
typedef T cpp_introspection::MessageTemplate< T >::MessageType |
Definition at line 42 of file message_template.h.
|
inlinevirtual |
Definition at line 44 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 117 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 147 of file message_template.h.
|
inlinevirtual |
Implements cpp_introspection::Message.
Definition at line 46 of file message_template.h.
|
inlinevirtual |
Implements cpp_introspection::Message.
Definition at line 48 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 89 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 96 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 75 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 82 of file message_template.h.
|
inlinevirtual |
Implements cpp_introspection::Message.
Definition at line 47 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 103 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 110 of file message_template.h.
|
inlinevirtual |
Implements cpp_introspection::Message.
Definition at line 49 of file message_template.h.
|
inlinevirtual |
Implements cpp_introspection::Message.
Definition at line 53 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 153 of file accessor.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 147 of file accessor.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 167 of file accessor.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 161 of file accessor.h.
|
inlinevirtual |
Implements cpp_introspection::Message.
Definition at line 52 of file message_template.h.
|
inlinevirtual |
Implements cpp_introspection::Message.
Definition at line 51 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 139 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 123 of file message_template.h.
|
virtual |
Implements cpp_introspection::Message.
Definition at line 131 of file message_template.h.