voice.h
Go to the documentation of this file.
1 // Copyright 2022 PAL Robotics S.L.
2 //
3 // Redistribution and use in source and binary forms, with or without
4 // modification, are permitted provided that the following conditions are met:
5 //
6 // * Redistributions of source code must retain the above copyright
7 // notice, this list of conditions and the following disclaimer.
8 //
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 //
13 // * Neither the name of the PAL Robotics S.L. nor the names of its
14 // contributors may be used to endorse or promote products derived from
15 // this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 
29 
30 #ifndef HRI_VOICE_H
31 #define HRI_VOICE_H
32 
33 #include <geometry_msgs/TransformStamped.h>
34 #include <hri_msgs/LiveSpeech.h>
35 
36 #include <memory>
37 #include <boost/optional.hpp>
38 
39 #include "base.h"
40 
42 
43 namespace hri
44 {
45 // the tf prefix follows REP-155
46 const static std::string VOICE_TF_PREFIX("voice_");
47 const static ros::Duration VOICE_TF_TIMEOUT(0.01);
48 
49 class Voice : public FeatureTracker
50 {
51 public:
52  Voice(ID id, ros::NodeHandle& nh, tf2_ros::Buffer* tf_buffer_ptr,
53  const std::string& reference_frame);
54 
55  virtual ~Voice();
56 
59  std::string frame() const
60  {
61  return VOICE_TF_PREFIX + id_;
62  }
63 
67  boost::optional<geometry_msgs::TransformStamped> transform() const;
68 
72  bool is_speaking() const
73  {
74  return _is_speaking;
75  }
76 
80  std::string speech() const
81  {
82  return _speech;
83  }
84 
88  std::string incremental_speech() const
89  {
90  return _incremental_speech;
91  }
92 
101  void onSpeaking(std::function<void(bool)> callback)
102  {
103  is_speaking_callbacks.push_back(callback);
104  }
105 
106 
113  void onSpeech(std::function<void(const std::string&)> callback)
114  {
115  speech_callbacks.push_back(callback);
116  }
117 
122  void onIncrementalSpeech(std::function<void(const std::string&)> callback)
123  {
124  incremental_speech_callbacks.push_back(callback);
125  }
126 
127  void init() override;
128 
129 private:
130  std::string _reference_frame;
132 
134  std::string _speech;
135  std::string _incremental_speech;
136 
137  std::vector<std::function<void(bool)>> is_speaking_callbacks;
138  std::vector<std::function<void(const std::string&)>> speech_callbacks;
139  std::vector<std::function<void(const std::string&)>> incremental_speech_callbacks;
140 
141  void _onSpeech(const hri_msgs::LiveSpeechConstPtr&);
142 
145 };
146 
147 typedef std::shared_ptr<Voice> VoicePtr;
148 typedef std::shared_ptr<const Voice> VoiceConstPtr;
149 typedef std::weak_ptr<Voice> VoiceWeakPtr;
150 typedef std::weak_ptr<const Voice> VoiceWeakConstPtr;
151 
152 } // namespace hri
153 #endif
std::string _reference_frame
Definition: voice.h:130
static const ros::Duration VOICE_TF_TIMEOUT(0.01)
std::shared_ptr< const Voice > VoiceConstPtr
Definition: voice.h:148
std::weak_ptr< const Voice > VoiceWeakConstPtr
Definition: voice.h:150
std::string _speech
Definition: voice.h:134
std::string incremental_speech() const
returns the last recognised incremental sentence (or an empty string if no speech was recognised yet)...
Definition: voice.h:88
static const std::string VOICE_TF_PREFIX("voice_")
void onIncrementalSpeech(std::function< void(const std::string &)> callback)
Registers a callback function, to be invoked everytime speech is recognised from this voice...
Definition: voice.h:122
ros::Subscriber speech_subscriber_
Definition: voice.h:144
bool _is_speaking
Definition: voice.h:133
tf2_ros::Buffer * _tf_buffer_ptr
Definition: voice.h:131
std::vector< std::function< void(const std::string &)> > speech_callbacks
Definition: voice.h:138
ros::Subscriber is_speaking_subscriber_
Definition: voice.h:143
Voice(ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
Definition: voice.cpp:35
std::weak_ptr< Voice > VoiceWeakPtr
Definition: voice.h:149
std::vector< std::function< void(const std::string &)> > incremental_speech_callbacks
Definition: voice.h:139
std::string _incremental_speech
Definition: voice.h:135
std::string speech() const
returns the last recognised final sentence (or an empty string if no speech was recognised yet)...
Definition: voice.h:80
void init() override
Definition: voice.cpp:46
void onSpeaking(std::function< void(bool)> callback)
Registers a callback function, to be invoked everytime speech is detected (ie, the person is speaking...
Definition: voice.h:101
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the estimated (stamped) 3D transform of the voice (if available).
Definition: voice.cpp:85
Definition: base.h:38
bool is_speaking() const
returns speech is currently detected in this voice, ie, whether the person is currently speaking...
Definition: voice.h:72
void onSpeech(std::function< void(const std::string &)> callback)
Registers a callback function, to be invoked everytime speech is recognised from this voice...
Definition: voice.h:113
std::shared_ptr< Voice > VoicePtr
Definition: voice.h:147
void _onSpeech(const hri_msgs::LiveSpeechConstPtr &)
Definition: voice.cpp:64
std::string frame() const
the name of the tf frame that correspond to this body
Definition: voice.h:59
virtual ~Voice()
Definition: voice.cpp:41
std::vector< std::function< void(bool)> > is_speaking_callbacks
Definition: voice.h:137
std::string ID
Definition: base.h:40


libhri
Author(s): Séverin Lemaignan
autogenerated on Wed Apr 19 2023 02:30:41