voice.cpp
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 #include <std_msgs/Bool.h>
30 #include "hri/voice.h"
31 
32 using namespace std;
33 using namespace hri;
34 
35 Voice::Voice(ID id, ros::NodeHandle& nh, tf2_ros::Buffer* tf_buffer_ptr,
36  const std::string& reference_frame)
37  : FeatureTracker{ id, nh }, _tf_buffer_ptr(tf_buffer_ptr), _reference_frame(reference_frame)
38 {
39 }
40 
42 {
43  ROS_DEBUG_STREAM("Deleting voice " << id_);
44 }
45 
47 {
48  ns_ = "/humans/voices/" + id_;
49  ROS_DEBUG_STREAM("New voice detected: " << ns_);
50 
51  is_speaking_subscriber_ = node_.subscribe<std_msgs::Bool>(
52  ns_ + "/is_speaking", 1, [&](const std_msgs::BoolConstPtr msg) {
53  _is_speaking = msg->data;
54  for (auto& cb : is_speaking_callbacks)
55  {
56  cb(msg->data);
57  }
58  });
59 
61  node_.subscribe<hri_msgs::LiveSpeech>(ns_ + "/speech", 1, &Voice::_onSpeech, this);
62 }
63 
64 void Voice::_onSpeech(const hri_msgs::LiveSpeechConstPtr& msg)
65 {
66  if (msg->incremental.size() > 0)
67  {
68  _incremental_speech = msg->incremental;
69  for (auto cb : incremental_speech_callbacks)
70  {
72  }
73  }
74 
75  if (msg->final.size() > 0)
76  {
77  _speech = msg->final;
78  for (auto cb : speech_callbacks)
79  {
80  cb(_speech);
81  }
82  }
83 }
84 
85 boost::optional<geometry_msgs::TransformStamped> Voice::transform() const
86 {
87  try
88  {
91 
92  return transform;
93  }
94  catch (tf2::LookupException)
95  {
96  ROS_WARN_STREAM("failed to transform the voice frame "
97  << frame() << " to " << _reference_frame << ". Are the frames published?");
98  return boost::optional<geometry_msgs::TransformStamped>();
99  }
100 }
hri::FeatureTracker::id
ID id() const
Definition: base.h:88
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::Voice::transform
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the estimated (stamped) 3D transform of the voice (if available).
Definition: voice.cpp:85
hri::Voice::speech_callbacks
std::vector< std::function< void(const std::string &)> > speech_callbacks
Definition: voice.h:137
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
hri::Voice::is_speaking_callbacks
std::vector< std::function< void(bool)> > is_speaking_callbacks
Definition: voice.h:136
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
ros::NodeHandle::subscribe
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::LookupException
hri::Voice::_speech
std::string _speech
Definition: voice.h:133
ros::Time
std
hri::Voice::_tf_buffer_ptr
tf2_ros::Buffer * _tf_buffer_ptr
Definition: voice.h:130
hri::ID
std::string ID
Definition: base.h:40
hri::Voice::is_speaking_subscriber_
ros::Subscriber is_speaking_subscriber_
Definition: voice.h:142
voice.h
hri::Voice::~Voice
virtual ~Voice()
Definition: voice.cpp:41
hri::FeatureTracker::ns_
std::string ns_
Definition: base.h:119
tf2_ros::Buffer::lookupTransform
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
ros::NodeHandle
hri::FeatureTracker::node_
ros::NodeHandle node_
Definition: base.h:121
hri::FeatureTracker::id_
ID id_
Definition: base.h:116


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