body.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 
30 #ifndef HRI_BODY_H
31 #define HRI_BODY_H
32 
33 #include <geometry_msgs/TransformStamped.h>
34 #include <sensor_msgs/RegionOfInterest.h>
35 #include <sensor_msgs/Image.h>
36 #include <hri_msgs/Skeleton2D.h>
37 #include <hri_msgs/NormalizedPointOfInterest2D.h>
38 #include <memory>
39 #include <boost/optional.hpp>
40 
41 #include "base.h"
42 #include "ros/subscriber.h"
43 
44 #include <opencv2/core.hpp>
45 
47 
48 typedef hri_msgs::NormalizedPointOfInterest2D SkeletonPoint;
49 
50 namespace hri
51 {
52 // the tf prefix follows REP-155
53 const static std::string BODY_TF_PREFIX("body_");
54 const static ros::Duration BODY_TF_TIMEOUT(0.01);
55 
56 class Body : public FeatureTracker
57 {
58 public:
59  Body(ID id, ros::NodeHandle& nh, tf2_ros::Buffer* tf_buffer_ptr,
60  const std::string& reference_frame);
61 
62  virtual ~Body();
63 
66  std::string frame() const
67  {
68  return BODY_TF_PREFIX + id_;
69  }
70 
94  cv::Rect roi() const;
95 
98  cv::Mat cropped() const;
99 
108  std::vector<SkeletonPoint> skeleton() const;
109 
112  boost::optional<geometry_msgs::TransformStamped> transform() const;
113 
114  void init() override;
115 
116 private:
117  size_t nb_roi;
118 
120  void onRoI(sensor_msgs::RegionOfInterestConstPtr roi);
121  cv::Rect roi_;
122 
124  void onCropped(sensor_msgs::ImageConstPtr roi);
125  cv::Mat cropped_;
126 
128  void onSkeleton(hri_msgs::Skeleton2DConstPtr skeleton);
129  std::vector<SkeletonPoint> skeleton_;
130 
131  std::string _reference_frame;
133 };
134 
135 typedef std::shared_ptr<Body> BodyPtr;
136 typedef std::shared_ptr<const Body> BodyConstPtr;
137 typedef std::weak_ptr<Body> BodyWeakPtr;
138 typedef std::weak_ptr<const Body> BodyWeakConstPtr;
139 
140 } // namespace hri
141 #endif
std::vector< SkeletonPoint > skeleton_
Definition: body.h:129
hri_msgs::NormalizedPointOfInterest2D SkeletonPoint
Definition: body.h:48
size_t nb_roi
Definition: body.h:117
std::weak_ptr< Body > BodyWeakPtr
Definition: body.h:137
void onRoI(sensor_msgs::RegionOfInterestConstPtr roi)
Definition: body.cpp:64
std::shared_ptr< Body > BodyPtr
Definition: body.h:135
cv::Rect roi_
Definition: body.h:121
std::vector< SkeletonPoint > skeleton() const
Returns the 2D skeleton keypoints.
Definition: body.cpp:89
cv::Mat cropped_
Definition: body.h:125
std::weak_ptr< const Body > BodyWeakConstPtr
Definition: body.h:138
Body(ID id, ros::NodeHandle &nh, tf2_ros::Buffer *tf_buffer_ptr, const std::string &reference_frame)
Definition: body.cpp:36
static const std::string BODY_TF_PREFIX("body_")
void onCropped(sensor_msgs::ImageConstPtr roi)
Definition: body.cpp:74
static const ros::Duration BODY_TF_TIMEOUT(0.01)
void init() override
Definition: body.cpp:49
ros::Subscriber roi_subscriber_
Definition: body.h:119
tf2_ros::Buffer * _tf_buffer_ptr
Definition: body.h:132
std::shared_ptr< const Body > BodyConstPtr
Definition: body.h:136
std::string _reference_frame
Definition: body.h:131
Definition: body.h:56
virtual ~Body()
Definition: body.cpp:43
cv::Rect roi() const
If available, returns the 2D region of interest (RoI) of the body.
Definition: body.cpp:69
void onSkeleton(hri_msgs::Skeleton2DConstPtr skeleton)
Definition: body.cpp:84
Definition: base.h:38
ros::Subscriber skeleton_subscriber_
Definition: body.h:127
std::string frame() const
the name of the tf frame that correspond to this body
Definition: body.h:66
boost::optional< geometry_msgs::TransformStamped > transform() const
Returns the (stamped) 3D transform of the body (if available).
Definition: body.cpp:94
ros::Subscriber cropped_subscriber_
Definition: body.h:123
std::string ID
Definition: base.h:40
cv::Mat cropped() const
Returns the body image, cropped from the source image.
Definition: body.cpp:79


libhri
Author(s): Séverin Lemaignan
autogenerated on Wed Apr 19 2023 02:30:41