Go to the documentation of this file.
29 #include <std_msgs/Bool.h>
36 const std::string& reference_frame)
37 :
FeatureTracker{
id, nh }, _tf_buffer_ptr(tf_buffer_ptr), _reference_frame(reference_frame)
48 ns_ =
"/humans/voices/" +
id_;
52 ns_ +
"/is_speaking", 1, [&](
const std_msgs::BoolConstPtr msg) {
66 if (msg->incremental.size() > 0)
75 if (msg->final.size() > 0)
98 return boost::optional<geometry_msgs::TransformStamped>();
std::vector< std::function< void(const std::string &)> > incremental_speech_callbacks
std::string _incremental_speech
std::string _reference_frame
ros::Subscriber speech_subscriber_
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the estimated (stamped) 3D transform of the voice (if available).
std::vector< std::function< void(const std::string &)> > speech_callbacks
#define ROS_DEBUG_STREAM(args)
#define ROS_WARN_STREAM(args)
std::vector< std::function< void(bool)> > is_speaking_callbacks
void _onSpeech(const hri_msgs::LiveSpeechConstPtr &)
std::string frame() const
the name of the tf frame that correspond to this body
const static ros::Duration VOICE_TF_TIMEOUT(0.01)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
tf2_ros::Buffer * _tf_buffer_ptr
ros::Subscriber is_speaking_subscriber_
virtual 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 ros::Duration timeout) const
libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58