-
Notifications
You must be signed in to change notification settings - Fork 95
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
High Resolution Pose Estimation new tool (#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]>
- Loading branch information
1 parent
75bbf30
commit bedccdd
Showing
59 changed files
with
1,464 additions
and
6 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Large diffs are not rendered by default.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
164 changes: 164 additions & 0 deletions
164
projects/opendr_ws/src/opendr_perception/scripts/hr_pose_estimation_node.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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() |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
11 changes: 11 additions & 0 deletions
11
...cts/python/perception/pose_estimation/high_resolution_pose_estimation/README.md
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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. | ||
|
||
|
83 changes: 83 additions & 0 deletions
83
...hon/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
62 changes: 62 additions & 0 deletions
62
...ects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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) |
Oops, something went wrong.