#include <rtt_tf-component.hpp>
Public Member Functions | |
void | cleanupHook () |
bool | configureHook () |
RTT_TF (std::string const &name) | |
bool | startHook () |
void | stopHook () |
void | updateHook () |
![]() | |
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::InputPortInterface & | addEventPort (const std::string &name, base::InputPortInterface &port, SlotFunction callback=SlotFunction()) |
base::InputPortInterface & | addEventPort (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::PortInterface & | addPort (const std::string &name, base::PortInterface &port) |
base::PortInterface & | addPort (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) |
ConfigurationInterface * | attributes () |
ConfigurationInterface * | attributes () |
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::ActivityInterface * | getActivity () |
T * | getActivity () |
base::AttributeBase * | getAttribute (const std::string &name) const |
base::AttributeBase * | getAttribute (const std::string &name) const |
virtual const std::string & | getName () const |
OperationInterfacePart * | getOperation (std::string name) |
OperationInterfacePart * | getOperation (std::string name) |
virtual TaskContext * | getPeer (const std::string &peer_name) const |
virtual TaskContext * | getPeer (const std::string &peer_name) const |
virtual PeerList | getPeerList () const |
virtual PeerList | getPeerList () const |
base::PortInterface * | getPort (const std::string &name) const |
base::PropertyBase * | getProperty (const std::string &name) const |
base::PropertyBase * | getProperty (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) |
OperationInterface * | operations () |
OperationInterface * | operations () |
DataFlowInterface * | ports () |
const DataFlowInterface * | ports () const |
PropertyBag * | properties () |
PropertyBag * | properties () |
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 () |
![]() | |
virtual bool | activate () |
virtual bool | activate () |
virtual bool | cleanup () |
virtual bool | cleanup () |
virtual bool | configure () |
virtual bool | configure () |
const ExecutionEngine * | engine () const |
ExecutionEngine * | engine () |
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, const std::string &name=std::string()) | |
virtual bool | trigger () |
virtual bool | trigger () |
virtual bool | update () |
virtual bool | update () |
virtual | ~TaskCore () |
Private Types | |
typedef boost::shared_ptr< tf2::BufferCore > | BufferCorePtr |
typedef boost::shared_ptr< RTT::OutputPort< geometry_msgs::TransformStamped > > | OutputPortGeometryTransfromStampedPtr |
typedef boost::shared_ptr< tf2_ros::TransformListener > | TransformListenerPtr |
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) |
void | listTrackers () |
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 |
bool | subscribeTransfrom (const std::string &target, const std::string &source) |
Private Attributes | |
BufferCorePtr | buffer_core |
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 |
std::map< std::pair< std::string, std::string >, OutputPortGeometryTransfromStampedPtr > | ports_trackers |
double | prop_buffer_size |
double | prop_cache_time |
std::string | prop_tf_prefix |
TransformListenerPtr | transform_listener |
Static Private Attributes | |
static const int | DEFAULT_BUFFER_SIZE = 100 |
Additional Inherited Members | |
![]() | |
typedef std::vector< std::string > | PeerList |
typedef boost::function< void(base::PortInterface *)> | SlotFunction |
![]() | |
enum | TaskState |
![]() | |
Exception | |
FatalError | |
Init | |
PreOperational | |
Running | |
RunTimeError | |
Stopped | |
![]() | |
typedef boost::function< void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, ros::Time time, TransformableResult result)> | TransformableCallback |
![]() | |
virtual void | dataOnPortCallback (base::PortInterface *port) |
virtual bool | dataOnPortHook (base::PortInterface *port) |
void | forceActivity (base::ActivityInterface *new_act) |
![]() | |
virtual bool | breakUpdateHook () |
virtual void | errorHook () |
virtual void | exception () |
virtual void | exceptionHook () |
virtual void | fatal () |
![]() | |
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) |
![]() | |
ExecutionEngine * | ee |
unsigned int | mCycleCounter |
unsigned int | mIOCounter |
std::string | mName |
TaskState | mTaskState |
unsigned int | mTimeOutCounter |
unsigned int | mTriggerCounter |
bool | mTriggerOnStart |
![]() | |
static const int | DEFAULT_CACHE_TIME |
static const uint32_t | MAX_GRAPH_DEPTH |
Definition at line 14 of file rtt_tf-component.hpp.
|
private |
Definition at line 18 of file rtt_tf-component.hpp.
|
private |
Definition at line 16 of file rtt_tf-component.hpp.
Definition at line 17 of file rtt_tf-component.hpp.
rtt_tf::RTT_TF::RTT_TF | ( | std::string const & | name | ) |
Definition at line 75 of file rtt_tf-component.cpp.
|
private |
Definition at line 92 of file rtt_tf-component.cpp.
|
private |
Definition at line 306 of file rtt_tf-component.cpp.
|
private |
Definition at line 313 of file rtt_tf-component.cpp.
|
private |
Definition at line 293 of file rtt_tf-component.cpp.
|
private |
Definition at line 300 of file rtt_tf-component.cpp.
|
private |
Definition at line 270 of file rtt_tf-component.cpp.
|
private |
Definition at line 277 of file rtt_tf-component.cpp.
|
virtual |
Reimplemented from RTT::base::TaskCore.
Definition at line 241 of file rtt_tf-component.cpp.
|
virtual |
Reimplemented from RTT::base::TaskCore.
Definition at line 141 of file rtt_tf-component.cpp.
|
private |
Definition at line 249 of file rtt_tf-component.cpp.
|
private |
Definition at line 174 of file rtt_tf-component.cpp.
|
private |
Definition at line 341 of file rtt_tf-component.cpp.
|
private |
Definition at line 263 of file rtt_tf-component.cpp.
|
private |
Definition at line 285 of file rtt_tf-component.cpp.
|
virtual |
Reimplemented from RTT::base::TaskCore.
Definition at line 206 of file rtt_tf-component.cpp.
|
virtual |
Reimplemented from RTT::base::TaskCore.
Definition at line 235 of file rtt_tf-component.cpp.
|
private |
Definition at line 319 of file rtt_tf-component.cpp.
|
virtual |
Reimplemented from RTT::base::TaskCore.
Definition at line 217 of file rtt_tf-component.cpp.
|
private |
Definition at line 31 of file rtt_tf-component.hpp.
|
staticprivate |
Definition at line 20 of file rtt_tf-component.hpp.
|
private |
Definition at line 26 of file rtt_tf-component.hpp.
|
private |
Definition at line 28 of file rtt_tf-component.hpp.
|
private |
Definition at line 27 of file rtt_tf-component.hpp.
|
private |
Definition at line 29 of file rtt_tf-component.hpp.
|
private |
Definition at line 30 of file rtt_tf-component.hpp.
|
private |
Definition at line 23 of file rtt_tf-component.hpp.
|
private |
Definition at line 22 of file rtt_tf-component.hpp.
|
private |
Definition at line 24 of file rtt_tf-component.hpp.
|
private |
Definition at line 32 of file rtt_tf-component.hpp.