person.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 #ifndef HRI_PERSON_H
30 #define HRI_PERSON_H
31 
32 #include <geometry_msgs/TransformStamped.h>
33 #include <functional>
34 #include <memory>
35 #include <boost/optional.hpp>
36 
37 #include "base.h"
38 #include "face.h"
39 #include "body.h"
40 #include "voice.h"
41 
42 #include <hri_msgs/EngagementLevel.h>
43 #include <std_msgs/Float32.h>
44 
46 #include "tf2_ros/message_filter.h"
48 
49 
50 namespace hri
51 {
52 const static std::string PERSON_TF_PREFIX("person_");
53 const static ros::Duration PERSON_TF_TIMEOUT(0.01);
54 
56 {
57  // disengaged: the human has not looked in the direction of the robot
59  // engaging: the human has started to look in the direction of the robot
60  ENGAGING = 2,
61  // engaged: the human is fully engaged with the robot
62  ENGAGED = 3,
63  // disengaging: the human has started to look away from the robot
65 };
66 
67 
68 class HRIListener;
69 
70 
71 class Person : public FeatureTracker
72 {
73 public:
74  Person(ID id, const HRIListener* listener, ros::NodeHandle& nh,
75  tf2_ros::Buffer* tf_buffer_ptr, const std::string& reference_frame);
76 
77  virtual ~Person();
78 
79  std::string frame() const
80  {
81  return PERSON_TF_PREFIX + id_;
82  }
83 
84  /* returns a (weak, constant) pointer to the face of this person, or
85  * a nullptr if this person is currently not associated to any detected face.
86  */
87  FaceWeakConstPtr face() const;
88 
89  /* returns a (weak, constant) pointer to the body of this person, or
90  * a nullptr if this person is currently not associated to any detected body.
91  */
92  BodyWeakConstPtr body() const;
93 
94  /* returns a (weak, constant) pointer to the voice of this person, or
95  * a nullptr if this person is currently not associated to any detected voice.
96  */
97  VoiceWeakConstPtr voice() const;
98 
99 
100  boost::optional<bool> anonymous() const
101  {
102  return _anonymous;
103  }
104 
105  ID alias() const
106  {
107  return _alias;
108  }
109 
110  boost::optional<EngagementLevel> engagement_status() const;
111 
112  float location_confidence() const
113  {
114  return _loc_confidence;
115  }
116 
117  boost::optional<geometry_msgs::TransformStamped> transform() const;
118 
119  void init() override;
123 
124 
125 protected:
126  // we use a raw pointer here. `this` is owned by the pointed HRIListener, so
127  // `this` would normally be destroyed before HRIListener (in reality, a
128  // pointer to `this` *might* outlive `HRIListener` -- make sure HRIListener
129  // is destroyed after all pointers to this person are released.
131 
132  void tfCallback(const geometry_msgs::TransformStampedConstPtr& transform_ptr)
133  {
134  ROS_WARN("got tf transform!");
135  }
136 
137  // if non-empty, this person 'does not exist' and is instead an alias to
138  // another person. hri::getPersons and hri::getTrackedPersons will returns
139  // pointers to the aliased person.
141 
142  boost::optional<bool> _anonymous;
143 
144  hri_msgs::EngagementLevelConstPtr _engagement_status;
145 
147 
148  std::string _reference_frame;
149 
157 
159 };
160 
161 typedef std::shared_ptr<Person> PersonPtr;
162 typedef std::shared_ptr<const Person> PersonConstPtr;
163 typedef std::weak_ptr<Person> PersonWeakPtr;
164 typedef std::weak_ptr<const Person> PersonWeakConstPtr;
165 
166 
167 } // namespace hri
168 
169 #endif
hri::Person::~Person
virtual ~Person()
Definition: person.cpp:55
hri::Person::anonymous
boost::optional< bool > anonymous() const
Definition: person.h:100
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
face.h
hri::DISENGAGING
@ DISENGAGING
Definition: person.h:64
hri::Person::Person
Person(ID id, const HRIListener *listener, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
Definition: person.cpp:42
hri::Person::_loc_confidence
float _loc_confidence
Definition: person.h:146
hri::Person::frame
std::string frame() const
Definition: person.h:79
base.h
hri::DISENGAGED
@ DISENGAGED
Definition: person.h:58
hri::Person::alias
ID alias() const
Definition: person.h:105
hri::Person::body_id
ID body_id
Definition: person.h:121
hri::Person::_reference_frame
std::string _reference_frame
Definition: person.h:148
hri::PersonWeakPtr
std::weak_ptr< Person > PersonWeakPtr
Definition: person.h:163
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
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::PersonConstPtr
std::shared_ptr< const Person > PersonConstPtr
Definition: person.h:162
message_filter.h
hri::Person
Definition: person.h:71
hri::FaceWeakConstPtr
std::weak_ptr< const Face > FaceWeakConstPtr
Definition: face.h:211
subscriber.h
hri::PERSON_TF_PREFIX
const static std::string PERSON_TF_PREFIX("person_")
hri::BodyWeakConstPtr
std::weak_ptr< const Body > BodyWeakConstPtr
Definition: body.h:139
ROS_WARN
#define ROS_WARN(...)
tf2_ros::Buffer
hri::EngagementLevel
EngagementLevel
Definition: person.h:55
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
body.h
hri::Person::anonymous_subscriber_
ros::Subscriber anonymous_subscriber_
Definition: person.h:153
transform_listener.h
hri::PersonWeakConstPtr
std::weak_ptr< const Person > PersonWeakConstPtr
Definition: person.h:164
hri::Person::location_confidence
float location_confidence() const
Definition: person.h:112
hri::PersonPtr
std::shared_ptr< Person > PersonPtr
Definition: person.h:161
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
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::Person::listener_
const HRIListener * listener_
Definition: person.h:130
hri::Person::engagement_subscriber_
ros::Subscriber engagement_subscriber_
Definition: person.h:155
voice.h
ros::Duration
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
ros::NodeHandle
hri::Person::tfCallback
void tfCallback(const geometry_msgs::TransformStampedConstPtr &transform_ptr)
Definition: person.h:132
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