Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
rtt_tf::RTT_TF Class Reference

#include <rtt_tf-component.hpp>

Inheritance diagram for rtt_tf::RTT_TF:
Inheritance graph
[legend]

Public Member Functions

void cleanupHook ()
 
bool configureHook ()
 
 RTT_TF (std::string const &name)
 
void updateHook ()
 
- Public Member Functions inherited from RTT::TaskContext
bool addAttribute (const std::string &name, T &attr)
 
bool addAttribute (base::AttributeBase &a)
 
bool addAttribute (base::AttributeBase &a)
 
bool addAttribute (const std::string &name, T &attr)
 
bool addConstant (const std::string &name, const T &attr)
 
bool addConstant (const std::string &name, const T &attr)
 
base::InputPortInterfaceaddEventPort (const std::string &name, base::InputPortInterface &port, SlotFunction callback=SlotFunction())
 
base::InputPortInterfaceaddEventPort (base::InputPortInterface &port, SlotFunction callback=SlotFunction())
 
Operation< Signature > & addOperation (Operation< Signature > &op)
 
Operation< Signature > & addOperation (Operation< Signature > &op)
 
Operation< typename internal::GetSignature< Func >::Signature > & addOperation (const std::string name, Func func, Service *serv, ExecutionThread et=ClientThread)
 
Operation< Signature > & addOperation (const std::string name, Signature *func, ExecutionThread et=ClientThread)
 
Operation< typename internal::GetSignature< Func >::Signature > & addOperation (const std::string name, Func func, Service *serv, ExecutionThread et=ClientThread)
 
Operation< Signature > & addOperation (const std::string name, Signature *func, ExecutionThread et=ClientThread)
 
virtual bool addPeer (TaskContext *peer, std::string alias="")
 
virtual bool addPeer (TaskContext *peer, std::string alias="")
 
base::PortInterfaceaddPort (const std::string &name, base::PortInterface &port)
 
base::PortInterfaceaddPort (base::PortInterface &port)
 
Property< T > & addProperty (const std::string &name, T &attr)
 
bool addProperty (base::PropertyBase &pb)
 
Property< T > & addProperty (const std::string &name, T &attr)
 
bool addProperty (base::PropertyBase &pb)
 
ConfigurationInterfaceattributes ()
 
ConfigurationInterfaceattributes ()
 
virtual void clear ()
 
virtual bool connectPeers (TaskContext *peer)
 
virtual bool connectPeers (TaskContext *peer)
 
virtual bool connectPorts (TaskContext *peer)
 
virtual bool connectServices (TaskContext *peer)
 
virtual bool connectServices (TaskContext *peer)
 
virtual void disconnect ()
 
virtual void disconnect ()
 
virtual void disconnectPeers (const std::string &name)
 
virtual void disconnectPeers (const std::string &name)
 
base::ActivityInterfacegetActivity ()
 
T * getActivity ()
 
base::AttributeBasegetAttribute (const std::string &name) const
 
base::AttributeBasegetAttribute (const std::string &name) const
 
virtual const std::string & getName () const
 
OperationInterfacePartgetOperation (std::string name)
 
OperationInterfacePartgetOperation (std::string name)
 
virtual TaskContextgetPeer (const std::string &peer_name) const
 
virtual TaskContextgetPeer (const std::string &peer_name) const
 
virtual PeerList getPeerList () const
 
virtual PeerList getPeerList () const
 
base::PortInterfacegetPort (const std::string &name) const
 
base::PropertyBasegetProperty (const std::string &name) const
 
base::PropertyBasegetProperty (const std::string &name) const
 
boost::shared_ptr< ServiceType > getProvider (const std::string &name)
 
boost::shared_ptr< ServiceType > getProvider (const std::string &name)
 
virtual bool hasPeer (const std::string &peer_name) const
 
virtual bool hasPeer (const std::string &peer_name) const
 
bool loadService (const std::string &service_name)
 
bool loadService (const std::string &service_name)
 
OperationInterfaceoperations ()
 
OperationInterfaceoperations ()
 
DataFlowInterfaceports ()
 
const DataFlowInterfaceports () const
 
PropertyBagproperties ()
 
PropertyBagproperties ()
 
Service::shared_ptr provides (const std::string &service_name)
 
Service::shared_ptr provides ()
 
Service::shared_ptr provides ()
 
Service::shared_ptr provides (const std::string &service_name)
 
virtual bool ready ()
 
virtual void removePeer (const std::string &name)
 
virtual void removePeer (TaskContext *peer)
 
virtual void removePeer (TaskContext *peer)
 
virtual void removePeer (const std::string &name)
 
ServiceRequester::shared_ptr requires (const std::string &service_name)
 
ServiceRequester::shared_ptr requires (const std::string &service_name)
 
ServiceRequester::shared_ptr requires ()
 
ServiceRequester::shared_ptr requires ()
 
bool setActivity (base::ActivityInterface *new_act)
 
virtual bool start ()
 
virtual bool stop ()
 
 TaskContext (const std::string &name, TaskState initial_state=Stopped)
 
virtual ~TaskContext ()
 
- Public Member Functions inherited from RTT::base::TaskCore
virtual bool activate ()
 
virtual bool activate ()
 
virtual bool cleanup ()
 
virtual bool cleanup ()
 
virtual bool configure ()
 
virtual bool configure ()
 
const ExecutionEngineengine () const
 
ExecutionEngineengine ()
 
virtual void error ()
 
virtual void error ()
 
virtual unsigned getCpuAffinity () const
 
virtual unsigned getCpuAffinity () const
 
unsigned int getCycleCounter () const
 
unsigned int getIOCounter () const
 
virtual Seconds getPeriod () const
 
virtual Seconds getPeriod () const
 
virtual TaskState getTargetState () const
 
virtual TaskState getTaskState () const
 
unsigned int getTimeOutCounter () const
 
unsigned int getTriggerCounter () const
 
virtual bool inException () const
 
virtual bool inException () const
 
virtual bool inFatalError () const
 
virtual bool inFatalError () const
 
virtual bool inRunTimeError () const
 
virtual bool inRunTimeError () const
 
virtual bool isActive () const
 
virtual bool isActive () const
 
virtual bool isConfigured () const
 
virtual bool isConfigured () const
 
virtual bool isRunning () const
 
virtual bool isRunning () const
 
virtual bool recover ()
 
virtual bool recover ()
 
virtual bool setCpuAffinity (unsigned cpu)
 
virtual bool setCpuAffinity (unsigned cpu)
 
virtual bool setPeriod (Seconds s)
 
virtual bool setPeriod (Seconds s)
 
 TaskCore (TaskState initial_state=Stopped)
 
virtual bool trigger ()
 
virtual bool trigger ()
 
virtual bool update ()
 
virtual bool update ()
 
virtual ~TaskCore ()
 

Private Member Functions

void addTFOperations (RTT::Service::shared_ptr service)
 
void broadcastStaticTransform (const geometry_msgs::TransformStamped &tform)
 
void broadcastStaticTransforms (const std::vector< geometry_msgs::TransformStamped > &tforms)
 
void broadcastTransform (const geometry_msgs::TransformStamped &tform)
 
void broadcastTransforms (const std::vector< geometry_msgs::TransformStamped > &tforms)
 
bool canTransform (const std::string &target, const std::string &source) const
 
bool canTransformAtTime (const std::string &target, const std::string &source, const ros::Time &common_time) const
 
ros::Time getLatestCommonTime (const std::string &target, const std::string &source) const
 
void internalUpdate (tf2_msgs::TFMessage &msg, RTT::InputPort< tf2_msgs::TFMessage > &port, bool is_static)
 
geometry_msgs::TransformStamped lookupTransform (const std::string &target, const std::string &source) const
 
geometry_msgs::TransformStamped lookupTransformAtTime (const std::string &target, const std::string &source, const ros::Time &common_time) const
 

Private Attributes

RTT::InputPort< tf2_msgs::TFMessage > port_tf_in
 
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_out
 
RTT::InputPort< tf2_msgs::TFMessage > port_tf_static_in
 
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_static_out
 
double prop_buffer_size
 
double prop_cache_time
 
std::string prop_tf_prefix
 

Static Private Attributes

static const int DEFAULT_BUFFER_SIZE = 100
 

Additional Inherited Members

- Public Types inherited from RTT::TaskContext
typedef std::vector< std::string > PeerList
 
typedef boost::function< void(base::PortInterface *)> SlotFunction
 
- Public Types inherited from RTT::base::TaskCore
enum  TaskState
 
- Public Attributes inherited from RTT::base::TaskCore
 Exception
 
 FatalError
 
 Init
 
 PreOperational
 
 Running
 
 RunTimeError
 
 Stopped
 
- Protected Types inherited from tf2::BufferCore
typedef boost::function< void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, ros::Time time, TransformableResult result)> TransformableCallback
 
- Protected Member Functions inherited from RTT::TaskContext
virtual void dataOnPortCallback (base::PortInterface *port)
 
virtual bool dataOnPortHook (base::PortInterface *port)
 
void forceActivity (base::ActivityInterface *new_act)
 
- Protected Member Functions inherited from RTT::base::TaskCore
virtual bool breakUpdateHook ()
 
virtual void errorHook ()
 
virtual void exception ()
 
virtual void exceptionHook ()
 
virtual void fatal ()
 
virtual bool startHook ()
 
virtual void stopHook ()
 
- Protected Member Functions inherited from tf2::BufferCore
boost::signals2::connection _addTransformsChangedListener (boost::function< void(void)> callback)
 
std::string _allFramesAsDot (double current_time) const
 
std::string _allFramesAsDot () const
 
void _chainAsVector (const std::string &target_frame, ros::Time target_time, const std::string &source_frame, ros::Time source_time, const std::string &fixed_frame, std::vector< std::string > &output) const
 
bool _frameExists (const std::string &frame_id_str) const
 
void _getFrameStrings (std::vector< std::string > &ids) const
 
int _getLatestCommonTime (CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
 
bool _getParent (const std::string &frame_id, ros::Time time, std::string &parent) const
 
CompactFrameID _lookupFrameNumber (const std::string &frameid_str) const
 
CompactFrameID _lookupOrInsertFrameNumber (const std::string &frameid_str)
 
void _removeTransformsChangedListener (boost::signals2::connection c)
 
CompactFrameID _validateFrameId (const char *function_name_arg, const std::string &frame_id) const
 
TransformableCallbackHandle addTransformableCallback (const TransformableCallback &cb)
 
TransformableRequestHandle addTransformableRequest (TransformableCallbackHandle handle, const std::string &target_frame, const std::string &source_frame, ros::Time time)
 
std::string allFramesAsString () const
 
std::string allFramesAsYAML (double current_time) const
 
std::string allFramesAsYAML () const
 
 BufferCore (ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
 
void cancelTransformableRequest (TransformableRequestHandle handle)
 
bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
 
bool canTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, std::string *error_msg=NULL) const
 
void clear ()
 
ros::Duration getCacheLength ()
 
bool isUsingDedicatedThread () const
 
geometry_msgs::TransformStamped lookupTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame) const
 
geometry_msgs::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
 
void removeTransformableCallback (TransformableCallbackHandle handle)
 
bool setTransform (const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
 
void setUsingDedicatedThread (bool value)
 
virtual ~BufferCore (void)
 
- Protected Attributes inherited from RTT::base::TaskCore
ExecutionEngineee
 
unsigned int mCycleCounter
 
unsigned int mIOCounter
 
TaskState mTaskState
 
unsigned int mTimeOutCounter
 
unsigned int mTriggerCounter
 
bool mTriggerOnStart
 
- Static Protected Attributes inherited from tf2::BufferCore
static const int DEFAULT_CACHE_TIME
 
static const uint32_t MAX_GRAPH_DEPTH
 

Detailed Description

Definition at line 11 of file rtt_tf-component.hpp.

Constructor & Destructor Documentation

rtt_tf::RTT_TF::RTT_TF ( std::string const &  name)

Definition at line 90 of file rtt_tf-component.cpp.

Member Function Documentation

void rtt_tf::RTT_TF::addTFOperations ( RTT::Service::shared_ptr  service)
private

Definition at line 107 of file rtt_tf-component.cpp.

void rtt_tf::RTT_TF::broadcastStaticTransform ( const geometry_msgs::TransformStamped &  tform)
private

Definition at line 284 of file rtt_tf-component.cpp.

void rtt_tf::RTT_TF::broadcastStaticTransforms ( const std::vector< geometry_msgs::TransformStamped > &  tforms)
private

Definition at line 291 of file rtt_tf-component.cpp.

void rtt_tf::RTT_TF::broadcastTransform ( const geometry_msgs::TransformStamped &  tform)
private

Definition at line 271 of file rtt_tf-component.cpp.

void rtt_tf::RTT_TF::broadcastTransforms ( const std::vector< geometry_msgs::TransformStamped > &  tforms)
private

Definition at line 278 of file rtt_tf-component.cpp.

bool rtt_tf::RTT_TF::canTransform ( const std::string &  target,
const std::string &  source 
) const
private

Definition at line 248 of file rtt_tf-component.cpp.

bool rtt_tf::RTT_TF::canTransformAtTime ( const std::string &  target,
const std::string &  source,
const ros::Time common_time 
) const
private

Definition at line 255 of file rtt_tf-component.cpp.

void rtt_tf::RTT_TF::cleanupHook ( )
virtual

Reimplemented from RTT::base::TaskCore.

Definition at line 219 of file rtt_tf-component.cpp.

bool rtt_tf::RTT_TF::configureHook ( )
virtual

Reimplemented from RTT::base::TaskCore.

Definition at line 148 of file rtt_tf-component.cpp.

ros::Time rtt_tf::RTT_TF::getLatestCommonTime ( const std::string &  target,
const std::string &  source 
) const
private

Definition at line 227 of file rtt_tf-component.cpp.

void rtt_tf::RTT_TF::internalUpdate ( tf2_msgs::TFMessage &  msg,
RTT::InputPort< tf2_msgs::TFMessage > &  port,
bool  is_static 
)
private

Definition at line 181 of file rtt_tf-component.cpp.

geometry_msgs::TransformStamped rtt_tf::RTT_TF::lookupTransform ( const std::string &  target,
const std::string &  source 
) const
private

Definition at line 241 of file rtt_tf-component.cpp.

geometry_msgs::TransformStamped rtt_tf::RTT_TF::lookupTransformAtTime ( const std::string &  target,
const std::string &  source,
const ros::Time common_time 
) const
private

Definition at line 263 of file rtt_tf-component.cpp.

void rtt_tf::RTT_TF::updateHook ( )
virtual

Reimplemented from RTT::base::TaskCore.

Definition at line 201 of file rtt_tf-component.cpp.

Member Data Documentation

const int rtt_tf::RTT_TF::DEFAULT_BUFFER_SIZE = 100
staticprivate

Definition at line 13 of file rtt_tf-component.hpp.

RTT::InputPort<tf2_msgs::TFMessage> rtt_tf::RTT_TF::port_tf_in
private

Definition at line 19 of file rtt_tf-component.hpp.

RTT::OutputPort<tf2_msgs::TFMessage> rtt_tf::RTT_TF::port_tf_out
private

Definition at line 21 of file rtt_tf-component.hpp.

RTT::InputPort<tf2_msgs::TFMessage> rtt_tf::RTT_TF::port_tf_static_in
private

Definition at line 20 of file rtt_tf-component.hpp.

RTT::OutputPort<tf2_msgs::TFMessage> rtt_tf::RTT_TF::port_tf_static_out
private

Definition at line 22 of file rtt_tf-component.hpp.

double rtt_tf::RTT_TF::prop_buffer_size
private

Definition at line 16 of file rtt_tf-component.hpp.

double rtt_tf::RTT_TF::prop_cache_time
private

Definition at line 15 of file rtt_tf-component.hpp.

std::string rtt_tf::RTT_TF::prop_tf_prefix
private

Definition at line 17 of file rtt_tf-component.hpp.


The documentation for this class was generated from the following files:


rtt_tf
Author(s): Ruben Smits
autogenerated on Sat Jun 8 2019 18:06:38