person.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/String.h>
30 #include <std_msgs/Bool.h>
31 
32 #include "geometry_msgs/TransformStamped.h"
33 #include "hri/person.h"
34 
35 #include "hri/hri.h"
36 #include "hri_msgs/EngagementLevel.h"
37 #include "std_msgs/Float32.h"
38 
39 using namespace std;
40 using namespace hri;
41 
42 Person::Person(ID id, const HRIListener* listener, ros::NodeHandle& nh,
43  tf2_ros::Buffer* tf_buffer_ptr, const std::string& reference_frame)
44  : FeatureTracker{ id, nh }
45  , listener_(listener)
46  , _engagement_status(nullptr)
47  , _alias("")
48  , _loc_confidence(0.)
49  , _tf_buffer_ptr(tf_buffer_ptr)
50  , _reference_frame(reference_frame)
51 {
52 }
53 
54 
56 {
57  ROS_DEBUG_STREAM("Deleting person " << id_);
58 }
59 
61 {
62  ns_ = "/humans/persons/" + id_;
63  ROS_DEBUG_STREAM("New person detected: " << ns_);
64 
65  face_id_subscriber_ = node_.subscribe<std_msgs::String>(
66  ns_ + "/face_id", 1, [&](const std_msgs::StringConstPtr msg) { face_id = msg->data; });
67 
68  body_id_subscriber_ = node_.subscribe<std_msgs::String>(
69  ns_ + "/body_id", 1, [&](const std_msgs::StringConstPtr msg) { body_id = msg->data; });
70 
71  voice_id_subscriber_ = node_.subscribe<std_msgs::String>(
72  ns_ + "/voice_id", 1,
73  [&](const std_msgs::StringConstPtr msg) { voice_id = msg->data; });
74 
75  anonymous_subscriber_ = node_.subscribe<std_msgs::Bool>(
76  ns_ + "/anonymous", 1,
77  [&](const std_msgs::BoolConstPtr msg) { _anonymous = msg->data; });
78 
79  alias_subscriber_ = node_.subscribe<std_msgs::String>(
80  ns_ + "/alias", 1, [&](const std_msgs::StringConstPtr msg) { _alias = msg->data; });
81 
83  ns_ + "/engagement_status", 1,
84  [&](const hri_msgs::EngagementLevelConstPtr msg) { _engagement_status = msg; });
85 
86  loc_confidence_subscriber_ = node_.subscribe<std_msgs::Float32>(
87  ns_ + "/location_confidence", 1,
88  [&](const std_msgs::Float32ConstPtr msg) { _loc_confidence = msg->data; });
89 }
90 
92 {
93  if (listener_->getFaces().count(face_id) != 0)
94  return listener_->getFaces()[face_id];
95  else
96  return FaceWeakConstPtr();
97 }
98 
100 {
101  if (listener_->getBodies().count(body_id) != 0)
102  return listener_->getBodies()[body_id];
103  else
104  return BodyWeakConstPtr();
105 }
106 
108 {
109  if (listener_->getVoices().count(voice_id) != 0)
110  return listener_->getVoices()[voice_id];
111  else
112  return VoiceWeakConstPtr();
113 }
114 
115 boost::optional<EngagementLevel> Person::engagement_status() const
116 {
117  if (!_engagement_status)
118  {
119  return boost::optional<EngagementLevel>();
120  }
121 
122  switch (_engagement_status->level)
123  {
124  case hri_msgs::EngagementLevel::UNKNOWN:
125  return boost::optional<EngagementLevel>();
134  default:
135  // we should handle all the possible engagement values
136  assert(false);
137  return boost::optional<EngagementLevel>();
138  }
139 }
140 
141 boost::optional<geometry_msgs::TransformStamped> Person::transform() const
142 {
143  if (_loc_confidence == 0)
144  {
145  return boost::optional<geometry_msgs::TransformStamped>();
146  }
147 
148  try
149  {
152 
153  return transform;
154  }
155  catch (tf2::LookupException)
156  {
157  ROS_WARN_STREAM("failed to transform person frame " << frame() << " to " << _reference_frame
158  << ". Are the frames published?");
159  return boost::optional<geometry_msgs::TransformStamped>();
160  }
161 }
162 
hri::Person::~Person
virtual ~Person()
Definition: person.cpp:55
hri::FeatureTracker::id
ID id() const
Definition: base.h:88
hri::Person::voice_id_subscriber_
ros::Subscriber voice_id_subscriber_
Definition: person.h:152
hri
Definition: base.h:38
hri::FeatureTracker
Definition: base.h:52
hri::Person::face_id_subscriber_
ros::Subscriber face_id_subscriber_
Definition: person.h:150
hri::Person::body_id_subscriber_
ros::Subscriber body_id_subscriber_
Definition: person.h:151
hri::DISENGAGING
@ DISENGAGING
Definition: person.h:64
hri::Person::_loc_confidence
float _loc_confidence
Definition: person.h:146
hri::Person::frame
std::string frame() const
Definition: person.h:79
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
hri::DISENGAGED
@ DISENGAGED
Definition: person.h:58
hri::HRIListener::getBodies
std::map< ID, BodyWeakConstPtr > getBodies() const
Returns the list of currently detected bodies, mapped to their IDs.
Definition: hri.cpp:76
hri::Person::body_id
ID body_id
Definition: person.h:121
hri::Person::_reference_frame
std::string _reference_frame
Definition: person.h:148
hri::Person::alias_subscriber_
ros::Subscriber alias_subscriber_
Definition: person.h:154
hri::Person::face
FaceWeakConstPtr face() const
Definition: person.cpp:91
hri::ENGAGED
@ ENGAGED
Definition: person.h:62
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
hri::Person::_engagement_status
hri_msgs::EngagementLevelConstPtr _engagement_status
Definition: person.h:144
hri::Person::engagement_status
boost::optional< EngagementLevel > engagement_status() const
Definition: person.cpp:115
hri::VoiceWeakConstPtr
std::weak_ptr< const Voice > VoiceWeakConstPtr
Definition: voice.h:149
hri::ENGAGING
@ ENGAGING
Definition: person.h:60
hri::FaceWeakConstPtr
std::weak_ptr< const Face > FaceWeakConstPtr
Definition: face.h:211
hri.h
hri::BodyWeakConstPtr
std::weak_ptr< const Body > BodyWeakConstPtr
Definition: body.h:139
tf2_ros::Buffer
hri::EngagementLevel
EngagementLevel
Definition: person.h:55
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::Person::voice_id
ID voice_id
Definition: person.h:122
hri::Person::loc_confidence_subscriber_
ros::Subscriber loc_confidence_subscriber_
Definition: person.h:156
hri::Person::anonymous_subscriber_
ros::Subscriber anonymous_subscriber_
Definition: person.h:153
hri::HRIListener::getFaces
std::map< ID, FaceWeakConstPtr > getFaces() const
Returns the list of currently detected faces, mapped to their IDs.
Definition: hri.cpp:62
ros::Time
hri::HRIListener
Main entry point to libhri. This is most likely what you want to use. Use example:
Definition: hri.h:70
hri::Person::_alias
ID _alias
Definition: person.h:140
hri::Person::transform
boost::optional< geometry_msgs::TransformStamped > transform() const
Definition: person.cpp:141
std
hri::Person::init
void init() override
Definition: person.cpp:60
hri::PERSON_TF_TIMEOUT
const static ros::Duration PERSON_TF_TIMEOUT(0.01)
hri::Person::_anonymous
boost::optional< bool > _anonymous
Definition: person.h:142
hri::Person::face_id
ID face_id
Definition: person.h:120
hri::Person::body
BodyWeakConstPtr body() const
Definition: person.cpp:99
hri::ID
std::string ID
Definition: base.h:40
hri::HRIListener::getVoices
std::map< ID, VoiceWeakConstPtr > getVoices() const
Returns the list of currently detected voices, mapped to their IDs.
Definition: hri.cpp:90
hri::Person::listener_
const HRIListener * listener_
Definition: person.h:130
hri::Person::engagement_subscriber_
ros::Subscriber engagement_subscriber_
Definition: person.h:155
hri::FeatureTracker::ns_
std::string ns_
Definition: base.h:119
person.h
hri::Person::_tf_buffer_ptr
tf2_ros::Buffer * _tf_buffer_ptr
Definition: person.h:158
hri::Person::voice
VoiceWeakConstPtr voice() const
Definition: person.cpp:107
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