Skip to content

Commit bedccdd

Browse files
mthodoristsampazkad-danielpassalis
authored
High Resolution Pose Estimation new tool (opendr-eu#356)
* High Resolution Pose Estimation new tool * changes on path for 1080pi image input * adding height1 height2 as params to learner * typos * fixed tests * edit Readme files, edit files(PEP8 changes) to pass tests * fix formatting * Apply suggestions from code review Co-authored-by: ad-daniel <[email protected]> Co-authored-by: Nikolaos Passalis <[email protected]> * Minor fix in comments of original pose estimation node * HR pose estimation ros1 node * Apply suggestions from code review Co-authored-by: ad-daniel <[email protected]> Co-authored-by: Kostas Tsampazis <[email protected]> * suggestions from review (edit functions, code duplication,typos,etc) * suggestions from review (edit functions, code duplication,typos,etc) * edit some paths * changes for test errors * apply suggestions from review * Apply suggestions from code review type casting issue on height variables str() to int() Co-authored-by: Nikolaos Passalis <[email protected]> * Missing stuff * add a CHANGELOG entry, reference the demo and documentation in index.md * Simplified HR pose estimation * pep8 fixes * apply review suggestions edited hardcoded values, removed unnecessary values from learner, added docstrings in functions edited the readme file after the changes * Update docs/reference/high-resolution-pose-estimation.md Co-authored-by: Nikolaos Passalis <[email protected]> * Apply suggestions from code review Co-authored-by: Kostas Tsampazis <[email protected]> * Apply suggestions from code review Co-authored-by: Kostas Tsampazis <[email protected]> * review fixes * typos Co-authored-by: Kostas Tsampazis <[email protected]> Co-authored-by: ad-daniel <[email protected]> Co-authored-by: ad-daniel <[email protected]> Co-authored-by: Nikolaos Passalis <[email protected]> Co-authored-by: Nikolaos <[email protected]>
1 parent 75bbf30 commit bedccdd

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

59 files changed

+1464
-6
lines changed

CHANGELOG.md

+2-1
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,8 @@ Released on December, XX, 2022.
88
- Added Continual Transformer Encoders ([#317](https://github.com/opendr-eu/opendr/pull/317)).
99
- Added Continual Spatio-Temporal Graph Convolutional Networks tool ([#370](https://github.com/opendr-eu/opendr/pull/370)).
1010
- Added AmbiguityMeasure utility tool ([#361](https://github.com/opendr-eu/opendr/pull/361)).
11-
- Added SiamRPN 2D tracking tool ([#367](https://github.com/opendr-eu/opendr/pull/367))
11+
- Added SiamRPN 2D tracking tool ([#367](https://github.com/opendr-eu/opendr/pull/367)).
12+
- Added High resolution pose estimation tool ([#356](https://github.com/opendr-eu/opendr/pull/356)).
1213

1314
- Bug Fixes:
1415
- Fixed `BoundingBoxList`, `TrackingAnnotationList`, `BoundingBoxList3D` and `TrackingAnnotationList3D` confidence warnings ([#365](https://github.com/opendr-eu/opendr/pull/365)).

docs/reference/high-resolution-pose-estimation.md

+358
Large diffs are not rendered by default.

docs/reference/index.md

+3-1
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@ Neither the copyright holder nor any applicable licensor will be liable for any
3030
- [landmark_based_facial_expression_recognition](landmark-based-facial-expression-recognition.md)
3131
- pose estimation:
3232
- [lightweight_open_pose Module](lightweight-open-pose.md)
33+
- [high_resolution_pose_estimation Module](high-resolution-pose-estimation.md)
3334
- activity recognition:
3435
- [skeleton-based action recognition](skeleton-based-action-recognition.md)
3536
- [continual skeleton-based action recognition Module](skeleton-based-action-recognition.md#class-costgcnlearner)
@@ -111,7 +112,8 @@ Neither the copyright holder nor any applicable licensor will be liable for any
111112
- heart anomaly detection:
112113
- [heart anomaly detection Demo](/projects/python/perception/heart_anomaly_detection)
113114
- pose estimation:
114-
- [lightweight_open_pose Demo](/projects/python/perception/lightweight_open_pose)
115+
- [lightweight_open_pose Demo](/projects/python/perception/pose_estimation/lightweight_open_pose)
116+
- [high_resolution_pose_estimation Demo](/projects/python/perception/pose_estimation/high_resolution_pose_estimation)
115117
- multimodal human centric:
116118
- [rgbd_hand_gesture_learner Demo](/projects/python/perception/multimodal_human_centric/rgbd_hand_gesture_recognition)
117119
- [audiovisual_emotion_recognition Demo](/projects/python/perception/multimodal_human_centric/audiovisual_emotion_recognition)

projects/opendr_ws/src/opendr_perception/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ include_directories(
2929

3030
catkin_install_python(PROGRAMS
3131
scripts/pose_estimation_node.py
32+
scripts/hr_pose_estimation_node.py
3233
scripts/fall_detection_node.py
3334
scripts/object_detection_2d_nanodet_node.py
3435
scripts/object_detection_2d_yolov5_node.py
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,164 @@
1+
#!/usr/bin/env python
2+
# Copyright 2020-2022 OpenDR European Project
3+
#
4+
# Licensed under the Apache License, Version 2.0 (the "License");
5+
# you may not use this file except in compliance with the License.
6+
# You may obtain a copy of the License at
7+
#
8+
# http://www.apache.org/licenses/LICENSE-2.0
9+
#
10+
# Unless required by applicable law or agreed to in writing, software
11+
# distributed under the License is distributed on an "AS IS" BASIS,
12+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
# See the License for the specific language governing permissions and
14+
# limitations under the License.
15+
16+
import argparse
17+
import torch
18+
19+
import rospy
20+
from sensor_msgs.msg import Image as ROS_Image
21+
from opendr_bridge.msg import OpenDRPose2D
22+
from opendr_bridge import ROSBridge
23+
24+
from opendr.engine.data import Image
25+
from opendr.perception.pose_estimation import draw
26+
from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
27+
28+
29+
class PoseEstimationNode:
30+
31+
def __init__(self, input_rgb_image_topic="/usb_cam/image_raw",
32+
output_rgb_image_topic="/opendr/image_pose_annotated", detections_topic="/opendr/poses", device="cuda",
33+
num_refinement_stages=2, use_stride=False, half_precision=False):
34+
"""
35+
Creates a ROS Node for high resolution pose estimation with HR Pose Estimation.
36+
:param input_rgb_image_topic: Topic from which we are reading the input image
37+
:type input_rgb_image_topic: str
38+
:param output_rgb_image_topic: Topic to which we are publishing the annotated image (if None, no annotated
39+
image is published)
40+
:type output_rgb_image_topic: str
41+
:param detections_topic: Topic to which we are publishing the annotations (if None, no pose detection message
42+
is published)
43+
:type detections_topic: str
44+
:param device: device on which we are running inference ('cpu' or 'cuda')
45+
:type device: str
46+
:param num_refinement_stages: Specifies the number of pose estimation refinement stages are added on the
47+
model's head, including the initial stage. Can be 0, 1 or 2, with more stages meaning slower and more accurate
48+
inference
49+
:type num_refinement_stages: int
50+
:param use_stride: Whether to add a stride value in the model, which reduces accuracy but increases
51+
inference speed
52+
:type use_stride: bool
53+
:param half_precision: Enables inference using half (fp16) precision instead of single (fp32) precision.
54+
Valid only for GPU-based inference
55+
:type half_precision: bool
56+
"""
57+
self.input_rgb_image_topic = input_rgb_image_topic
58+
59+
if output_rgb_image_topic is not None:
60+
self.image_publisher = rospy.Publisher(output_rgb_image_topic, ROS_Image, queue_size=1)
61+
else:
62+
self.image_publisher = None
63+
64+
if detections_topic is not None:
65+
self.pose_publisher = rospy.Publisher(detections_topic, OpenDRPose2D, queue_size=1)
66+
else:
67+
self.pose_publisher = None
68+
69+
self.bridge = ROSBridge()
70+
71+
# Initialize the high resolution pose estimation learner
72+
self.pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=num_refinement_stages,
73+
mobilenet_use_stride=use_stride,
74+
half_precision=half_precision)
75+
self.pose_estimator.download(path=".", verbose=True)
76+
self.pose_estimator.load("openpose_default")
77+
78+
def listen(self):
79+
"""
80+
Start the node and begin processing input data.
81+
"""
82+
rospy.init_node('opendr_hr_pose_estimation_node', anonymous=True)
83+
rospy.Subscriber(self.input_rgb_image_topic, ROS_Image, self.callback, queue_size=1, buff_size=10000000)
84+
rospy.loginfo("Pose estimation node started.")
85+
rospy.spin()
86+
87+
def callback(self, data):
88+
"""
89+
Callback that processes the input data and publishes to the corresponding topics.
90+
:param data: Input image message
91+
:type data: sensor_msgs.msg.Image
92+
"""
93+
# Convert sensor_msgs.msg.Image into OpenDR Image
94+
image = self.bridge.from_ros_image(data, encoding='bgr8')
95+
96+
# Run pose estimation
97+
poses = self.pose_estimator.infer(image)
98+
99+
# Publish detections in ROS message
100+
if self.pose_publisher is not None:
101+
for pose in poses:
102+
if pose.id is None: # Temporary fix for pose not having id
103+
pose.id = -1
104+
# Convert OpenDR pose to ROS pose message using bridge and publish it
105+
self.pose_publisher.publish(self.bridge.to_ros_pose(pose))
106+
107+
if self.image_publisher is not None:
108+
# Get an OpenCV image back
109+
image = image.opencv()
110+
# Annotate image with poses
111+
for pose in poses:
112+
draw(image, pose)
113+
# Convert the annotated OpenDR image to ROS image message using bridge and publish it
114+
self.image_publisher.publish(self.bridge.to_ros_image(Image(image), encoding='bgr8'))
115+
116+
117+
def main():
118+
parser = argparse.ArgumentParser()
119+
parser.add_argument("-i", "--input_rgb_image_topic", help="Topic name for input rgb image",
120+
type=str, default="/usb_cam/image_raw")
121+
parser.add_argument("-o", "--output_rgb_image_topic", help="Topic name for output annotated rgb image",
122+
type=lambda value: value if value.lower() != "none" else None,
123+
default="/opendr/image_pose_annotated")
124+
parser.add_argument("-d", "--detections_topic", help="Topic name for detection messages",
125+
type=lambda value: value if value.lower() != "none" else None,
126+
default="/opendr/poses")
127+
parser.add_argument("--device", help="Device to use, either \"cpu\" or \"cuda\", defaults to \"cuda\"",
128+
type=str, default="cuda", choices=["cuda", "cpu"])
129+
parser.add_argument("--accelerate", help="Enables acceleration flags (e.g., stride)", default=False,
130+
action="store_true")
131+
args = parser.parse_args()
132+
133+
try:
134+
if args.device == "cuda" and torch.cuda.is_available():
135+
device = "cuda"
136+
elif args.device == "cuda":
137+
print("GPU not found. Using CPU instead.")
138+
device = "cpu"
139+
else:
140+
print("Using CPU.")
141+
device = "cpu"
142+
except:
143+
print("Using CPU.")
144+
device = "cpu"
145+
146+
if args.accelerate:
147+
stride = True
148+
stages = 0
149+
half_prec = True
150+
else:
151+
stride = False
152+
stages = 2
153+
half_prec = False
154+
155+
pose_estimator_node = PoseEstimationNode(device=device,
156+
input_rgb_image_topic=args.input_rgb_image_topic,
157+
output_rgb_image_topic=args.output_rgb_image_topic,
158+
detections_topic=args.detections_topic,
159+
num_refinement_stages=stages, use_stride=stride, half_precision=half_prec)
160+
pose_estimator_node.listen()
161+
162+
163+
if __name__ == '__main__':
164+
main()

projects/opendr_ws/src/opendr_perception/scripts/pose_estimation_node.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@ def callback(self, data):
9999
# Publish detections in ROS message
100100
if self.pose_publisher is not None:
101101
for pose in poses:
102-
# Convert OpenDR pose to ROS2 pose message using bridge and publish it
102+
# Convert OpenDR pose to ROS pose message using bridge and publish it
103103
self.pose_publisher.publish(self.bridge.to_ros_pose(pose))
104104

105105
if self.image_publisher is not None:
@@ -108,7 +108,7 @@ def callback(self, data):
108108
# Annotate image with poses
109109
for pose in poses:
110110
draw(image, pose)
111-
# Convert the annotated OpenDR image to ROS2 image message using bridge and publish it
111+
# Convert the annotated OpenDR image to ROS image message using bridge and publish it
112112
self.image_publisher.publish(self.bridge.to_ros_image(Image(image), encoding='bgr8'))
113113

114114

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
# High Resolution Pose Estimation
2+
3+
This folder contains sample applications that demonstrate various parts of the functionality provided by the High Resolution Pose Estimation algorithm provided by OpenDR.
4+
5+
More specifically, the applications provided are:
6+
7+
1. demos/inference_demo.py: A tool that demonstrates how to perform inference on a single high resolution image and then draw the detected poses.
8+
2. demos/eval_demo.py: A tool that demonstrates how to perform evaluation using the High Resolution Pose Estimation algorithm on 720p, 1080p and 1440p datasets.
9+
3. demos/benchmarking_demo.py: A simple benchmarking tool for measuring the performance of High Resolution Pose Estimation in various platforms.
10+
11+
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,83 @@
1+
# Copyright 2020-2022 OpenDR European Project
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import cv2
16+
import time
17+
from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
18+
import argparse
19+
from os.path import join
20+
from tqdm import tqdm
21+
import numpy as np
22+
23+
24+
if __name__ == '__main__':
25+
parser = argparse.ArgumentParser()
26+
parser.add_argument("--device", help="Device to use (cpu, cuda)", type=str, default="cuda")
27+
parser.add_argument("--accelerate", help="Enables acceleration flags (e.g., stride)", default=False,
28+
action="store_true")
29+
parser.add_argument("--height1", help="Base height of resizing in heatmap generation", default=360)
30+
parser.add_argument("--height2", help="Base height of resizing in second inference", default=540)
31+
32+
args = parser.parse_args()
33+
34+
device, accelerate, base_height1, base_height2 = args.device, args.accelerate,\
35+
args.height1, args.height2
36+
37+
if device == 'cpu':
38+
import torch
39+
torch.set_flush_denormal(True)
40+
torch.set_num_threads(8)
41+
42+
if accelerate:
43+
stride = True
44+
stages = 0
45+
half_precision = True
46+
else:
47+
stride = False
48+
stages = 2
49+
half_precision = False
50+
51+
pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
52+
mobilenet_use_stride=stride, half_precision=half_precision,
53+
first_pass_height=int(base_height1),
54+
second_pass_height=int(base_height2))
55+
pose_estimator.download(path=".", verbose=True)
56+
pose_estimator.load("openpose_default")
57+
58+
# Download one sample image
59+
pose_estimator.download(path=".", mode="test_data")
60+
image_path = join("temp", "dataset", "image", "000000000785_1080.jpg")
61+
img = cv2.imread(image_path)
62+
63+
fps_list = []
64+
print("Benchmarking...")
65+
for i in tqdm(range(50)):
66+
start_time = time.perf_counter()
67+
# Perform inference
68+
poses = pose_estimator.infer(img)
69+
70+
end_time = time.perf_counter()
71+
fps_list.append(1.0 / (end_time - start_time))
72+
print("Average FPS: %.2f" % (np.mean(fps_list)))
73+
74+
# If pynvml is available, try to get memory stats for cuda
75+
try:
76+
if 'cuda' in device:
77+
from pynvml import nvmlInit, nvmlDeviceGetMemoryInfo, nvmlDeviceGetHandleByIndex
78+
79+
nvmlInit()
80+
info = nvmlDeviceGetMemoryInfo(nvmlDeviceGetHandleByIndex(0))
81+
print("Memory allocated: %.2f MB " % (info.used / 1024 ** 2))
82+
except ImportError:
83+
pass
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,62 @@
1+
# Copyright 2020-2022 OpenDR European Project
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
16+
import argparse
17+
from os.path import join
18+
from opendr.engine.datasets import ExternalDataset
19+
import time
20+
21+
22+
if __name__ == '__main__':
23+
parser = argparse.ArgumentParser()
24+
parser.add_argument("--device", help="Device to use (cpu, cuda)", type=str, default="cuda")
25+
parser.add_argument("--accelerate", help="Enables acceleration flags (e.g., stride)", default=False,
26+
action="store_true")
27+
parser.add_argument("--height1", help="Base height of resizing in first inference", default=360)
28+
parser.add_argument("--height2", help="Base height of resizing in second inference", default=540)
29+
30+
args = parser.parse_args()
31+
32+
device, accelerate, base_height1, base_height2 = args.device, args.accelerate,\
33+
args.height1, args.height2
34+
35+
if accelerate:
36+
stride = True
37+
stages = 0
38+
half_precision = True
39+
else:
40+
stride = True
41+
stages = 2
42+
half_precision = True
43+
44+
pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
45+
mobilenet_use_stride=stride,
46+
half_precision=half_precision,
47+
first_pass_height=int(base_height1),
48+
second_pass_height=int(base_height2))
49+
pose_estimator.download(path=".", verbose=True)
50+
pose_estimator.load("openpose_default")
51+
52+
# Download a sample dataset
53+
pose_estimator.download(path=".", mode="test_data")
54+
55+
eval_dataset = ExternalDataset(path=join("temp", "dataset"), dataset_type="COCO")
56+
57+
t0 = time.time()
58+
results_dict = pose_estimator.eval(eval_dataset, use_subset=False, verbose=True, silent=True,
59+
images_folder_name="image", annotations_filename="annotation.json")
60+
t1 = time.time()
61+
print("\n Evaluation time: ", t1 - t0, "seconds")
62+
print("Evaluation results = ", results_dict)

0 commit comments

Comments
 (0)