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 
112  void onSpeech(std::function<void(const std::string&)> callback)
113  {
114  speech_callbacks.push_back(callback);
115  }
116 
121  void onIncrementalSpeech(std::function<void(const std::string&)> callback)
122  {
123  incremental_speech_callbacks.push_back(callback);
124  }
125 
126  void init() override;
127 
128 private:
129  std::string _reference_frame;
131 
133  std::string _speech;
134  std::string _incremental_speech;
135 
136  std::vector<std::function<void(bool)>> is_speaking_callbacks;
137  std::vector<std::function<void(const std::string&)>> speech_callbacks;
138  std::vector<std::function<void(const std::string&)>> incremental_speech_callbacks;
139 
140  void _onSpeech(const hri_msgs::LiveSpeechConstPtr&);
141 
144 };
145 
146 typedef std::shared_ptr<Voice> VoicePtr;
147 typedef std::shared_ptr<const Voice> VoiceConstPtr;
148 typedef std::weak_ptr<Voice> VoiceWeakPtr;
149 typedef std::weak_ptr<const Voice> VoiceWeakConstPtr;
150 
151 } // namespace hri
152 #endif
hri::VoiceConstPtr
std::shared_ptr< const Voice > VoiceConstPtr
Definition: voice.h:147
hri::Voice::incremental_speech_callbacks
std::vector< std::function< void(const std::string &)> > incremental_speech_callbacks
Definition: voice.h:138
hri
Definition: base.h:38
hri::Voice::_incremental_speech
std::string _incremental_speech
Definition: voice.h:134
hri::FeatureTracker
Definition: base.h:52
hri::Voice::init
void init() override
Definition: voice.cpp:46
hri::Voice::_reference_frame
std::string _reference_frame
Definition: voice.h:129
hri::Voice::speech_subscriber_
ros::Subscriber speech_subscriber_
Definition: voice.h:143
hri::Voice::_is_speaking
bool _is_speaking
Definition: voice.h:132
hri::VoiceWeakPtr
std::weak_ptr< Voice > VoiceWeakPtr
Definition: voice.h:148
hri::Voice::transform
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the estimated (stamped) 3D transform of the voice (if available).
Definition: voice.cpp:85
base.h
hri::Voice::speech_callbacks
std::vector< std::function< void(const std::string &)> > speech_callbacks
Definition: voice.h:137
hri::Voice::is_speaking
bool is_speaking() const
returns speech is currently detected in this voice, ie, whether the person is currently speaking.
Definition: voice.h:72
hri::Voice::is_speaking_callbacks
std::vector< std::function< void(bool)> > is_speaking_callbacks
Definition: voice.h:136
hri::VoiceWeakConstPtr
std::weak_ptr< const Voice > VoiceWeakConstPtr
Definition: voice.h:149
hri::Voice::_onSpeech
void _onSpeech(const hri_msgs::LiveSpeechConstPtr &)
Definition: voice.cpp:64
hri::Voice::frame
std::string frame() const
the name of the tf frame that correspond to this body
Definition: voice.h:59
hri::VOICE_TF_TIMEOUT
const static ros::Duration VOICE_TF_TIMEOUT(0.01)
tf2_ros::Buffer
hri::Voice
Definition: voice.h:49
transform_listener.h
hri::Voice::_speech
std::string _speech
Definition: voice.h:133
hri::Voice::speech
std::string speech() const
returns the last recognised final sentence (or an empty string if no speech was recognised yet).
Definition: voice.h:80
hri::Voice::incremental_speech
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
hri::Voice::onIncrementalSpeech
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:121
hri::Voice::onSpeech
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:112
hri::VOICE_TF_PREFIX
const static std::string VOICE_TF_PREFIX("voice_")
hri::Voice::_tf_buffer_ptr
tf2_ros::Buffer * _tf_buffer_ptr
Definition: voice.h:130
hri::Voice::onSpeaking
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
hri::ID
std::string ID
Definition: base.h:40
hri::Voice::is_speaking_subscriber_
ros::Subscriber is_speaking_subscriber_
Definition: voice.h:142
hri::Voice::~Voice
virtual ~Voice()
Definition: voice.cpp:41
ros::Duration
hri::VoicePtr
std::shared_ptr< Voice > VoicePtr
Definition: voice.h:146
hri::Voice::Voice
Voice(ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
Definition: voice.cpp:35
ros::NodeHandle
ros::Subscriber
hri::FeatureTracker::id_
ID id_
Definition: base.h:116


libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58