Class FeatureTracker

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< FeatureTracker >

Derived Types

Class Documentation

class FeatureTracker : public std::enable_shared_from_this<FeatureTracker>

Subclassed by hri::Body, hri::Face, hri::Person, hri::Voice

Public Functions

explicit FeatureTracker(ID id, std::string feature_ns, std::string feature_tf_prefix, NodeInterfaces node_interfaces, rclcpp::CallbackGroup::SharedPtr callback_group, const tf2::BufferCore &tf_buffer, const std::string &reference_frame)

Creates a new feature tracker (eg, a face, body or voice tracker).

This constructor should not be called directly. Instead, use one of the specialization: hri::Face, hri::Body, hri::Voice.

Note however that instances would normally be automatically created, and accessed via the methods exposed by hri::HRIListener.

Note that the resulting instance is non-copyable, as it includes non-trivial, and typically non-reentrant, logic to subscribe/unsubscribe HRI-related topics.

virtual ~FeatureTracker() = default
FeatureTracker(const FeatureTracker&) = delete
inline ID id() const

Returns the unique ID of this feature.

:see: FeatureTracker::getNamespace, to access the fully-qualified topic namespace under which this feature is published.

inline std::string ns() const

Returns the topic namespace under which this feature is advertised.

inline std::string frame() const

Returns the name of the tf frame that correspond to this feature.

inline bool valid() const

Returns whether the feature is still ‘valid’, i.e., existing.

If not, then the feature is not functional, all the optional members will be reset and the topic subsciptions terminated.

inline virtual std::optional<geometry_msgs::msg::TransformStamped> transform() const

Returns the estimated (stamped) 3D transform of self (if available).

inline bool operator<(const FeatureTracker &other) const

Protected Functions

std::optional<geometry_msgs::msg::TransformStamped> transformFromReference(std::string frame_name) const

Returns the estimated (stamped) 3D transform of the argument frame (if available).

inline void invalidate()

Makes the feature ‘invalid’, i.e., not existing anymore.

Protected Attributes

const ID kId_
const std::string kNs_
const std::string kFrame_
NodeInterfaces node_interfaces_
rclcpp::CallbackGroup::SharedPtr callback_group_
const tf2::BufferCore &tf_buffer_
const std::string &reference_frame_
bool valid_