Go to the documentation of this file.
29 #include <std_msgs/String.h>
30 #include <std_msgs/Bool.h>
32 #include "geometry_msgs/TransformStamped.h"
36 #include "hri_msgs/EngagementLevel.h"
37 #include "std_msgs/Float32.h"
46 , _engagement_status(
nullptr)
49 , _tf_buffer_ptr(tf_buffer_ptr)
50 , _reference_frame(reference_frame)
62 ns_ =
"/humans/persons/" +
id_;
66 ns_ +
"/face_id", 1, [&](
const std_msgs::StringConstPtr msg) {
face_id = msg->data; });
69 ns_ +
"/body_id", 1, [&](
const std_msgs::StringConstPtr msg) {
body_id = msg->data; });
73 [&](
const std_msgs::StringConstPtr msg) {
voice_id = msg->data; });
76 ns_ +
"/anonymous", 1,
77 [&](
const std_msgs::BoolConstPtr msg) {
_anonymous = msg->data; });
80 ns_ +
"/alias", 1, [&](
const std_msgs::StringConstPtr msg) {
_alias = msg->data; });
83 ns_ +
"/engagement_status", 1,
87 ns_ +
"/location_confidence", 1,
88 [&](
const std_msgs::Float32ConstPtr msg) {
_loc_confidence = msg->data; });
119 return boost::optional<EngagementLevel>();
124 case hri_msgs::EngagementLevel::UNKNOWN:
125 return boost::optional<EngagementLevel>();
137 return boost::optional<EngagementLevel>();
145 return boost::optional<geometry_msgs::TransformStamped>();
158 <<
". Are the frames published?");
159 return boost::optional<geometry_msgs::TransformStamped>();
ros::Subscriber voice_id_subscriber_
ros::Subscriber face_id_subscriber_
ros::Subscriber body_id_subscriber_
std::string frame() const
#define ROS_DEBUG_STREAM(args)
std::map< ID, BodyWeakConstPtr > getBodies() const
Returns the list of currently detected bodies, mapped to their IDs.
std::string _reference_frame
ros::Subscriber alias_subscriber_
FaceWeakConstPtr face() const
#define ROS_WARN_STREAM(args)
hri_msgs::EngagementLevelConstPtr _engagement_status
boost::optional< EngagementLevel > engagement_status() const
std::weak_ptr< const Voice > VoiceWeakConstPtr
std::weak_ptr< const Face > FaceWeakConstPtr
std::weak_ptr< const Body > BodyWeakConstPtr
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())
ros::Subscriber loc_confidence_subscriber_
ros::Subscriber anonymous_subscriber_
std::map< ID, FaceWeakConstPtr > getFaces() const
Returns the list of currently detected faces, mapped to their IDs.
Main entry point to libhri. This is most likely what you want to use. Use example:
boost::optional< geometry_msgs::TransformStamped > transform() const
const static ros::Duration PERSON_TF_TIMEOUT(0.01)
boost::optional< bool > _anonymous
BodyWeakConstPtr body() const
std::map< ID, VoiceWeakConstPtr > getVoices() const
Returns the list of currently detected voices, mapped to their IDs.
const HRIListener * listener_
ros::Subscriber engagement_subscriber_
tf2_ros::Buffer * _tf_buffer_ptr
VoiceWeakConstPtr voice() const
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
libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58