Go to the documentation of this file.
32 #include <geometry_msgs/TransformStamped.h>
35 #include <boost/optional.hpp>
42 #include <hri_msgs/EngagementLevel.h>
43 #include <std_msgs/Float32.h>
117 boost::optional<geometry_msgs::TransformStamped>
transform()
const;
119 void init()
override;
132 void tfCallback(
const geometry_msgs::TransformStampedConstPtr& transform_ptr)
boost::optional< bool > anonymous() const
ros::Subscriber voice_id_subscriber_
ros::Subscriber face_id_subscriber_
ros::Subscriber body_id_subscriber_
Person(ID id, const HRIListener *listener, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
std::string frame() const
std::string _reference_frame
std::weak_ptr< Person > PersonWeakPtr
ros::Subscriber alias_subscriber_
FaceWeakConstPtr face() const
hri_msgs::EngagementLevelConstPtr _engagement_status
boost::optional< EngagementLevel > engagement_status() const
std::weak_ptr< const Voice > VoiceWeakConstPtr
std::shared_ptr< const Person > PersonConstPtr
std::weak_ptr< const Face > FaceWeakConstPtr
const static std::string PERSON_TF_PREFIX("person_")
std::weak_ptr< const Body > BodyWeakConstPtr
ros::Subscriber loc_confidence_subscriber_
ros::Subscriber anonymous_subscriber_
std::weak_ptr< const Person > PersonWeakConstPtr
float location_confidence() const
std::shared_ptr< Person > PersonPtr
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
const HRIListener * listener_
ros::Subscriber engagement_subscriber_
tf2_ros::Buffer * _tf_buffer_ptr
VoiceWeakConstPtr voice() const
void tfCallback(const geometry_msgs::TransformStampedConstPtr &transform_ptr)
libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58