Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

High Resolution Pose Estimation new tool #356

Merged
merged 42 commits into from
Dec 21, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
42 commits
Select commit Hold shift + click to select a range
46aabce
High Resolution Pose Estimation new tool
mthodoris Nov 28, 2022
3d2612f
changes on path for 1080pi image input
mthodoris Dec 1, 2022
d3756c2
adding height1 height2 as params to learner
mthodoris Dec 2, 2022
9a8fe2b
typos
mthodoris Dec 2, 2022
a0d90e7
fixed tests
mthodoris Dec 2, 2022
e45ba3a
edit Readme files, edit files(PEP8 changes) to pass tests
mthodoris Dec 6, 2022
0ca25e1
Merge branch 'develop' into hr_pose_estimation
tsampazk Dec 6, 2022
37aeb65
Merge branch 'develop' into hr_pose_estimation
tsampazk Dec 7, 2022
95ede8d
Merge branch 'develop' into hr_pose_estimation
tsampazk Dec 8, 2022
49aa849
Merge branch 'develop' into hr_pose_estimation
ad-daniel Dec 11, 2022
0081557
fix formatting
ad-daniel Dec 11, 2022
6ba580c
Apply suggestions from code review
mthodoris Dec 12, 2022
b012f18
Merge branch 'develop' into hr_pose_estimation
tsampazk Dec 12, 2022
8d906b3
Minor fix in comments of original pose estimation node
tsampazk Dec 12, 2022
5334c7e
HR pose estimation ros1 node
tsampazk Dec 12, 2022
7ea8c7a
Apply suggestions from code review
mthodoris Dec 13, 2022
c209bfe
suggestions from review
mthodoris Dec 13, 2022
eec2d90
Merge branch 'hr_pose_estimation' of https://github.com/opendr-eu/ope…
mthodoris Dec 13, 2022
fcadc14
suggestions from review
mthodoris Dec 13, 2022
d3340f5
edit some paths
mthodoris Dec 13, 2022
d6ba595
changes for test errors
mthodoris Dec 13, 2022
aef4d33
Merge branch 'develop' into hr_pose_estimation
tsampazk Dec 15, 2022
e9dabd1
apply suggestions from review
mthodoris Dec 19, 2022
4416a5c
Merge branch 'develop' into hr_pose_estimation
ad-daniel Dec 19, 2022
6b3149a
Merge branch 'develop' into hr_pose_estimation
ad-daniel Dec 20, 2022
2d42b0b
Apply suggestions from code review
mthodoris Dec 20, 2022
15608ee
Missing stuff
ad-daniel Dec 20, 2022
9e4bea8
add a CHANGELOG entry, reference the demo and documentation in index.md
mthodoris Dec 20, 2022
9f77fae
Merge branch 'hr_pose_estimation' of https://github.com/opendr-eu/ope…
mthodoris Dec 20, 2022
0dd322a
Simplified HR pose estimation
passalis Dec 21, 2022
191c3f6
pep8 fixes
passalis Dec 21, 2022
0edfb3b
Merge branch 'develop' into hr_pose_estimation
passalis Dec 21, 2022
3bf439c
Merge branch 'hr_pose_estimation' of https://github.com/opendr-eu/ope…
mthodoris Dec 21, 2022
4ba8ae3
Merge branch 'develop' into hr_pose_estimation
passalis Dec 21, 2022
4234552
Merge branch 'hr_pose_estimation' of https://github.com/opendr-eu/ope…
mthodoris Dec 21, 2022
4a6c7d2
apply review suggestions
mthodoris Dec 21, 2022
664d0bb
Update docs/reference/high-resolution-pose-estimation.md
mthodoris Dec 21, 2022
82313ba
Apply suggestions from code review
mthodoris Dec 21, 2022
bcf222b
Apply suggestions from code review
mthodoris Dec 21, 2022
d6853ad
review fixes
mthodoris Dec 21, 2022
18dff24
typos
mthodoris Dec 21, 2022
27a614d
Merge branch 'develop' into hr_pose_estimation
ad-daniel Dec 21, 2022
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@ Released on December, XX, 2022.
- Added Continual Transformer Encoders ([#317](https://github.com/opendr-eu/opendr/pull/317)).
- Added Continual Spatio-Temporal Graph Convolutional Networks tool ([#370](https://github.com/opendr-eu/opendr/pull/370)).
- Added AmbiguityMeasure utility tool ([#361](https://github.com/opendr-eu/opendr/pull/361)).
- Added SiamRPN 2D tracking tool ([#367](https://github.com/opendr-eu/opendr/pull/367))
- Added SiamRPN 2D tracking tool ([#367](https://github.com/opendr-eu/opendr/pull/367)).
- Added High resolution pose estimation tool ([#356](https://github.com/opendr-eu/opendr/pull/356)).

- Bug Fixes:
- Fixed `BoundingBoxList`, `TrackingAnnotationList`, `BoundingBoxList3D` and `TrackingAnnotationList3D` confidence warnings ([#365](https://github.com/opendr-eu/opendr/pull/365)).
Expand Down
358 changes: 358 additions & 0 deletions docs/reference/high-resolution-pose-estimation.md

Large diffs are not rendered by default.

4 changes: 3 additions & 1 deletion docs/reference/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ Neither the copyright holder nor any applicable licensor will be liable for any
- [landmark_based_facial_expression_recognition](landmark-based-facial-expression-recognition.md)
- pose estimation:
- [lightweight_open_pose Module](lightweight-open-pose.md)
- [high_resolution_pose_estimation Module](high-resolution-pose-estimation.md)
- activity recognition:
- [skeleton-based action recognition](skeleton-based-action-recognition.md)
- [continual skeleton-based action recognition Module](skeleton-based-action-recognition.md#class-costgcnlearner)
Expand Down Expand Up @@ -111,7 +112,8 @@ Neither the copyright holder nor any applicable licensor will be liable for any
- heart anomaly detection:
- [heart anomaly detection Demo](/projects/python/perception/heart_anomaly_detection)
- pose estimation:
- [lightweight_open_pose Demo](/projects/python/perception/lightweight_open_pose)
- [lightweight_open_pose Demo](/projects/python/perception/pose_estimation/lightweight_open_pose)
- [high_resolution_pose_estimation Demo](/projects/python/perception/pose_estimation/high_resolution_pose_estimation)
- multimodal human centric:
- [rgbd_hand_gesture_learner Demo](/projects/python/perception/multimodal_human_centric/rgbd_hand_gesture_recognition)
- [audiovisual_emotion_recognition Demo](/projects/python/perception/multimodal_human_centric/audiovisual_emotion_recognition)
Expand Down
1 change: 1 addition & 0 deletions projects/opendr_ws/src/opendr_perception/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ include_directories(

catkin_install_python(PROGRAMS
scripts/pose_estimation_node.py
scripts/hr_pose_estimation_node.py
scripts/fall_detection_node.py
scripts/object_detection_2d_nanodet_node.py
scripts/object_detection_2d_yolov5_node.py
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,164 @@
#!/usr/bin/env python
# Copyright 2020-2022 OpenDR European Project
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import argparse
import torch

import rospy
from sensor_msgs.msg import Image as ROS_Image
from opendr_bridge.msg import OpenDRPose2D
from opendr_bridge import ROSBridge

from opendr.engine.data import Image
from opendr.perception.pose_estimation import draw
from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner


class PoseEstimationNode:

def __init__(self, input_rgb_image_topic="/usb_cam/image_raw",
output_rgb_image_topic="/opendr/image_pose_annotated", detections_topic="/opendr/poses", device="cuda",
num_refinement_stages=2, use_stride=False, half_precision=False):
"""
Creates a ROS Node for high resolution pose estimation with HR Pose Estimation.
:param input_rgb_image_topic: Topic from which we are reading the input image
:type input_rgb_image_topic: str
:param output_rgb_image_topic: Topic to which we are publishing the annotated image (if None, no annotated
image is published)
:type output_rgb_image_topic: str
:param detections_topic: Topic to which we are publishing the annotations (if None, no pose detection message
is published)
:type detections_topic: str
:param device: device on which we are running inference ('cpu' or 'cuda')
:type device: str
:param num_refinement_stages: Specifies the number of pose estimation refinement stages are added on the
model's head, including the initial stage. Can be 0, 1 or 2, with more stages meaning slower and more accurate
inference
:type num_refinement_stages: int
:param use_stride: Whether to add a stride value in the model, which reduces accuracy but increases
inference speed
:type use_stride: bool
:param half_precision: Enables inference using half (fp16) precision instead of single (fp32) precision.
Valid only for GPU-based inference
:type half_precision: bool
"""
self.input_rgb_image_topic = input_rgb_image_topic

if output_rgb_image_topic is not None:
self.image_publisher = rospy.Publisher(output_rgb_image_topic, ROS_Image, queue_size=1)
else:
self.image_publisher = None

if detections_topic is not None:
self.pose_publisher = rospy.Publisher(detections_topic, OpenDRPose2D, queue_size=1)
else:
self.pose_publisher = None

self.bridge = ROSBridge()

# Initialize the high resolution pose estimation learner
self.pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=num_refinement_stages,
mobilenet_use_stride=use_stride,
half_precision=half_precision)
self.pose_estimator.download(path=".", verbose=True)
self.pose_estimator.load("openpose_default")

def listen(self):
"""
Start the node and begin processing input data.
"""
rospy.init_node('opendr_hr_pose_estimation_node', anonymous=True)
rospy.Subscriber(self.input_rgb_image_topic, ROS_Image, self.callback, queue_size=1, buff_size=10000000)
rospy.loginfo("Pose estimation node started.")
rospy.spin()

def callback(self, data):
"""
Callback that processes the input data and publishes to the corresponding topics.
:param data: Input image message
:type data: sensor_msgs.msg.Image
"""
# Convert sensor_msgs.msg.Image into OpenDR Image
image = self.bridge.from_ros_image(data, encoding='bgr8')

# Run pose estimation
poses = self.pose_estimator.infer(image)

# Publish detections in ROS message
if self.pose_publisher is not None:
for pose in poses:
if pose.id is None: # Temporary fix for pose not having id
pose.id = -1
# Convert OpenDR pose to ROS pose message using bridge and publish it
self.pose_publisher.publish(self.bridge.to_ros_pose(pose))

if self.image_publisher is not None:
# Get an OpenCV image back
image = image.opencv()
# Annotate image with poses
for pose in poses:
draw(image, pose)
# Convert the annotated OpenDR image to ROS image message using bridge and publish it
self.image_publisher.publish(self.bridge.to_ros_image(Image(image), encoding='bgr8'))


def main():
parser = argparse.ArgumentParser()
parser.add_argument("-i", "--input_rgb_image_topic", help="Topic name for input rgb image",
type=str, default="/usb_cam/image_raw")
parser.add_argument("-o", "--output_rgb_image_topic", help="Topic name for output annotated rgb image",
type=lambda value: value if value.lower() != "none" else None,
default="/opendr/image_pose_annotated")
parser.add_argument("-d", "--detections_topic", help="Topic name for detection messages",
type=lambda value: value if value.lower() != "none" else None,
default="/opendr/poses")
parser.add_argument("--device", help="Device to use, either \"cpu\" or \"cuda\", defaults to \"cuda\"",
type=str, default="cuda", choices=["cuda", "cpu"])
parser.add_argument("--accelerate", help="Enables acceleration flags (e.g., stride)", default=False,
action="store_true")
args = parser.parse_args()

try:
if args.device == "cuda" and torch.cuda.is_available():
device = "cuda"
elif args.device == "cuda":
print("GPU not found. Using CPU instead.")
device = "cpu"
else:
print("Using CPU.")
device = "cpu"
except:
print("Using CPU.")
device = "cpu"

if args.accelerate:
stride = True
stages = 0
half_prec = True
else:
stride = False
stages = 2
half_prec = False

pose_estimator_node = PoseEstimationNode(device=device,
input_rgb_image_topic=args.input_rgb_image_topic,
output_rgb_image_topic=args.output_rgb_image_topic,
detections_topic=args.detections_topic,
num_refinement_stages=stages, use_stride=stride, half_precision=half_prec)
pose_estimator_node.listen()


if __name__ == '__main__':
main()
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ def callback(self, data):
# Publish detections in ROS message
if self.pose_publisher is not None:
for pose in poses:
# Convert OpenDR pose to ROS2 pose message using bridge and publish it
# Convert OpenDR pose to ROS pose message using bridge and publish it
self.pose_publisher.publish(self.bridge.to_ros_pose(pose))

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


Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
# High Resolution Pose Estimation

This folder contains sample applications that demonstrate various parts of the functionality provided by the High Resolution Pose Estimation algorithm provided by OpenDR.

More specifically, the applications provided are:

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.
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.
3. demos/benchmarking_demo.py: A simple benchmarking tool for measuring the performance of High Resolution Pose Estimation in various platforms.


Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
# Copyright 2020-2022 OpenDR European Project
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import cv2
import time
from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
import argparse
from os.path import join
from tqdm import tqdm
import numpy as np


if __name__ == '__main__':
parser = argparse.ArgumentParser()
parser.add_argument("--device", help="Device to use (cpu, cuda)", type=str, default="cuda")
parser.add_argument("--accelerate", help="Enables acceleration flags (e.g., stride)", default=False,
action="store_true")
parser.add_argument("--height1", help="Base height of resizing in heatmap generation", default=360)
parser.add_argument("--height2", help="Base height of resizing in second inference", default=540)

args = parser.parse_args()

device, accelerate, base_height1, base_height2 = args.device, args.accelerate,\
args.height1, args.height2

if device == 'cpu':
import torch
torch.set_flush_denormal(True)
torch.set_num_threads(8)

if accelerate:
stride = True
stages = 0
half_precision = True
else:
stride = False
stages = 2
half_precision = False

pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
mobilenet_use_stride=stride, half_precision=half_precision,
first_pass_height=int(base_height1),
second_pass_height=int(base_height2))
pose_estimator.download(path=".", verbose=True)
pose_estimator.load("openpose_default")

# Download one sample image
pose_estimator.download(path=".", mode="test_data")
image_path = join("temp", "dataset", "image", "000000000785_1080.jpg")
img = cv2.imread(image_path)

fps_list = []
print("Benchmarking...")
for i in tqdm(range(50)):
start_time = time.perf_counter()
# Perform inference
poses = pose_estimator.infer(img)

end_time = time.perf_counter()
fps_list.append(1.0 / (end_time - start_time))
print("Average FPS: %.2f" % (np.mean(fps_list)))

# If pynvml is available, try to get memory stats for cuda
try:
if 'cuda' in device:
from pynvml import nvmlInit, nvmlDeviceGetMemoryInfo, nvmlDeviceGetHandleByIndex

nvmlInit()
info = nvmlDeviceGetMemoryInfo(nvmlDeviceGetHandleByIndex(0))
print("Memory allocated: %.2f MB " % (info.used / 1024 ** 2))
except ImportError:
pass
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
# Copyright 2020-2022 OpenDR European Project
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
import argparse
from os.path import join
from opendr.engine.datasets import ExternalDataset
import time


if __name__ == '__main__':
parser = argparse.ArgumentParser()
parser.add_argument("--device", help="Device to use (cpu, cuda)", type=str, default="cuda")
parser.add_argument("--accelerate", help="Enables acceleration flags (e.g., stride)", default=False,
action="store_true")
parser.add_argument("--height1", help="Base height of resizing in first inference", default=360)
parser.add_argument("--height2", help="Base height of resizing in second inference", default=540)

args = parser.parse_args()

device, accelerate, base_height1, base_height2 = args.device, args.accelerate,\
args.height1, args.height2

if accelerate:
stride = True
stages = 0
half_precision = True
else:
stride = True
stages = 2
half_precision = True

pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
mobilenet_use_stride=stride,
half_precision=half_precision,
first_pass_height=int(base_height1),
second_pass_height=int(base_height2))
pose_estimator.download(path=".", verbose=True)
pose_estimator.load("openpose_default")

# Download a sample dataset
pose_estimator.download(path=".", mode="test_data")

eval_dataset = ExternalDataset(path=join("temp", "dataset"), dataset_type="COCO")

t0 = time.time()
results_dict = pose_estimator.eval(eval_dataset, use_subset=False, verbose=True, silent=True,
images_folder_name="image", annotations_filename="annotation.json")
t1 = time.time()
print("\n Evaluation time: ", t1 - t0, "seconds")
print("Evaluation results = ", results_dict)
Loading