From 46aabceda8a838e89f7f3b5b7c259caa1a20d042 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Mon, 28 Nov 2022 12:20:31 +0200
Subject: [PATCH 01/27] High Resolution Pose Estimation new tool

---
 .../high_resolution_pose_estimation.md        | 388 +++++++
 .../high_resolution_pose_estimation/README.md |  11 +
 .../demos/benchmarking_demo.py                |  85 ++
 .../demos/eval_demo.py                        |  60 ++
 .../demos/inference_demo.py                   |  65 ++
 .../perception/pose_estimation/__init__.py    |   4 +-
 .../HighResolutionLearner.py                  | 967 ++++++++++++++++++
 .../hr_pose_estimation/README.md              |  11 +
 .../hr_pose_estimation/__init__.py            |   0
 .../hr_pose_estimation/algorithm/README.md    |  44 +
 .../hr_pose_estimation/algorithm/__init__.py  |   0
 .../algorithm/datasets/__init__.py            |   0
 .../algorithm/datasets/coco.py                | 180 ++++
 .../algorithm/datasets/transformations.py     | 249 +++++
 .../algorithm/models/__init__.py              |   0
 .../algorithm/models/with_mobilenet.py        | 126 +++
 .../algorithm/models/with_mobilenet_v2.py     | 252 +++++
 .../algorithm/models/with_shufflenet.py       | 422 ++++++++
 .../algorithm/modules/__init__.py             |   0
 .../algorithm/modules/conv.py                 |  32 +
 .../algorithm/modules/get_parameters.py       |  21 +
 .../algorithm/modules/keypoints.py            | 159 +++
 .../algorithm/modules/load_state.py           |  35 +
 .../algorithm/modules/loss.py                 |   5 +
 .../algorithm/modules/one_euro_filter.py      |  51 +
 .../algorithm/scripts/__init__.py             |   0
 .../algorithm/scripts/make_val_subset.py      |  43 +
 .../algorithm/scripts/prepare_train_labels.py | 122 +++
 .../hr_pose_estimation/algorithm/val.py       | 161 +++
 .../hr_pose_estimation/filtered_pose.py       |  22 +
 .../hr_pose_estimation/utilities.py           | 153 +++
 31 files changed, 3667 insertions(+), 1 deletion(-)
 create mode 100644 docs/reference/high_resolution_pose_estimation.md
 create mode 100644 projects/python/perception/high_resolution_pose_estimation/README.md
 create mode 100644 projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
 create mode 100644 projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
 create mode 100644 projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/README.md
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/__init__.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/__init__.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/__init__.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/coco.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/transformations.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/__init__.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet_v2.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_shufflenet.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/__init__.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/conv.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/get_parameters.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/keypoints.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/load_state.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/loss.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/one_euro_filter.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/__init__.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/make_val_subset.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/prepare_train_labels.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/val.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/filtered_pose.py
 create mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/utilities.py

diff --git a/docs/reference/high_resolution_pose_estimation.md b/docs/reference/high_resolution_pose_estimation.md
new file mode 100644
index 0000000000..00c21cc9ef
--- /dev/null
+++ b/docs/reference/high_resolution_pose_estimation.md
@@ -0,0 +1,388 @@
+## high_resolution_pose_estimation module
+
+The *high_resolution_pose_estimation* module contains the *HighResolutionPoseEstimationLearner* class, which inherits from the abstract class *Learner*.
+
+### Class HighResolutionPoseEstimationLearner
+Bases: `engine.learners.Learner`
+
+The *HighResolutionLightweightOpenPose* class is an implementation for pose estimation in high resolution images. This method is creating a heatmap of a resized version of the input image. Using this heatmap, the input image is being cropped keeping the area of interest and then it isused for pose estimation. The pose estimation is based on the Lightweight OpenPose algorithm. 
+In this method there are two important variables which are responsible for the increase in speed and in accuracy in high resolution images. These variables are the *first_pass_height* and the *second height* that the image is resized in this procedure.
+
+The [HighResolutionPoseEstiamtionLearner](/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py) class has the
+following public methods:
+
+#### `HighResolutionPoseEstimationLearner` constructor
+```python
+HighResolutionPoseEstimationLearner(self,device, backbone, temp_path, mobilenet_use_stride, mobilenetv2_width, shufflenet_groups, num_refinement_stages, batches_per_iter, experiment_name, num_workers, weights_only, output_name, multiscale, scales, visualize,  img_mean, img_scale, pad_value)
+```
+
+Constructor parameters:
+
+- **device**: *{'cpu', 'cuda'}, default='cuda'*\
+  Specifies the device to be used.
+- **backbone**: *{'mobilenet, 'mobilenetv2', 'shufflenet'}, default='mobilenet'*\
+    Specifies the backbone architecture.
+- **temp_path**: *str, default='temp'*\
+  Specifies a path where the algorithm looks for pretrained backbone weights, the checkpoints are saved along with the logging files. Moreover the JSON file that contains the evaluation detections is saved here.
+- **mobilenet_use_stride**: *bool, default=True*\
+  Whether to add an additional stride value in the mobilenet model, which reduces accuracy but increases inference speed.
+- **mobilenetv2_width**: *[0.0 - 1.0], default=1.0*\
+  If the mobilenetv2 backbone is used, this parameter specified its size.
+- **shufflenet_groups**: *int, default=3*\
+  If the shufflenet backbone is used, it specifies the number of groups to be used in grouped 1x1 convolutions in each ShuffleUnit.
+- **num_refinement_stages**: *int, default=2*\
+  Specifies the number of pose estimation refinement stages are added on the model's head, including the initial stage.
+- **batches_per_iter**: *int, default=1*\
+  Specifies per how many batches a backward optimizer step is performed.
+- **base_height**: *int, default=256*\
+  Specifies the height, based on which the images will be resized before performing the forward pass when using the Lightweight OpenPose.
+- **experiment_name**: *str, default='default'*\
+  String name to attach to checkpoints.
+- **num_workers**: *int, default=8*\
+  Specifies the number of workers to be used by the data loader.
+- **weights_only**: *bool, default=True*\
+  If True, only the model weights will be loaded; it won't load optimizer, scheduler, num_iter, current_epoch information.
+- **output_name**: *str, default='detections.json'*\
+  The name of the json files where the evaluation detections are stored, inside the temp_path.
+- **multiscale**: *bool, default=False*\
+  Specifies whether evaluation will run in the predefined multiple scales setup or not. It overwrites self.scales to [0.5, 1.0, 1.5, 2.0].
+- **scales**: *list, default=None*\
+  A list of integer scales that define the multiscale evaluation setup. Used to manually set the scales instead of going for the predefined multiscale setup.
+- **visualize**: *bool, default=False*\
+  Specifies whether the images along with the poses will be shown, one by one during evaluation.
+
+- **img_mean**: *list, default=(128, 128, 128)]*\
+  Specifies the mean based on which the images are normalized.
+- **img_scale**: *float, default=1/256*\
+  Specifies the scale based on which the images are normalized.
+- **pad_value**: *list, default=(0, 0, 0)*\
+  Specifies the pad value based on which the images' width is padded.
+- **half_precision**: *bool, default=False*\
+  Enables inference using half (fp16) precision instead of single (fp32) precision. Valid only for GPU-based inference.
+
+
+
+#### `LightweightOpenPoseLearner.eval`
+```python
+HighResolutionPoseEstimationLearner.eval(self, dataset, first_pass_height, second_pass_height, silent, verbose, use_subset, subset_size, images_folder_name, annotations_filename)
+```
+
+This method is used to evaluate a trained model on an evaluation dataset.
+Returns a dictionary containing stats regarding evaluation.
+
+Parameters:
+
+- **dataset**: *object*\
+  Object that holds the evaluation dataset.
+  Can be of type `ExternalDataset` or a custom dataset inheriting from `DatasetIterator`.
+- **first_pass_height**: *int*\
+    It is the height that the input image is resized during the heatmap generation procedure.
+- **second_pass_height**: *int*\
+    It is the base height that is used for resizing on the pose estimation procedure.
+- **silent**: *bool, default=False*\
+  If set to True, disables all printing of evaluation progress reports and other information to STDOUT.
+- **verbose**: *bool, default=True*\
+  If set to True, enables the maximum verbosity.
+- **val_subset**: *bool, default=True*\
+  If set to True, a subset of the validation dataset is created and used in evaluation.
+- **subset_size**: *int, default=250*\
+  Controls the size of the validation subset.
+- **images_folder_name**: *str, default='val2017'*\
+  Folder name that contains the dataset images.
+  This folder should be contained in the dataset path provided.
+  Note that this is a folder name, not a path.
+- **annotations_filename**: *str, default='person_keypoints_val2017.json'*\
+  Filename of the annotations JSON file.
+  This file should be contained in the dataset path provided.
+
+#### `HighResolutionPoseEstimation.infer`
+```python
+HighResolutionPoseEstimation.infer(img, fisrt_pass_height, second_pass_height, upsample_ratio, track, smooth)
+```
+
+This method is used to perform pose estimation on an image.
+Returns a list of `engine.target.Pose` objects, where each holds a pose, or returns an empty list if no detection were made.
+
+Parameters:
+
+- **img**: *object***\
+  Object of type engine.data.Image.
+- **first_height**: *int*\
+    It is the height that the input image is resized during the heatmap generation procedure.
+- **second height**: *int*\
+    It is the base height that is used for resizing on the pose estimation procedure.
+- **upsample_ratio**: *int, default=4*\
+  Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing.
+- **track**: *bool, default=True*\
+  If True, infer propagates poses ids from previous frame results to track poses.
+- **smooth**: *bool, default=True*\
+  If True, smoothing is performed on pose keypoints between frames.
+
+
+#### `LightweightOpenPoseLearner.first_pass`
+```python
+HighResolutionPoseEstimationLearner.first_pass(self, net,img)
+```
+This method is used for extracting from the input image a heatmap about human locations in the picture.
+
+Parameters:
+- **img**: *object***\
+  Object of type engine.data.Image.
+- **net**: *object*\
+  The model that is used for creating the heatmap.
+
+#### `LightweightOpenPoseLearner.second_pass`
+```python
+HighResolutionPoseEstimationLearner.second_pass_infer(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, device,
+                          pad_value=(0, 0, 0),
+                          img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256))
+```
+On this method it is carried out the second inference step which estimates the human poses on the image that is inserted. Following the steps of the proposed method this image should be the cropped part of the initial high resolution image that came out from taking into account the area of interest of heatmap generation.
+
+Parameters:
+- **net**: *object*\
+  The model that is used for creating the heatmap.
+- **img**: *object***\
+  Object of type engine.data.Image.
+- **net_input_height_size**: *int*\
+    It is the height that is used for resizing the image on the pose estimation procedure.
+- **max_width**: *int*\
+   It is the max width that the cropped image should have in order to keep the height-width ratio below a certain value.
+- **stride**: *int*\
+   Is the stride value of mobilenet which reduces accuracy but increases inference speed.
+- **upsample_ratio**: *int, default=4*\
+  Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing.
+
+- **device**: *{'cpu', 'cuda'}, default='cuda'*\
+  Specifies the device to be used.
+- **pad_value**: *list, default=(0, 0, 0)*\
+  Specifies the pad value based on which the images' width is padded.
+- **img_mean**: *list, default=(128, 128, 128)]*\
+  Specifies the mean based on which the images are normalized.
+- **img_scale**: *float, default=1/256*\
+  Specifies the scale based on which the images are normalized.
+
+#### `HighResolutionPoseEstimation.Pooling`
+```python
+HighResolutionPoseEstimation.Pooling(self, img, kernel)
+```
+Parameters:
+- **img**: *object***\
+  Object of type engine.data.Image.
+- **kernel**: *int*\
+  The size of kernel in Average Pooling procedure before heatmap generation in order to resize the input image.
+
+#### `HighResolutionPoseEstimation.infer_light_odr()`
+```python
+HighResolutionPoseEstimation.infer_light_odr(self, img, upsample_ratio=4, track=True, smooth=True)
+```
+This method is an inference function of OpenDR LightWeight OpenPose pose estiamtion.
+
+Parameters:
+
+- **img**: *object***\
+  Object of type engine.data.Image.
+- **upsample_ratio**: *int, default=4*\
+  Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing.
+- **track**: *bool, default=True*\
+  If True, infer propagates poses ids from previous frame results to track poses.
+- **smooth**: *bool, default=True*\
+  If True, smoothing is performed on pose keypoints between frames.
+
+#### `HighResolutionPoseEstiamtion.save`
+```python
+HighResolutionPoseEstimation.save(self, path, verbose)
+```
+
+This method is used to save a trained model.
+Provided with the path "/my/path/name" (absolute or relative), it creates the "name" directory, if it does not already
+exist. Inside this folder, the model is saved as "name.pth" and the metadata file as "name.json". If the directory
+already exists, the "name.pth" and "name.json" files are overwritten.
+
+
+
+Parameters:
+
+- **path**: *str*\
+  Path to save the model, including the filename.
+- **verbose**: *bool, default=False*\
+  If set to True, prints a message on success.
+
+#### `HighResolutionPoseEstimation.load`
+```python
+HighResolutionPoseEstimation.load(self, path, verbose)
+```
+
+This method is used to load a previously saved model from its saved folder.
+Loads the model from inside the directory of the path provided, using the metadata .json file included.
+
+Parameters:
+
+- **path**: *str*\
+  Path of the model to be loaded.
+- **verbose**: *bool, default=False*\
+  If set to True, prints a message on success.
+
+#### `HighResolutionPoseEstimation.download`
+```python
+HighResolutionPoseEstimation.download(self, path, mode, verbose, url)
+```
+
+Download utility for various Lightweight Open Pose components. Downloads files depending on mode and
+saves them in the path provided. It supports downloading:
+1. the default mobilenet pretrained model
+2. mobilenet, mobilenetv2 and shufflenet weights needed for training
+3. a test dataset with a single COCO image and its annotation
+
+Parameters:
+
+- **path**: *str, default=None*\
+  Local path to save the files, defaults to self.temp_path if None.
+- **mode**: *str, default="pretrained"*\
+  What file to download, can be one of "pretrained", "weights", "test_data"
+- **verbose**: *bool, default=False*\
+  Whether to print messages in the console.
+- **url**: *str, default=OpenDR FTP URL*\
+  URL of the FTP server.
+
+
+#### Examples
+
+* **Inference and result drawing example on a test .jpg image using OpenCV.**
+  ```python
+  import cv2
+  from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
+  from opendr.perception.pose_estimation import draw
+  from opendr.engine.data import Image
+  
+
+  pose_estimator = HighResolutionPoseEstimationLearner(device="cuda", temp_path='./parent_dir')
+  pose_estimator.download()  # Download the default pretrained mobilenet model in the temp_path
+  pose_estimator.load("./parent_dir/mobilenet_openpose")
+  pose_estimator.download(mode="test_data")  # Download a test data taken from COCO2017
+  
+  first_pass_height = 360
+  second_pass_height = 540
+   
+  img = Image.open('./parent_dir/dataset/image/000000000785_1080.jpg')
+  orig_img = img.opencv()  # Keep original image
+  current_poses = pose_estimator.infer(img,  first_pass_height, second_pass_height)
+  img_opencv = img.opencv()
+  for pose in current_poses:
+      draw(img_opencv, pose)
+  img_opencv = cv2.addWeighted(orig_img, 0.6, img_opencv, 0.4, 0)
+  cv2.imshow('Result', img_opencv)
+  cv2.waitKey(0)
+  ```
+
+
+#### Performance Evaluation
+
+
+In order to check the performance of the *HighResolutionPoseEstimationLearner* it had been tested on various platforms and with different optimizations that Lightweight OpenPose offers.
+The experiments are conducted on a 1080p image.
+#### Lightweight OpenPose With resizing on 256 pixels
+|                    **Method**                    | **CPU i7-9700K (FPS)** | **RTX 2070 (FPS)** | **Jetson TX2 (FPS)** | **Xavier NX (FPS)** |
+|:------------------------------------------------:|-----------------------|-------------------|----------------------|---------------------|
+|                OpenDR - Baseline                 | 0.9                   | 46.3              | 4.6                  | 6.4                 |
+|                  OpenDR - Full                   | 2.9                   | 83.1              | 11.2                 | 13.5                |
+
+
+#### Lightweght OpenPoseWithout resizing
+| Method            | CPU i7-9700K (FPS) | RTX 2070  (FPS) | Jetson TX2 (FPS) | Xavier NX (FPS) |
+|-------------------|--------------------|-----------------|------------------|-----------------|
+| OpenDR - Baseline | 0.05               | 2.6             | 0.3              | 0.5             |
+| OpenDR - Full     | 0.2                | 10.8            | 1.4              | 3.1             |
+
+#### High-Resolution Pose Estimation
+| Method                 | CPU i7-9700K (FPS) | RTX 2070 (FPS) | Jetson TX2 (FPS) | Xavier NX (FPS) |
+|------------------------|--------------------|----------------|------------------|-----------------|
+| HRPoseEstim - Baseline | 2.3                | 13.6           | 1.4              | 1.8             |
+| HRPoseEstim - Half     | 2.7                | 16.1           | 1.3              | 3.0             |
+| HRPoseEstim - Stride   | 8.1                | 27.0           | 4                | 4.9             |
+| HRPoseEstim - Stages   | 3.7                | 16.5           | 1.9              | 2.7             |
+| HRPoseEstim - H+S      | 8.2                | 25.9           | 3.6              | 5.5             |
+| HRPoseEstim - Full     | 10.9               | 31.7           | 4.8              | 6.9             |
+
+
+As it is shown in the previous Table, OpenDr Lightweight OpenPose achieves higher FPS when it is resing the input image into 256 pixels. It is easier to process that image but as it is shown in the next tables the method falls apart when it comes to accuracy and there are no detections.
+
+We have evaluated the effect of using different inference settings, namely:
+- *HRPoseEstim - Baseline*, which refers to directly using the High Resolution Pose Estimation method,which is based in Lightweight OpenPose,
+- *HRPoseEstim - Half*, which refers to enabling inference in half (FP) precision,
+- *HRPoseEstim - Stride*, which refers to increasing stride by two in the input layer of the model,
+- *HRPoseEstim - Stages*, which refers to removing the refinement stages,
+- *HRPoseEstim - H+S*, which uses both half precision and increased stride, and
+- *HRPoseEstim - Full*, which refers to combining all three available optimization.
+was used as input to the models. 
+
+The average precision and average recall on the COCO evaluation split is also reported in the Table below:
+#### Lightweight OpenPose
+| Method            | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) | Evaluation time (sec) |
+|-------------------|------------------------------|---------------------------|-----------------------|
+| OpenDR - Baseline | 0.0                          | 0.0                       | 6558                  |
+
+
+#### High Resolution Pose Estimation
+| Method                 | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) | Evaluation Time (sec) |
+|------------------------|------------------------------|---------------------------|-----------------------|
+| HRPoseEstim - Baseline | 0.615                        | 0.637                     | 288                   |
+| HRPoseEstim - Half     | 0.604                        | 0.621                     | 269                   |
+| HRPoseEstim - Stride   | 0.262                        | 0.274                     | 160                   |
+| HRPoseEstim - Stages   | 0.539                        | 0.562                     | 238                   |
+| HRPoseEstim - H+S      | 0.254                        | 0.267                     | 165                   |
+| HRPoseEstim - Full     | 0.259                        | 0.272                     | 145                   |
+
+
+
+The average precision and the average recall have been calculated on a 1080p version of COCO2017 validation dataset and the results are reported in the table below:
+
+| Method | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) |
+|-------------------|------------------------------|---------------------------|
+| HRPoseEstim - Baseline | 0.518                        | 0.536                     |
+| HRPoseEstim - Half     | 0.509                        | 0.520                     |
+| HRPoseEstim - Stride   | 0.143                        | 0.149                     |
+| HRPoseEstim - Stages   | 0.474                        | 0.496                     |
+| HRPoseEstim - H+S      | 0.134                        | 0.139                     |
+| HRPoseEstim - Full     | 0.141                        | 0.150                     |
+
+For measuring the precision and recall we used the standard approach proposed for COCO, using an Intersection of Union (IoU) metric at 0.5. 
+
+
+#### Notes
+
+For the metrics of the algorithm the COCO dataset evaluation scores are used as explained [here](
+https://cocodataset.org/#keypoints-eval).
+
+Keypoints and how poses are constructed is according to the original method described [here](
+https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch/blob/master/TRAIN-ON-CUSTOM-DATASET.md).
+
+Pose keypoints ids are matched as:
+
+| Keypoint ID 	| Keypoint name  	| Keypoint abbrev. 	|
+|-------------	|----------------	|------------------	|
+| 0           	| nose           	| nose             	|
+| 1           	| neck           	| neck             	|
+| 2           	| right shoulder 	| r_sho            	|
+| 3           	| right elbow    	| r_elb            	|
+| 4           	| right wrist    	| r_wri            	|
+| 5           	| left shoulder  	| l_sho            	|
+| 6           	| left elbow     	| l_elb            	|
+| 7           	| left wrist     	| l_wri            	|
+| 8           	| right hip      	| r_hip            	|
+| 9           	| right knee     	| r_knee           	|
+| 10          	| right ankle    	| r_ank            	|
+| 11          	| left hip       	| l_hip            	|
+| 12          	| left knee      	| l_knee           	|
+| 13          	| left ankle     	| l_ank            	|
+| 14          	| right eye      	| r_eye            	|
+| 15          	| left eye       	| l_eye            	|
+| 16          	| right ear      	| r_ear            	|
+| 17          	| left ear       	| l_ear            	|
+
+
+#### References
+<a name="open-pose-1" href="https://arxiv.org/abs/1812.08008">[1]</a> OpenPose: Realtime Multi-Person 2D Pose Estimation using Part Affinity Fields,
+[arXiv](https://arxiv.org/abs/1812.08008).
+<a name="open-pose-2" href="https://arxiv.org/abs/1811.12004">[2]</a> Real-time 2D Multi-Person Pose Estimation on CPU: Lightweight OpenPose,
+[arXiv](https://arxiv.org/abs/1811.12004).
diff --git a/projects/python/perception/high_resolution_pose_estimation/README.md b/projects/python/perception/high_resolution_pose_estimation/README.md
new file mode 100644
index 0000000000..8342848ad2
--- /dev/null
+++ b/projects/python/perception/high_resolution_pose_estimation/README.md
@@ -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 specific, 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 a 720p, 1080p, 1440p dataset. 
+3. demos/benchmarking.py: A simple benchmarking tool for measuring the performance of High Resolution Pose Estimation in various platforms.
+
+
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
new file mode 100644
index 0000000000..1aa259a233
--- /dev/null
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
@@ -0,0 +1,85 @@
+# 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("--onnx", help="Use ONNX", default=False, action="store_true")
+    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()
+
+    onnx, device, accelerate,base_height1,base_height2 = args.onnx, 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)
+    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("temp2", "dataset", "image", "000000000785_1440.jpg")
+    img = cv2.imread(image_path)
+
+    if onnx:
+        pose_estimator.optimize()
+
+    fps_list = []
+    print("Benchmarking...")
+    for i in tqdm(range(50)):
+        start_time = time.perf_counter()
+        # Perform inference
+
+        poses = pose_estimator.infer(img, base_height1, base_height2)
+
+        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
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
new file mode 100644
index 0000000000..9a35becb66
--- /dev/null
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
@@ -0,0 +1,60 @@
+
+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("--onnx", help="Use ONNX", default=False, action="store_true")
+    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)
+    parser.add_argument("--hrdata", help="Select the image resolution for inference", default=1440)
+
+    args = parser.parse_args()
+
+    onnx, device, accelerate,base_height1,base_height2,hrdata = args.onnx, args.device, args.accelerate, args.height1, args.height2,args.hrdata
+
+
+    if hrdata == 1440:
+        data_file="data_1440"
+    elif hrdata == 1080:
+        data_file="data_1080"
+    elif hrdata == 720:
+        data_file="data_720"
+    else:
+        raise Exception("The inference image resolution is not valid")
+
+
+    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)
+    pose_estimator.download(path=".", verbose=True)
+    pose_estimator.load("openpose_default")
+
+    if onnx:
+        pose_estimator.optimize()
+
+    # Download a sample dataset
+    pose_estimator.download(path=".", mode="test_data")
+
+    eval_dataset = ExternalDataset(path=join("temp2", "dataset",data_file), dataset_type="COCO")
+
+    t0=time.time()
+    results_dict = pose_estimator.eval(eval_dataset,base_height1,base_height2, 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)
\ No newline at end of file
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
new file mode 100644
index 0000000000..dab85bbd5b
--- /dev/null
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
@@ -0,0 +1,65 @@
+
+import cv2
+from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
+
+from opendr.perception.pose_estimation import draw
+from opendr.engine.data import Image
+import argparse
+from os.path import join
+
+
+if __name__ == '__main__':
+    parser = argparse.ArgumentParser()
+    parser.add_argument("--onnx", help="Use ONNX", default=False, action="store_true")
+    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=540)
+    parser.add_argument("--height2", help="Base height of resizing in second inference", default=540)
+    parser.add_argument("--hrdata",help="Select the image resolution for inference",default=1440)
+
+    args = parser.parse_args()
+
+    onnx, device, accelerate,base_height1,base_height2,hrdata = args.onnx, args.device, args.accelerate, args.height1, args.height2,args.hrdata
+
+    if hrdata == 1440:
+        image_file="000000000785_1440.jpg"
+    elif hrdata == 1080:
+        image_file="000000000785_1080.jpg"
+    elif hrdata == 720:
+        image_file="000000000785_720.jpg"
+    else:
+        raise Exception("The inference image resolution is not valid")
+
+    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)
+    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("temp2", "dataset", "image", image_file)
+
+    img = Image.open(image_path)
+
+    if onnx:
+        pose_estimator.optimize()
+
+    poses = pose_estimator.infer(img,base_height1,base_height2)
+
+    img_cv = img.opencv()
+    for pose in poses:
+        draw(img_cv, pose)
+    cv2.imshow('Results', img_cv)
+    cv2.waitKey(0)
+
diff --git a/src/opendr/perception/pose_estimation/__init__.py b/src/opendr/perception/pose_estimation/__init__.py
index d0d7c3cc14..e483312051 100644
--- a/src/opendr/perception/pose_estimation/__init__.py
+++ b/src/opendr/perception/pose_estimation/__init__.py
@@ -1,6 +1,8 @@
 from opendr.perception.pose_estimation.lightweight_open_pose.lightweight_open_pose_learner import \
     LightweightOpenPoseLearner
+from opendr.perception.pose_estimation.hr_pose_estimation.HighResolutionLearner import \
+    HighResolutionPoseEstimationLearner
 
 from opendr.perception.pose_estimation.lightweight_open_pose.utilities import draw, get_bbox
 
-__all__ = ['LightweightOpenPoseLearner', 'draw', 'get_bbox']
+__all__ = ['LightweightOpenPoseLearner', 'draw', 'get_bbox','HighResolutionPoseEstimationLearner']
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
new file mode 100644
index 0000000000..64e08f3031
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
@@ -0,0 +1,967 @@
+# General imports
+# General imports
+import torchvision.transforms
+import onnxruntime as ort
+import os
+import ntpath
+import shutil
+import cv2
+import torch
+import json
+import numpy as np
+from tqdm import tqdm
+
+from urllib.request import urlretrieve
+
+# OpenDR engine imports
+from opendr.engine.learners import Learner
+from opendr.engine.datasets import ExternalDataset, DatasetIterator
+from opendr.engine.data import Image
+from opendr.engine.target import Pose
+from opendr.engine.constants import OPENDR_SERVER_URL
+
+# OpenDR lightweight_open_pose imports
+
+from opendr.perception.pose_estimation.hr_pose_estimation.filtered_pose import FilteredPose
+from opendr.perception.pose_estimation.hr_pose_estimation.utilities import track_poses
+from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.models.with_mobilenet import \
+    PoseEstimationWithMobileNet
+from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.models.with_mobilenet_v2 import \
+    PoseEstimationWithMobileNetV2
+from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.models.with_shufflenet import \
+    PoseEstimationWithShuffleNet
+
+from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.modules.load_state import \
+    load_state  # , load_from_mobilenet
+from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.modules.keypoints import \
+    extract_keypoints, group_keypoints
+from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.datasets.coco import CocoValDataset
+
+from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.val import \
+    convert_to_coco_format, run_coco_eval, normalize, pad_width
+from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.scripts import \
+    make_val_subset
+
+
+class HighResolutionPoseEstimationLearner(Learner):
+
+    def __init__(self, device='cuda', backbone='mobilenet',
+                 temp_path='temp', mobilenet_use_stride=True, mobilenetv2_width=1.0, shufflenet_groups=3,
+                 num_refinement_stages=2, batches_per_iter=1,base_height=256,
+                 experiment_name='default', num_workers=8, weights_only=True, output_name='detections.json',
+                 multiscale=False, scales=None, visualize=False,
+                 img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256), pad_value=(0, 0, 0),
+                 half_precision=False):
+
+        super(HighResolutionPoseEstimationLearner, self).__init__(temp_path=temp_path, device=device, backbone=backbone)
+        self.parent_dir = temp_path  # Parent dir should be filled by the user according to README
+
+        self.num_refinement_stages = num_refinement_stages  # How many extra refinement stages to add
+        self.batches_per_iter = batches_per_iter
+
+        self.experiment_name = experiment_name
+        self.num_workers = num_workers
+        self.backbone = backbone.lower()
+        self.half = half_precision
+
+        supportedBackbones = ["mobilenet", "mobilenetv2", "shufflenet"]
+        if self.backbone not in supportedBackbones:
+            raise ValueError(self.backbone + " not a valid backbone. Supported backbones:" + str(supportedBackbones))
+        if self.backbone == "mobilenet":
+            self.use_stride = mobilenet_use_stride
+        else:
+            self.use_stride = None
+        if self.backbone == "mobilenetv2":
+            self.mobilenetv2_width = mobilenetv2_width
+        if self.backbone == "shufflenet":
+            self.shufflenet_groups = shufflenet_groups
+        # if self.backbone == "mobilenet":
+        #     self.from_mobilenet = True # TODO from_mobilenet = True, bugs out the loading
+        # else:
+        #     self.from_mobilenet = False
+
+        self.weights_only = weights_only  # If True, it won't load optimizer, scheduler, num_iter, current_epoch
+
+        self.output_name = os.path.join(self.parent_dir, output_name)  # Path to json file containing detections
+        self.visualize = visualize
+        self.base_height = base_height
+        if scales is None:
+            scales = [1]
+        self.multiscale = multiscale  # If set to true, overwrites self.scales to [0.5, 1.0, 1.5, 2.0]
+        self.scales = scales
+        if self.use_stride:
+            self.stride = 8 * 2
+        else:
+            self.stride = 8
+        self.upsample_ratio = 4
+
+        self.img_mean = img_mean
+        self.img_scale = img_scale
+        self.pad_value = pad_value
+        self.previous_poses = []
+
+        self.ort_session = None  # ONNX runtime inference session
+        self.model_train_state = True
+
+    def first_pass(self, net, img):
+        height, width, _ = img.shape
+
+        if 'cuda' in self.device:
+            tensor_img = torch.from_numpy(img).permute(2, 0, 1).unsqueeze(0).float().cuda()
+            tensor_img = tensor_img.cuda()
+            if self.half:
+                tensor_img = tensor_img.half()
+        else:
+            tensor_img = torch.from_numpy(img).permute(2, 0, 1).unsqueeze(0).float().cpu()
+
+        start = torch.cuda.Event(enable_timing=True)
+        end = torch.cuda.Event(enable_timing=True)
+        start.record()
+
+        stages_output = net(tensor_img)
+
+        end.record()
+        torch.cuda.synchronize()
+
+        stage2_pafs = stages_output[-1]
+        pafs = np.transpose(stage2_pafs.squeeze().cpu().data.numpy(), (1, 2, 0))
+
+        avg_pafs = pafs
+        return avg_pafs
+
+    def second_pass_infer(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, device,
+                          pad_value=(0, 0, 0),
+                          img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256)):
+        height, width, _ = img.shape
+        scale = net_input_height_size / height
+        img_ratio = width / height
+        if img_ratio > 6:
+            scale = max_width / width
+
+        scaled_img = cv2.resize(img, (0, 0), fx=scale, fy=scale, interpolation=cv2.INTER_LINEAR)
+        scaled_img = normalize(scaled_img, img_mean, img_scale)
+        min_dims = [net_input_height_size, max(scaled_img.shape[1], net_input_height_size)]
+        padded_img, pad = pad_width(scaled_img, stride, pad_value, min_dims)
+
+        if 'cuda' in self.device:
+            tensor_img = torch.from_numpy(padded_img).permute(2, 0, 1).unsqueeze(0).float().cuda()
+            tensor_img = tensor_img.cuda()
+            if self.half:
+                tensor_img = tensor_img.half()
+        else:
+            tensor_img = torch.from_numpy(padded_img).permute(2, 0, 1).unsqueeze(0).float().cpu()
+
+        start = torch.cuda.Event(enable_timing=True)
+        end = torch.cuda.Event(enable_timing=True)
+        start.record()
+
+        stages_output = net(tensor_img)
+
+        end.record()
+        torch.cuda.synchronize()
+
+        stage2_heatmaps = stages_output[-2]
+        heatmaps = np.transpose(stage2_heatmaps.squeeze().cpu().data.numpy(), (1, 2, 0))
+        heatmaps = heatmaps.astype(np.float32)
+        heatmaps = cv2.resize(heatmaps, (0, 0), fx=upsample_ratio, fy=upsample_ratio, interpolation=cv2.INTER_CUBIC)
+
+        stage2_pafs = stages_output[-1]
+        pafs = np.transpose(stage2_pafs.squeeze().cpu().data.numpy(), (1, 2, 0))
+        pafs = pafs.astype(np.float32)
+        pafs = cv2.resize(pafs, (0, 0), fx=upsample_ratio, fy=upsample_ratio, interpolation=cv2.INTER_CUBIC)
+
+        return heatmaps, pafs, scale, pad
+
+    def Pooling(self, img, kernel):  # Pooling on input image for dim reduction
+        pooling = torch.nn.AvgPool2d(kernel)
+        pool_img = torchvision.transforms.ToTensor()(img)
+        pool_img = pool_img.unsqueeze(0)
+        pool_img = pooling(pool_img)
+        pool_img = pool_img.squeeze(0).permute(1, 2, 0).cpu().float().numpy()
+        return pool_img
+
+    def fit(self, val_dataset=None, logging_path='', logging_flush_secs=30,
+            silent=False, verbose=True, use_val_subset=True, val_subset_size=250,
+            val_images_folder_name="val2017", val_annotations_filename="person_keypoints_val2017.json"):
+        raise NotImplementedError
+
+    def optimize(self, do_constant_folding=False):
+        raise NotImplementedError
+
+
+    def reset(self):
+        """This method is not used in this implementation."""
+        return NotImplementedError
+
+    def save(self, path, verbose=False):
+        """
+        This method is used to save a trained model.
+        Provided with the path, absolute or relative, including a *folder* name, it creates a directory with the name
+        of the *folder* provided and saves the model inside with a proper format and a .json file with metadata.
+
+        If self.optimize was ran previously, it saves the optimized ONNX model in a similar fashion, by copying it
+        from the self.temp_path it was saved previously during conversion.
+
+        :param path: for the model to be saved, including the folder name
+        :type path: str
+        :param verbose: whether to print success message or not, defaults to 'False'
+        :type verbose: bool, optional
+        """
+        if self.model is None and self.ort_session is None:
+            raise UserWarning("No model is loaded, cannot save.")
+
+        folder_name, _, tail = self.__extract_trailing(path)  # Extract trailing folder name from path
+        # Also extract folder name without any extension if extension is erroneously provided
+        folder_name_no_ext = folder_name.split(sep='.')[0]
+
+        # Extract path without folder name, by removing folder name from original path
+        path_no_folder_name = path.replace(folder_name, '')
+        # If tail is '', then path was a/b/c/, which leaves a trailing double '/'
+        if tail == '':
+            path_no_folder_name = path_no_folder_name[0:-1]  # Remove one '/'
+
+        # Create model directory
+        full_path_to_model_folder = path_no_folder_name + folder_name_no_ext
+        os.makedirs(full_path_to_model_folder, exist_ok=True)
+
+        model_metadata = {"model_paths": [], "framework": "pytorch", "format": "", "has_data": False,
+                          "inference_params": {}, "optimized": None, "optimizer_info": {}, "backbone": self.backbone}
+
+        if self.ort_session is None:
+            model_metadata["model_paths"] = [folder_name_no_ext + ".pth"]
+            model_metadata["optimized"] = False
+            model_metadata["format"] = "pth"
+
+            custom_dict = {'state_dict': self.model.state_dict()}
+            torch.save(custom_dict, os.path.join(full_path_to_model_folder, model_metadata["model_paths"][0]))
+            if verbose:
+                print("Saved Pytorch model.")
+        else:
+            model_metadata["model_paths"] = [os.path.join(folder_name_no_ext + ".onnx")]
+            model_metadata["optimized"] = True
+            model_metadata["format"] = "onnx"
+            # Copy already optimized model from temp path
+            shutil.copy2(os.path.join(self.temp_path, "onnx_model_temp.onnx"),
+                         os.path.join(full_path_to_model_folder, model_metadata["model_paths"][0]))
+            model_metadata["optimized"] = True
+            if verbose:
+                print("Saved ONNX model.")
+
+        with open(os.path.join(full_path_to_model_folder, folder_name_no_ext + ".json"), 'w') as outfile:
+            json.dump(model_metadata, outfile)
+
+    def eval(self, dataset, first_pass_height, second_pass_height, silent=False, verbose=True, use_subset=True,
+             subset_size=250,
+             images_folder_name="val2017", annotations_filename="person_keypoints_val2017.json"):
+
+        data = self.__prepare_val_dataset(dataset, use_subset=use_subset,
+                                          subset_name="val_subset.json",
+                                          subset_size=subset_size,
+                                          images_folder_default_name=images_folder_name,
+                                          annotations_filename=annotations_filename,
+                                          verbose=verbose and not silent)
+        # Model initialization if needed
+        if self.model is None and self.checkpoint_load_iter != 0:
+            # No model loaded, initializing new
+            self.init_model()
+            # User set checkpoint_load_iter, so they want to load a checkpoint
+            # Try to find the checkpoint_load_iter checkpoint
+            checkpoint_name = "checkpoint_iter_" + str(self.checkpoint_load_iter) + ".pth"
+            checkpoints_folder = os.path.join(self.parent_dir, '{}_checkpoints'.format(self.experiment_name))
+            full_path = os.path.join(checkpoints_folder, checkpoint_name)
+            try:
+                checkpoint = torch.load(full_path, map_location=torch.device(self.device))
+            except FileNotFoundError as e:
+                e.strerror = "File " + checkpoint_name + " not found inside checkpoints_folder, " \
+                                                         "provided checkpoint_load_iter (" + \
+                             str(self.checkpoint_load_iter) + \
+                             ") doesn't correspond to a saved checkpoint.\nNo such file or directory."
+                raise e
+            if not silent and verbose:
+                print("Loading checkpoint:", full_path)
+
+            # Loads weights in self.model from checkpoint
+            # if self.from_mobilenet:  # TODO see todo on ctor
+            #     load_from_mobilenet(self.model, checkpoint)
+            # else:
+            load_state(self.model, checkpoint)
+        elif self.model is None:
+            raise AttributeError("self.model is None. Please load a model or set checkpoint_load_iter.")
+
+        self.model = self.model.eval()  # Change model state to evaluation
+        self.model.to(self.device)
+        if "cuda" in self.device:
+            self.model = self.model.to(self.device)
+            if self.half:
+                self.model.half()
+
+        if self.multiscale:
+            self.scales = [0.5, 1.0, 1.5, 2.0]
+
+        self.net = self.model
+        coco_result = []
+        num_keypoints = Pose.num_kpts
+
+        pbar_eval = None
+        if not silent:
+            pbarDesc = "Evaluation progress"
+            pbar_eval = tqdm(desc=pbarDesc, total=len(data), bar_format="{l_bar}%s{bar}{r_bar}" % '\x1b[38;5;231m')
+
+        img_height = data[0]['img'].shape[0]
+
+        if img_height == 1080 or img_height == 1440:
+            offset = 200
+        elif img_height == 720:
+            offset = 50
+        else:
+            offset = 0
+
+        for sample in data:
+            file_name = sample['file_name']
+            img = sample['img']
+            h, w, _ = img.shape
+            max_width = w
+            kernel = int(h / first_pass_height)
+            if kernel > 0:
+                pool_img = HighResolutionPoseEstimationLearner.Pooling(self, img, kernel)
+                base_height = pool_img.shape[0]
+            else:
+                pool_img = img
+                base_height = img.shape[0]
+
+            perc = 0.3  # percentage around cropping
+
+            thresshold = 0.1  # thresshold for heatmap
+
+            # ------- Heatmap Generation -------
+            avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.net, pool_img)
+            avg_pafs = avg_pafs.astype(np.float32)
+
+            pafs_map = cv2.blur(avg_pafs, (5, 5))
+            pafs_map[pafs_map < thresshold] = 0
+
+            heatmap = pafs_map.sum(axis=2)
+            heatmap = heatmap * 100
+            heatmap = heatmap.astype(np.uint8)
+            heatmap = cv2.blur(heatmap, (5, 5))
+
+            contours, hierarchy = cv2.findContours(heatmap, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
+            count = []
+
+            if len(contours) > 0:
+                for x in contours:
+                    count.append(x)
+                xdim = []
+                ydim = []
+
+                for j in range(len(count)):  # Loop for every human (every contour)
+                    for i in range(len(count[j])):
+                        xdim.append(count[j][i][0][0])
+                        ydim.append(count[j][i][0][1])
+
+                h, w, _ = pool_img.shape
+                xmin = int(np.floor(min(xdim))) * int((w / heatmap.shape[1])) * kernel
+                xmax = int(np.floor(max(xdim))) * int((w / heatmap.shape[1])) * kernel
+                ymin = int(np.floor(min(ydim))) * int((h / heatmap.shape[0])) * kernel
+                ymax = int(np.floor(max(ydim))) * int((h / heatmap.shape[0])) * kernel
+
+                extra_pad_x = int(perc * (xmax - xmin))  # Adding an extra pad around cropped image
+                extra_pad_y = int(perc * (ymax - ymin))
+
+                if xmin - extra_pad_x > 0: xmin = xmin - extra_pad_x
+                if xmax + extra_pad_x < img.shape[1]: xmax = xmax + extra_pad_x
+                if ymin - extra_pad_y > 0: ymin = ymin - extra_pad_y
+                if ymax + extra_pad_y < img.shape[0]: ymax = ymax + extra_pad_y
+
+                if (xmax - xmin) > 40 and (ymax - ymin) > 40:
+                    crop_img = img[ymin:ymax, xmin:xmax]
+                else:
+                    crop_img = img[offset:img.shape[0], offset:img.shape[1]]
+
+                h, w, _ = crop_img.shape
+
+                # ------- Second pass of the image, inference for pose estimation -------
+                avg_heatmaps, avg_pafs, scale, pad = HighResolutionPoseEstimationLearner.second_pass_infer(self, self.net,
+                                                                                                           crop_img,
+                                                                                                           second_pass_height,
+                                                                                                           max_width,
+                                                                                                           self.stride,
+                                                                                                           self.upsample_ratio,
+                                                                                                           self.device)
+                total_keypoints_num = 0
+                all_keypoints_by_type = []
+                for kpt_idx in range(18):
+                    total_keypoints_num += extract_keypoints(avg_heatmaps[:, :, kpt_idx], all_keypoints_by_type,
+                                                             total_keypoints_num)
+
+                pose_entries, all_keypoints = group_keypoints(all_keypoints_by_type, avg_pafs)
+
+                for kpt_id in range(all_keypoints.shape[0]):
+                    all_keypoints[kpt_id, 0] = (all_keypoints[kpt_id, 0] * self.stride / self.upsample_ratio - pad[
+                        1]) / scale
+                    all_keypoints[kpt_id, 1] = (all_keypoints[kpt_id, 1] * self.stride / self.upsample_ratio - pad[
+                        0]) / scale
+
+                for i in range(all_keypoints.shape[0]):
+                    for j in range(all_keypoints.shape[1]):
+                        if j == 0:
+                            all_keypoints[i][j] = round((all_keypoints[i][j] + xmin) - offset)  # Adjust offset if needed for evaluation on our HR datasets
+                        if j == 1:
+                            all_keypoints[i][j] = round((all_keypoints[i][j] + ymin) - offset)  # Adjust offset if needed for evaluation on our HR datasets
+
+                current_poses = []
+                for n in range(len(pose_entries)):
+                    if len(pose_entries[n]) == 0:
+                        continue
+                    pose_keypoints = np.ones((num_keypoints, 2), dtype=np.int32) * -1
+                    for kpt_id in range(num_keypoints):
+                        if pose_entries[n][kpt_id] != -1.0:  # keypoint was found
+                            pose_keypoints[kpt_id, 0] = int(all_keypoints[int(pose_entries[n][kpt_id]), 0])
+                            pose_keypoints[kpt_id, 1] = int(all_keypoints[int(pose_entries[n][kpt_id]), 1])
+                    pose = Pose(pose_keypoints, pose_entries[n][18])
+                    current_poses.append(pose)
+
+                coco_keypoints, scores = convert_to_coco_format(pose_entries, all_keypoints)
+
+                image_id = int(file_name[0:file_name.rfind('.')])
+
+                for idx in range(len(coco_keypoints)):
+                    coco_result.append({
+                        'image_id': image_id,
+                        'category_id': 1,  # person
+                        'keypoints': coco_keypoints[idx],
+                        'score': scores[idx],
+                        'person': idx
+                    })
+
+            if self.visualize:
+                for keypoints in coco_keypoints:
+                    for idx in range(len(keypoints) // 3):
+                        cv2.circle(img, (int(keypoints[idx * 3]), int(keypoints[idx * 3 + 1])),
+                                   3, (255, 0, 255), -1)
+                cv2.imshow('keypoints', img)
+                key = cv2.waitKey()
+                if key == 27:  # esc
+                    return
+            if not silent:
+                pbar_eval.update(1)
+
+        with open(self.output_name, 'w') as f:
+            json.dump(coco_result, f, indent=4)
+        if len(coco_result) != 0:
+            if use_subset:
+                result = run_coco_eval(os.path.join(dataset.path, "val_subset.json"),
+                                       self.output_name, verbose=not silent)
+            else:
+                result = run_coco_eval(os.path.join(dataset.path, annotations_filename),
+                                       self.output_name, verbose=not silent)
+            return {"average_precision": result.stats[0:5], "average_recall": result.stats[5:]}
+        else:
+            if not silent and verbose:
+                print("Evaluation ended with no detections.")
+            return {"average_precision": [0.0 for _ in range(5)], "average_recall": [0.0 for _ in range(5)]}
+
+    def infer(self, img, first_pass_height, second_pass_height, upsample_ratio=4, stride=8, track=True, smooth=True,
+              multiscale=False, visualize=False):
+        self.net = self.model
+        current_poses = []
+
+        offset = 0
+        num_keypoints = Pose.num_kpts
+
+        if not isinstance(img, Image):
+            img = Image(img)
+
+            # Bring image into the appropriate format for the implementation
+        img = img.convert(format='channels_last', channel_order='bgr')
+
+        h, w, _ = img.shape
+        max_width = w
+        kernel = int(h / first_pass_height)
+        if kernel > 0:
+            pool_img = HighResolutionPoseEstimationLearner.Pooling(self, img, kernel)
+            base_height = pool_img.shape[0]
+        else:
+            pool_img = img
+            base_height = img.shape[0]
+
+        perc = 0.3  # percentage around cropping
+
+        thresshold = 0.1  # threshold for heatmap
+
+        # ------- Heatmap Generation -------
+        avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.net, pool_img)
+        avg_pafs = avg_pafs.astype(np.float32)
+        pafs_map = cv2.blur(avg_pafs, (5, 5))
+
+        pafs_map[pafs_map < thresshold] = 0
+
+        heatmap = pafs_map.sum(axis=2)
+        heatmap = heatmap * 100
+        heatmap = heatmap.astype(np.uint8)
+        heatmap = cv2.blur(heatmap, (5, 5))
+
+        contours, hierarchy = cv2.findContours(heatmap, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
+        count = []
+
+        if len(contours) > 0:
+            for x in contours:
+                count.append(x)
+            xdim = []
+            ydim = []
+
+            for j in range(len(count)):  # Loop for every human (every contour)
+                for i in range(len(count[j])):
+                    xdim.append(count[j][i][0][0])
+                    ydim.append(count[j][i][0][1])
+
+            h, w, _ = pool_img.shape
+            xmin = int(np.floor(min(xdim))) * int((w / heatmap.shape[1])) * kernel
+            xmax = int(np.floor(max(xdim))) * int((w / heatmap.shape[1])) * kernel
+            ymin = int(np.floor(min(ydim))) * int((h / heatmap.shape[0])) * kernel
+            ymax = int(np.floor(max(ydim))) * int((h / heatmap.shape[0])) * kernel
+
+            extra_pad_x = int(perc * (xmax - xmin))  # Adding an extra pad around cropped image
+            extra_pad_y = int(perc * (ymax - ymin))
+
+            if xmin - extra_pad_x > 0: xmin = xmin - extra_pad_x
+            if xmax + extra_pad_x < img.shape[1]: xmax = xmax + extra_pad_x
+            if ymin - extra_pad_y > 0: ymin = ymin - extra_pad_y
+            if ymax + extra_pad_y < img.shape[0]: ymax = ymax + extra_pad_y
+
+            if (xmax - xmin) > 40 and (ymax - ymin) > 40:
+                crop_img = img[ymin:ymax, xmin:xmax]
+            else:
+                crop_img = img[offset:img.shape[0], offset:img.shape[1]]
+
+            h, w, _ = crop_img.shape
+
+            # ------- Second pass of the image, inference for pose estimation -------
+            avg_heatmaps, avg_pafs, scale, pad = HighResolutionPoseEstimationLearner.second_pass_infer(self, self.net,
+                                                                                                       crop_img,
+                                                                                                       second_pass_height,
+                                                                                                       max_width,
+                                                                                                       stride,
+                                                                                                       upsample_ratio,
+                                                                                                       self.device)
+            total_keypoints_num = 0
+            all_keypoints_by_type = []
+            for kpt_idx in range(18):
+                total_keypoints_num += extract_keypoints(avg_heatmaps[:, :, kpt_idx], all_keypoints_by_type,
+                                                         total_keypoints_num)
+
+            pose_entries, all_keypoints = group_keypoints(all_keypoints_by_type, avg_pafs)
+
+            for kpt_id in range(all_keypoints.shape[0]):
+                all_keypoints[kpt_id, 0] = (all_keypoints[kpt_id, 0] * stride / upsample_ratio - pad[1]) / scale
+                all_keypoints[kpt_id, 1] = (all_keypoints[kpt_id, 1] * stride / upsample_ratio - pad[0]) / scale
+
+            for i in range(all_keypoints.shape[0]):
+                for j in range(all_keypoints.shape[1]):
+                    if j == 0:
+                        all_keypoints[i][j] = round((all_keypoints[i][j] + xmin) - offset)  # Adjust offset if needed for evaluation on our HR datasets
+                    if j == 1:
+                        all_keypoints[i][j] = round((all_keypoints[i][j] + ymin) - offset)  # Adjust offset if needed for evaluation on our HR datasets
+
+            current_poses = []
+            for n in range(len(pose_entries)):
+                if len(pose_entries[n]) == 0:
+                    continue
+                pose_keypoints = np.ones((num_keypoints, 2), dtype=np.int32) * -1
+                for kpt_id in range(num_keypoints):
+                    if pose_entries[n][kpt_id] != -1.0:  # keypoint was found
+                        pose_keypoints[kpt_id, 0] = int(all_keypoints[int(pose_entries[n][kpt_id]), 0])
+                        pose_keypoints[kpt_id, 1] = int(all_keypoints[int(pose_entries[n][kpt_id]), 1])
+                pose = Pose(pose_keypoints, pose_entries[n][18])
+                current_poses.append(pose)
+
+        return current_poses
+
+    def infer_light_odr(self, img, upsample_ratio=4, track=True, smooth=True):      #LwOP from OpenDR implementation
+        """
+        This method is used to perform pose estimation on an image.
+
+        :param img: image to run inference on
+        :rtype img: engine.data.Image class object
+        :param upsample_ratio: Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing,
+            defaults to 4
+        :type upsample_ratio: int, optional
+        :param track: If True, infer propagates poses ids from previous frame results to track poses, defaults to 'True'
+        :type track: bool, optional
+        :param smooth: If True, smoothing is performed on pose keypoints between frames, defaults to 'True'
+        :type smooth: bool, optional
+        :return: Returns a list of engine.target.Pose objects, where each holds a pose, or returns an empty list if no
+            detections were made.
+        :rtype: list of engine.target.Pose objects
+        """
+        if not isinstance(img, Image):
+            img = Image(img)
+
+        # Bring image into the appropriate format for the implementation
+        img = img.convert(format='channels_last', channel_order='bgr')
+
+        height, width, _ = img.shape
+        scale = self.base_height / height
+
+        scaled_img = cv2.resize(img, (0, 0), fx=scale, fy=scale, interpolation=cv2.INTER_LINEAR)
+        scaled_img = normalize(scaled_img, self.img_mean, self.img_scale)
+        min_dims = [self.base_height, max(scaled_img.shape[1], self.base_height)]
+        padded_img, pad = pad_width(scaled_img, self.stride, self.pad_value, min_dims)
+
+        tensor_img = torch.from_numpy(padded_img).permute(2, 0, 1).unsqueeze(0).float()
+        if "cuda" in self.device:
+            tensor_img = tensor_img.to(self.device)
+            if self.half:
+                tensor_img = tensor_img.half()
+
+        if self.ort_session is not None:
+            stages_output = self.ort_session.run(None, {'data': np.array(tensor_img.cpu())})
+            stage2_heatmaps = torch.tensor(stages_output[-2])
+            stage2_pafs = torch.tensor(stages_output[-1])
+        else:
+            if self.model is None:
+                raise UserWarning("No model is loaded, cannot run inference. Load a model first using load().")
+            if self.model_train_state:
+                self.model.eval()
+                self.model_train_state = False
+            stages_output = self.model(tensor_img)
+            stage2_heatmaps = stages_output[-2]
+            stage2_pafs = stages_output[-1]
+
+        heatmaps = np.transpose(stage2_heatmaps.squeeze().cpu().data.numpy(), (1, 2, 0))
+        if self.half:
+            heatmaps = np.float32(heatmaps)
+        heatmaps = cv2.resize(heatmaps, (0, 0), fx=upsample_ratio, fy=upsample_ratio, interpolation=cv2.INTER_CUBIC)
+
+        pafs = np.transpose(stage2_pafs.squeeze().cpu().data.numpy(), (1, 2, 0))
+        if self.half:
+            pafs = np.float32(pafs)
+        pafs = cv2.resize(pafs, (0, 0), fx=upsample_ratio, fy=upsample_ratio, interpolation=cv2.INTER_CUBIC)
+
+        total_keypoints_num = 0
+        all_keypoints_by_type = []
+        num_keypoints = 18
+        for kpt_idx in range(num_keypoints):  # 19th for bg
+            total_keypoints_num += extract_keypoints(heatmaps[:, :, kpt_idx], all_keypoints_by_type,
+                                                     total_keypoints_num)
+
+        pose_entries, all_keypoints = group_keypoints(all_keypoints_by_type, pafs)
+        for kpt_id in range(all_keypoints.shape[0]):
+            all_keypoints[kpt_id, 0] = (all_keypoints[kpt_id, 0] * self.stride / upsample_ratio - pad[1]) / scale
+            all_keypoints[kpt_id, 1] = (all_keypoints[kpt_id, 1] * self.stride / upsample_ratio - pad[0]) / scale
+        current_poses = []
+        for n in range(len(pose_entries)):
+            if len(pose_entries[n]) == 0:
+                continue
+            pose_keypoints = np.ones((num_keypoints, 2), dtype=np.int32) * -1
+            for kpt_id in range(num_keypoints):
+                if pose_entries[n][kpt_id] != -1.0:  # keypoint was found
+                    pose_keypoints[kpt_id, 0] = int(all_keypoints[int(pose_entries[n][kpt_id]), 0])
+                    pose_keypoints[kpt_id, 1] = int(all_keypoints[int(pose_entries[n][kpt_id]), 1])
+            if smooth:
+                pose = FilteredPose(pose_keypoints, pose_entries[n][18])
+            else:
+                pose = Pose(pose_keypoints, pose_entries[n][18])
+            current_poses.append(pose)
+
+        if track:
+            track_poses(self.previous_poses, current_poses, smooth=smooth)
+            self.previous_poses = current_poses
+        return current_poses
+
+    def init_model(self):
+        if self.model is None:
+            # No model loaded, initializing new
+            if self.backbone == "mobilenet":
+                self.model = PoseEstimationWithMobileNet(self.num_refinement_stages, use_stride=self.use_stride)
+            elif self.backbone == "mobilenetv2":
+                self.model = PoseEstimationWithMobileNetV2(self.num_refinement_stages,
+                                                           width_mult=self.mobilenetv2_width)
+            elif self.backbone == "shufflenet":
+                self.model = PoseEstimationWithShuffleNet(self.num_refinement_stages,
+                                                          groups=self.shufflenet_groups)
+        else:
+            raise UserWarning("Tried to initialize model while model is already initialized.")
+        self.model.to(self.device)
+
+    def load(self, path, verbose=False):
+        """
+        Loads the model from inside the path provided, based on the metadata .json file included.
+        :param path: path of the directory the model was saved
+        :type path: str
+        :param verbose: whether to print success message or not, defaults to 'False'
+        :type verbose: bool, optional
+        """
+        model_name, _, _ = self.__extract_trailing(path)  # Trailing folder name from the path provided
+
+        with open(os.path.join(path, model_name + ".json")) as metadata_file:
+            metadata = json.load(metadata_file)
+
+        self.backbone = metadata["backbone"]
+        if not metadata["optimized"]:
+            self.__load_from_pth(os.path.join(path, metadata['model_paths'][0]))
+            if verbose:
+                print("Loaded Pytorch model.")
+        else:
+            self.__load_from_onnx(os.path.join(path, metadata['model_paths'][0]))
+            if verbose:
+                print("Loaded ONNX model.")
+
+    def __load_from_pth(self, path):
+        """
+        This method loads a regular Pytorch model from the path provided into self.model.
+
+        :param path: path to .pth model
+        :type path: str
+        """
+        self.init_model()
+        checkpoint = torch.load(path, map_location=torch.device(self.device))
+        # if self.from_mobilenet:  # TODO see todo on ctor
+        #     load_from_mobilenet(self.model, checkpoint)
+        # else:
+        load_state(self.model, checkpoint)
+        if "cuda" in self.device:
+            self.model.to(self.device)
+            if self.half:
+                self.model.half()
+        self.model.train(False)
+
+    def __load_from_onnx(self, path):
+        """
+        This method loads an ONNX model from the path provided into an onnxruntime inference session.
+
+        :param path: path to ONNX model
+        :type path: str
+        """
+        self.ort_session = ort.InferenceSession(path)
+
+        # The comments below are the alternative way to use the onnx model, it might be useful in the future
+        # depending on how ONNX saving/loading will be implemented across the toolkit.
+        # # Load the ONNX model
+        # self.model = onnx.load(path)
+        #
+        # # Check that the IR is well formed
+        # onnx.checker.check_model(self.model)
+        #
+        # # Print a human readable representation of the graph
+        # onnx.helper.printable_graph(self.model.graph)
+
+    @staticmethod
+    def __extract_trailing(path):
+        """
+        Extracts the trailing folder name or filename from a path provided in an OS-generic way, also handling
+        cases where the last trailing character is a separator. Returns the folder name and the split head and tail.
+
+        :param path: the path to extract the trailing filename or folder name from
+        :type path: str
+        :return: the folder name, the head and tail of the path
+        :rtype: tuple of three strings
+        """
+        head, tail = ntpath.split(path)
+        folder_name = tail or ntpath.basename(head)  # handle both a/b/c and a/b/c/
+        return folder_name, head, tail
+
+    def download(self, path=None, mode="pretrained", verbose=False,
+                 url=OPENDR_SERVER_URL + "perception/pose_estimation/lightweight_open_pose/"):
+        """
+        Download utility for various Lightweight Open Pose components. Downloads files depending on mode and
+        saves them in the path provided. It supports downloading:
+        1) the default mobilenet pretrained model
+        2) mobilenet, mobilenetv2 and shufflenet weights needed for training
+        3) a test dataset with a single COCO image and its annotation
+        :param path: Local path to save the files, defaults to self.temp_path if None
+        :type path: str, path, optional
+        :param mode: What file to download, can be one of "pretrained", "weights", "test_data", defaults to "pretrained"
+        :type mode: str, optional
+        :param verbose: Whether to print messages in the console, defaults to False
+        :type verbose: bool, optional
+        :param url: URL of the FTP server, defaults to OpenDR FTP URL
+        :type url: str, optional
+        """
+        valid_modes = ["weights", "pretrained", "test_data"]
+        if mode not in valid_modes:
+            raise UserWarning("mode parameter not valid:", mode, ", file should be one of:", valid_modes)
+
+        if path is None:
+            path = self.temp_path
+
+        if not os.path.exists(path):
+            os.makedirs(path)
+
+        if mode == "pretrained":
+            # Create model's folder
+            path = os.path.join(path, "openpose_default")
+            if not os.path.exists(path):
+                os.makedirs(path)
+
+            if verbose:
+                print("Downloading pretrained model...")
+
+            # Download the model's files
+            if self.backbone == "mobilenet":
+                if not os.path.exists(os.path.join(path, "openpose_default.json")):
+                    file_url = os.path.join(url, "openpose_default/openpose_default.json")
+                    urlretrieve(file_url, os.path.join(path, "openpose_default.json"))
+                    if verbose:
+                        print("Downloaded metadata json.")
+                else:
+                    if verbose:
+                        print("Metadata json file already exists.")
+                if not os.path.exists(os.path.join(path, "openpose_default.pth")):
+                    file_url = os.path.join(url, "openpose_default/openpose_default.pth")
+                    urlretrieve(file_url, os.path.join(path, "openpose_default.pth"))
+                else:
+                    if verbose:
+                        print("Trained model .pth file already exists.")
+            elif self.backbone == "mobilenetv2":
+                raise UserWarning("mobilenetv2 does not support pretrained model.")
+            elif self.backbone == "shufflenet":
+                raise UserWarning("shufflenet does not support pretrained model.")
+            if verbose:
+                print("Pretrained model download complete.")
+
+        elif mode == "weights":
+            if verbose:
+                print("Downloading weights file...")
+            if self.backbone == "mobilenet":
+                if not os.path.exists(os.path.join(self.temp_path, "mobilenet_sgd_68.848.pth.tar")):
+                    file_url = os.path.join(url, "mobilenet_sgd_68.848.pth.tar")
+                    urlretrieve(file_url, os.path.join(self.temp_path, "mobilenet_sgd_68.848.pth.tar"))
+                    if verbose:
+                        print("Downloaded mobilenet weights.")
+                else:
+                    if verbose:
+                        print("Weights file already exists.")
+            elif self.backbone == "mobilenetv2":
+                if not os.path.exists(os.path.join(self.temp_path, "mobilenetv2_1.0-f2a8633.pth.tar")):
+                    file_url = os.path.join(url, "mobilenetv2_1.0-f2a8633.pth.tar")
+                    urlretrieve(file_url, os.path.join(self.temp_path, "mobilenetv2_1.0-f2a8633.pth.tar"))
+                    if verbose:
+                        print("Downloaded mobilenetv2 weights.")
+                else:
+                    if verbose:
+                        print("Weights file already exists.")
+            elif self.backbone == "shufflenet":
+                if not os.path.exists(os.path.join(self.temp_path, "shufflenet.pth.tar")):
+                    file_url = os.path.join(url, "shufflenet.pth.tar")
+                    urlretrieve(file_url, os.path.join(self.temp_path, "shufflenet.pth.tar"))
+                    if verbose:
+                        print("Downloaded shufflenet weights.")
+                else:
+                    if verbose:
+                        print("Weights file already exists.")
+            if verbose:
+                print("Weights file download complete.")
+
+        elif mode == "test_data":
+            if verbose:
+                print("Downloading test data...")
+            if not os.path.exists(os.path.join(self.temp_path, "dataset")):
+                os.makedirs(os.path.join(self.temp_path, "dataset"))
+            if not os.path.exists(os.path.join(self.temp_path, "dataset", "image")):
+                os.makedirs(os.path.join(self.temp_path, "dataset", "image"))
+            # Download annotation file
+            file_url = os.path.join(url, "dataset", "annotation.json")
+            urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "annotation.json"))
+            # Download test image
+            url=OPENDR_SERVER_URL + "/perception/pose_estimation/high_resolution_pose_estimation/"
+            file_url = os.path.join(url, "dataset", "image", "000000000785_1080.jpg")
+            urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "image", "000000000785_1080.jpg"))
+
+            if verbose:
+                print("Test data download complete.")
+
+    @staticmethod
+    def __prepare_val_dataset(dataset, use_subset=False, subset_name="val_subset.json",
+                              subset_size=250,
+                              images_folder_default_name="val2017",
+                              annotations_filename="person_keypoints_val2017.json",
+                              verbose=True):
+        """
+        This internal method prepares the validation dataset depending on what type of dataset is provided.
+
+        If an ExternalDataset object type is provided, the method tried to prepare the dataset based on the original
+        implementation, supposing that the dataset is in the COCO format. The path provided is searched for the
+        images folder and the annotations file, converts the annotations file into the internal format used if needed
+        and finally the CocoValDataset object is returned.
+
+        If the dataset is of the DatasetIterator format, then it's a custom implementation of a dataset and all
+        required operations should be handled by the user, so the dataset object is just returned.
+
+        :param dataset: the dataset
+        :type dataset: ExternalDataset class object or DatasetIterator class object
+        :param use_subset: whether to return a subset of the validation dataset, defaults to 'False'
+        :type use_subset: bool, optional
+        :param subset_name: the .json file where the validation dataset subset is saved, defaults to "val_subset.json"
+        :type subset_name: str, optional
+        :param subset_size: the size of the subset, defaults to 250
+        :type subset_size: int
+        :param images_folder_default_name: the name of the folder that contains the image files, defaults to "val2017"
+        :type images_folder_default_name: str, optional
+        :param annotations_filename: the .json file that contains the original annotations, defaults
+            to "person_keypoints_val2017.json"
+        :type annotations_filename: str, optional
+        :param verbose: whether to print additional information, defaults to 'True'
+        :type verbose: bool, optional
+
+        :raises UserWarning: UserWarnings with appropriate messages are raised for wrong type of dataset, or wrong paths
+            and filenames
+
+        :return: returns CocoValDataset object or custom DatasetIterator implemented by user
+        :rtype: CocoValDataset class object or DatasetIterator instance
+        """
+        if isinstance(dataset, ExternalDataset):
+            if dataset.dataset_type.lower() != "coco":
+                raise UserWarning("dataset_type must be \"COCO\"")
+
+            # Get files and subdirectories of dataset.path directory
+            f = []
+            dirs = []
+            for (dirpath, dirnames, filenames) in os.walk(dataset.path):
+                f = filenames
+                dirs = dirnames
+                break
+
+            # Get images folder
+            if images_folder_default_name not in dirs:
+                raise UserWarning("Didn't find \"" + images_folder_default_name +
+                                  "\" folder in the dataset path provided.")
+            images_folder = os.path.join(dataset.path, images_folder_default_name)
+
+            # Get annotations file
+            if annotations_filename not in f:
+                raise UserWarning("Didn't find \"" + annotations_filename +
+                                  "\" file in the dataset path provided.")
+            val_labels_file = os.path.join(dataset.path, annotations_filename)
+
+            if use_subset:
+                val_sub_labels_file = os.path.join(dataset.path, subset_name)
+                if subset_name not in f:
+                    if verbose:
+                        print("Didn't find " + subset_name + " in dataset.path, creating new...")
+                    make_val_subset.make_val_subset(val_labels_file,
+                                                    output_path=val_sub_labels_file,
+                                                    num_images=subset_size)
+                    if verbose:
+                        print("Created new validation subset file.")
+                    data = CocoValDataset(val_sub_labels_file, images_folder)
+                else:
+                    if verbose:
+                        print("Val subset already exists.")
+                    data = CocoValDataset(val_sub_labels_file, images_folder)
+                    if len(data) != subset_size:
+                        if verbose:
+                            print("Val subset is wrong size, creating new.")
+                        # os.remove(val_sub_labels_file)
+                        make_val_subset.make_val_subset(val_labels_file,
+                                                        output_path=val_sub_labels_file,
+                                                        num_images=subset_size)
+                        if verbose:
+                            print("Created new validation subset file.")
+                        data = CocoValDataset(val_sub_labels_file, images_folder)
+            else:
+                data = CocoValDataset(val_labels_file, images_folder)
+            return data
+
+        elif isinstance(dataset, DatasetIterator):
+            return dataset
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/README.md b/src/opendr/perception/pose_estimation/hr_pose_estimation/README.md
new file mode 100644
index 0000000000..e9a89a99ca
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/README.md
@@ -0,0 +1,11 @@
+# OpenDR Pose Estimation - High Resolution Open Pose
+
+This folder contains the OpenDR Learner and Target classes implemented for the high resolution pose estimation task.
+
+
+# Sources
+
+Large parts of the Learner and utilities.py code are taken from [Daniil-Osokin/lightweight-human-pose-estimation.pytorch](
+https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch) with modifications to make them compatible 
+with OpenDR specifications.
+
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md
new file mode 100644
index 0000000000..3299138ac4
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md
@@ -0,0 +1,44 @@
+# OpenDR Pose Estimation - Lightweight Open Pose
+
+This folder contains the Open Pose[1] algorithm implementation for pose estimation in the OpenDR Toolkit, 
+in the form of Lightweight Open Pose [2].
+
+## Sources
+
+The algorithms files are copied from [Daniil-Osokin/lightweight-human-pose-estimation.pytorch](
+https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch) with minor modifications listed below:
+
+1. `datasets/coco.py`: PEP8 changes
+2. `datasets/transformations.py`: PEP8 changes
+3. `models/with_mobilenet`: PEP8 changes
+4. `modules/conv.py`: PEP8 changes
+5. `modules/get_parameters.py`: PEP8 changes
+6. `modules/keypoints.py`: PEP8 changes
+7. `modules/load_state.py`: 
+    - Modified `load_state()` by adding a try/except block
+    - Commented out warning prints from both functions
+8. `modules/loss.py`: PEP8 changes
+9. `one_euro_filter.py`:  PEP8 changes
+10. `scripts/make_val_subset.py`: Modified to work as a callable function
+11. `scripts/prepare_train_labels.py`:
+    - PEP8 changes
+    - Modified to work as a callable function
+12. `val.py`: 
+    - PEP8 changes
+    - Removed `main`
+    - Added verbose conditionals in `run_coco_eval()`
+
+## Added Files
+Two additional backbone models were added in the `models` directory.
+
+- `models/with_mobilenet_v2.py`: Copied from [tonylins/pytorch-mobilenet-v2](
+https://github.com/tonylins/pytorch-mobilenet-v2) and modified to work as a backbone for pose estimation.
+- `models/with_shufflenet.py`: Copied from [jaxony/ShuffleNet](https://github.com/jaxony/ShuffleNet) and modified to 
+work as a backbone for pose estimation. 
+
+## References
+
+- [1]: OpenPose: Realtime Multi-Person 2D Pose Estimation using Part Affinity Fields, 
+[arXiv](https://arxiv.org/abs/1812.08008).
+- [2]: Real-time 2D Multi-Person Pose Estimation on CPU: Lightweight OpenPose, 
+[arXiv](https://arxiv.org/abs/1811.12004).
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/coco.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/coco.py
new file mode 100644
index 0000000000..a9551d37aa
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/coco.py
@@ -0,0 +1,180 @@
+import copy
+import json
+import math
+import os
+import pickle
+
+import cv2
+import numpy as np
+import pycocotools
+
+from torch.utils.data.dataset import Dataset
+
+BODY_PARTS_KPT_IDS = [[1, 8], [8, 9], [9, 10], [1, 11], [11, 12], [12, 13], [1, 2], [2, 3], [3, 4], [2, 16],
+                      [1, 5], [5, 6], [6, 7], [5, 17], [1, 0], [0, 14], [0, 15], [14, 16], [15, 17]]
+
+
+def get_mask(segmentations, mask):
+    for segmentation in segmentations:
+        rle = pycocotools.mask.frPyObjects(segmentation, mask.shape[0], mask.shape[1])
+        mask[pycocotools.mask.decode(rle) > 0.5] = 0
+    return mask
+
+
+class CocoTrainDataset(Dataset):
+    def __init__(self, labels, images_folder, stride, sigma, paf_thickness, transform=None):
+        super().__init__()
+        self._images_folder = images_folder
+        self._stride = stride
+        self._sigma = sigma
+        self._paf_thickness = paf_thickness
+        self._transform = transform
+        with open(labels, 'rb') as f:
+            self._labels = pickle.load(f)
+
+    def __getitem__(self, idx):
+        label = copy.deepcopy(self._labels[idx])  # label modified in transform
+        image = cv2.imread(os.path.join(self._images_folder, label['img_paths']), cv2.IMREAD_COLOR)
+        mask = np.ones(shape=(label['img_height'], label['img_width']), dtype=np.float32)
+        mask = get_mask(label['segmentations'], mask)
+        sample = {
+            'label': label,
+            'image': image,
+            'mask': mask
+        }
+        if self._transform:
+            sample = self._transform(sample)
+
+        mask = cv2.resize(sample['mask'], dsize=None, fx=1 / self._stride, fy=1 / self._stride,
+                          interpolation=cv2.INTER_AREA)
+        keypoint_maps = self._generate_keypoint_maps(sample)
+        sample['keypoint_maps'] = keypoint_maps
+        keypoint_mask = np.zeros(shape=keypoint_maps.shape, dtype=np.float32)
+        for idx in range(keypoint_mask.shape[0]):
+            keypoint_mask[idx] = mask
+        sample['keypoint_mask'] = keypoint_mask
+
+        paf_maps = self._generate_paf_maps(sample)
+        sample['paf_maps'] = paf_maps
+        paf_mask = np.zeros(shape=paf_maps.shape, dtype=np.float32)
+        for idx in range(paf_mask.shape[0]):
+            paf_mask[idx] = mask
+        sample['paf_mask'] = paf_mask
+
+        image = sample['image'].astype(np.float32)
+        image = (image - 128) / 256
+        sample['image'] = image.transpose((2, 0, 1))
+        del sample['label']
+        return sample
+
+    def __len__(self):
+        return len(self._labels)
+
+    def _generate_keypoint_maps(self, sample):
+        n_keypoints = 18
+        n_rows, n_cols, _ = sample['image'].shape
+        keypoint_maps = np.zeros(shape=(n_keypoints + 1,
+                                        n_rows // self._stride, n_cols // self._stride), dtype=np.float32)  # +1 for bg
+
+        label = sample['label']
+        for keypoint_idx in range(n_keypoints):
+            keypoint = label['keypoints'][keypoint_idx]
+            if keypoint[2] <= 1:
+                self._add_gaussian(keypoint_maps[keypoint_idx], keypoint[0], keypoint[1], self._stride, self._sigma)
+            for another_annotation in label['processed_other_annotations']:
+                keypoint = another_annotation['keypoints'][keypoint_idx]
+                if keypoint[2] <= 1:
+                    self._add_gaussian(keypoint_maps[keypoint_idx], keypoint[0], keypoint[1], self._stride, self._sigma)
+        keypoint_maps[-1] = 1 - keypoint_maps.max(axis=0)
+        return keypoint_maps
+
+    def _add_gaussian(self, keypoint_map, x, y, stride, sigma):
+        n_sigma = 4
+        tl = [int(x - n_sigma * sigma), int(y - n_sigma * sigma)]
+        tl[0] = max(tl[0], 0)
+        tl[1] = max(tl[1], 0)
+
+        br = [int(x + n_sigma * sigma), int(y + n_sigma * sigma)]
+        map_h, map_w = keypoint_map.shape
+        br[0] = min(br[0], map_w * stride)
+        br[1] = min(br[1], map_h * stride)
+
+        shift = stride / 2 - 0.5
+        for map_y in range(tl[1] // stride, br[1] // stride):
+            for map_x in range(tl[0] // stride, br[0] // stride):
+                d2 = (map_x * stride + shift - x) * (map_x * stride + shift - x) + \
+                     (map_y * stride + shift - y) * (map_y * stride + shift - y)
+                exponent = d2 / 2 / sigma / sigma
+                if exponent > 4.6052:  # threshold, ln(100), ~0.01
+                    continue
+                keypoint_map[map_y, map_x] += math.exp(-exponent)
+                if keypoint_map[map_y, map_x] > 1:
+                    keypoint_map[map_y, map_x] = 1
+
+    def _generate_paf_maps(self, sample):
+        n_pafs = len(BODY_PARTS_KPT_IDS)
+        n_rows, n_cols, _ = sample['image'].shape
+        paf_maps = np.zeros(shape=(n_pafs * 2, n_rows // self._stride, n_cols // self._stride), dtype=np.float32)
+
+        label = sample['label']
+        for paf_idx in range(n_pafs):
+            keypoint_a = label['keypoints'][BODY_PARTS_KPT_IDS[paf_idx][0]]
+            keypoint_b = label['keypoints'][BODY_PARTS_KPT_IDS[paf_idx][1]]
+            if keypoint_a[2] <= 1 and keypoint_b[2] <= 1:
+                self._set_paf(paf_maps[paf_idx * 2:paf_idx * 2 + 2],
+                              keypoint_a[0], keypoint_a[1], keypoint_b[0], keypoint_b[1],
+                              self._stride, self._paf_thickness)
+            for another_annotation in label['processed_other_annotations']:
+                keypoint_a = another_annotation['keypoints'][BODY_PARTS_KPT_IDS[paf_idx][0]]
+                keypoint_b = another_annotation['keypoints'][BODY_PARTS_KPT_IDS[paf_idx][1]]
+                if keypoint_a[2] <= 1 and keypoint_b[2] <= 1:
+                    self._set_paf(paf_maps[paf_idx * 2:paf_idx * 2 + 2],
+                                  keypoint_a[0], keypoint_a[1], keypoint_b[0], keypoint_b[1],
+                                  self._stride, self._paf_thickness)
+        return paf_maps
+
+    def _set_paf(self, paf_map, x_a, y_a, x_b, y_b, stride, thickness):
+        x_a /= stride
+        y_a /= stride
+        x_b /= stride
+        y_b /= stride
+        x_ba = x_b - x_a
+        y_ba = y_b - y_a
+        _, h_map, w_map = paf_map.shape
+        x_min = int(max(min(x_a, x_b) - thickness, 0))
+        x_max = int(min(max(x_a, x_b) + thickness, w_map))
+        y_min = int(max(min(y_a, y_b) - thickness, 0))
+        y_max = int(min(max(y_a, y_b) + thickness, h_map))
+        norm_ba = (x_ba * x_ba + y_ba * y_ba) ** 0.5
+        if norm_ba < 1e-7:  # Same points, no paf
+            return
+        x_ba /= norm_ba
+        y_ba /= norm_ba
+
+        for y in range(y_min, y_max):
+            for x in range(x_min, x_max):
+                x_ca = x - x_a
+                y_ca = y - y_a
+                d = math.fabs(x_ca * y_ba - y_ca * x_ba)
+                if d <= thickness:
+                    paf_map[0, y, x] = x_ba
+                    paf_map[1, y, x] = y_ba
+
+
+class CocoValDataset(Dataset):
+    def __init__(self, labels, images_folder):
+        super().__init__()
+        with open(labels, 'r') as f:
+            self._labels = json.load(f)
+        self._images_folder = images_folder
+
+    def __getitem__(self, idx):
+        file_name = self._labels['images'][idx]['file_name']
+        img = cv2.imread(os.path.join(self._images_folder, file_name), cv2.IMREAD_COLOR)
+        return {
+            'img': img,
+            'file_name': file_name
+        }
+
+    def __len__(self):
+        return len(self._labels['images'])
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/transformations.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/transformations.py
new file mode 100644
index 0000000000..99295f8e76
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/transformations.py
@@ -0,0 +1,249 @@
+import random
+
+import cv2
+import numpy as np
+
+
+class ConvertKeypoints:
+    def __call__(self, sample):
+        label = sample['label']
+        h, w, _ = sample['image'].shape
+        keypoints = label['keypoints']
+        for keypoint in keypoints:  # keypoint[2] == 0: occluded, == 1: visible, == 2: not in image
+            if keypoint[0] == keypoint[1] == 0:
+                keypoint[2] = 2
+            if keypoint[0] < 0 or keypoint[0] >= w or keypoint[1] < 0 or keypoint[1] >= h:
+                keypoint[2] = 2
+        for other_label in label['processed_other_annotations']:
+            keypoints = other_label['keypoints']
+            for keypoint in keypoints:
+                if keypoint[0] == keypoint[1] == 0:
+                    keypoint[2] = 2
+                if keypoint[0] < 0 or keypoint[0] >= w or keypoint[1] < 0 or keypoint[1] >= h:
+                    keypoint[2] = 2
+        label['keypoints'] = self._convert(label['keypoints'], w, h)
+
+        for other_label in label['processed_other_annotations']:
+            other_label['keypoints'] = self._convert(other_label['keypoints'], w, h)
+        return sample
+
+    def _convert(self, keypoints, w, h):
+        # Nose, Neck, R hand, L hand, R leg, L leg, Eyes, Ears
+        reorder_map = [1, 7, 9, 11, 6, 8, 10, 13, 15, 17, 12, 14, 16, 3, 2, 5, 4]
+        converted_keypoints = list(keypoints[i - 1] for i in reorder_map)
+        converted_keypoints.insert(1, [(keypoints[5][0] + keypoints[6][0]) / 2,
+                                       (keypoints[5][1] + keypoints[6][1]) / 2, 0])  # Add neck as a mean of shoulders
+        if keypoints[5][2] == 2 or keypoints[6][2] == 2:
+            converted_keypoints[1][2] = 2
+        elif keypoints[5][2] == 1 and keypoints[6][2] == 1:
+            converted_keypoints[1][2] = 1
+        if converted_keypoints[1][0] < 0 or converted_keypoints[1][0] >= w or converted_keypoints[1][1] < 0 or \
+                converted_keypoints[1][1] >= h:
+            converted_keypoints[1][2] = 2
+        return converted_keypoints
+
+
+class Scale:
+    def __init__(self, prob=1, min_scale=0.5, max_scale=1.1, target_dist=0.6):
+        self._prob = prob
+        self._min_scale = min_scale
+        self._max_scale = max_scale
+        self._target_dist = target_dist
+
+    def __call__(self, sample):
+        prob = random.random()
+        scale_multiplier = 1
+        if prob <= self._prob:
+            prob = random.random()
+            scale_multiplier = (self._max_scale - self._min_scale) * prob + self._min_scale
+        label = sample['label']
+        scale_abs = self._target_dist / label['scale_provided']
+        scale = scale_abs * scale_multiplier
+        sample['image'] = cv2.resize(sample['image'], dsize=(0, 0), fx=scale, fy=scale)
+        label['img_height'], label['img_width'], _ = sample['image'].shape
+        sample['mask'] = cv2.resize(sample['mask'], dsize=(0, 0), fx=scale, fy=scale)
+
+        label['objpos'][0] *= scale
+        label['objpos'][1] *= scale
+        for keypoint in sample['label']['keypoints']:
+            keypoint[0] *= scale
+            keypoint[1] *= scale
+        for other_annotation in sample['label']['processed_other_annotations']:
+            other_annotation['objpos'][0] *= scale
+            other_annotation['objpos'][1] *= scale
+            for keypoint in other_annotation['keypoints']:
+                keypoint[0] *= scale
+                keypoint[1] *= scale
+        return sample
+
+
+class Rotate:
+    def __init__(self, pad, max_rotate_degree=40):
+        self._pad = pad
+        self._max_rotate_degree = max_rotate_degree
+
+    def __call__(self, sample):
+        prob = random.random()
+        degree = (prob - 0.5) * 2 * self._max_rotate_degree
+        h, w, _ = sample['image'].shape
+        img_center = (w / 2, h / 2)
+        R = cv2.getRotationMatrix2D(img_center, degree, 1)
+
+        abs_cos = abs(R[0, 0])
+        abs_sin = abs(R[0, 1])
+
+        bound_w = int(h * abs_sin + w * abs_cos)
+        bound_h = int(h * abs_cos + w * abs_sin)
+        dsize = (bound_w, bound_h)
+
+        R[0, 2] += dsize[0] / 2 - img_center[0]
+        R[1, 2] += dsize[1] / 2 - img_center[1]
+        sample['image'] = cv2.warpAffine(sample['image'], R, dsize=dsize,
+                                         borderMode=cv2.BORDER_CONSTANT, borderValue=self._pad)
+        sample['label']['img_height'], sample['label']['img_width'], _ = sample['image'].shape
+        sample['mask'] = cv2.warpAffine(sample['mask'], R, dsize=dsize,
+                                        borderMode=cv2.BORDER_CONSTANT, borderValue=(1, 1, 1))  # border is ok
+        label = sample['label']
+        label['objpos'] = self._rotate(label['objpos'], R)
+        for keypoint in label['keypoints']:
+            point = [keypoint[0], keypoint[1]]
+            point = self._rotate(point, R)
+            keypoint[0], keypoint[1] = point[0], point[1]
+        for other_annotation in label['processed_other_annotations']:
+            for keypoint in other_annotation['keypoints']:
+                point = [keypoint[0], keypoint[1]]
+                point = self._rotate(point, R)
+                keypoint[0], keypoint[1] = point[0], point[1]
+        return sample
+
+    def _rotate(self, point, R):
+        return [R[0, 0] * point[0] + R[0, 1] * point[1] + R[0, 2],
+                R[1, 0] * point[0] + R[1, 1] * point[1] + R[1, 2]]
+
+
+class CropPad:
+    def __init__(self, pad, center_perterb_max=40, crop_x=368, crop_y=368):
+        self._pad = pad
+        self._center_perterb_max = center_perterb_max
+        self._crop_x = crop_x
+        self._crop_y = crop_y
+
+    def __call__(self, sample):
+        prob_x = random.random()
+        prob_y = random.random()
+
+        offset_x = int((prob_x - 0.5) * 2 * self._center_perterb_max)
+        offset_y = int((prob_y - 0.5) * 2 * self._center_perterb_max)
+        label = sample['label']
+        shifted_center = (label['objpos'][0] + offset_x, label['objpos'][1] + offset_y)
+        offset_left = -int(shifted_center[0] - self._crop_x / 2)
+        offset_up = -int(shifted_center[1] - self._crop_y / 2)
+
+        cropped_image = np.empty(shape=(self._crop_y, self._crop_x, 3), dtype=np.uint8)
+        for i in range(3):
+            cropped_image[:, :, i].fill(self._pad[i])
+        cropped_mask = np.empty(shape=(self._crop_y, self._crop_x), dtype=np.uint8)
+        cropped_mask.fill(1)
+
+        image_x_start = int(shifted_center[0] - self._crop_x / 2)
+        image_y_start = int(shifted_center[1] - self._crop_y / 2)
+        image_x_finish = image_x_start + self._crop_x
+        image_y_finish = image_y_start + self._crop_y
+        crop_x_start = 0
+        crop_y_start = 0
+        crop_x_finish = self._crop_x
+        crop_y_finish = self._crop_y
+
+        w, h = label['img_width'], label['img_height']
+        should_crop = True
+        if image_x_start < 0:  # Adjust crop area
+            crop_x_start -= image_x_start
+            image_x_start = 0
+        if image_x_start >= w:
+            should_crop = False
+
+        if image_y_start < 0:
+            crop_y_start -= image_y_start
+            image_y_start = 0
+        if image_y_start >= h:
+            should_crop = False
+
+        if image_x_finish > w:
+            diff = image_x_finish - w
+            image_x_finish -= diff
+            crop_x_finish -= diff
+        if image_x_finish < 0:
+            should_crop = False
+
+        if image_y_finish > h:
+            diff = image_y_finish - h
+            image_y_finish -= diff
+            crop_y_finish -= diff
+        if image_y_finish < 0:
+            should_crop = False
+
+        if should_crop:
+            cropped_image[crop_y_start:crop_y_finish, crop_x_start:crop_x_finish, :] = \
+                sample['image'][image_y_start:image_y_finish, image_x_start:image_x_finish, :]
+            cropped_mask[crop_y_start:crop_y_finish, crop_x_start:crop_x_finish] = \
+                sample['mask'][image_y_start:image_y_finish, image_x_start:image_x_finish]
+
+        sample['image'] = cropped_image
+        sample['mask'] = cropped_mask
+        label['img_width'] = self._crop_x
+        label['img_height'] = self._crop_y
+
+        label['objpos'][0] += offset_left
+        label['objpos'][1] += offset_up
+        for keypoint in label['keypoints']:
+            keypoint[0] += offset_left
+            keypoint[1] += offset_up
+        for other_annotation in label['processed_other_annotations']:
+            for keypoint in other_annotation['keypoints']:
+                keypoint[0] += offset_left
+                keypoint[1] += offset_up
+
+        return sample
+
+    def _inside(self, point, width, height):
+        if point[0] < 0 or point[1] < 0:
+            return False
+        if point[0] >= width or point[1] >= height:
+            return False
+        return True
+
+
+class Flip:
+    def __init__(self, prob=0.5):
+        self._prob = prob
+
+    def __call__(self, sample):
+        prob = random.random()
+        do_flip = prob <= self._prob
+        if not do_flip:
+            return sample
+
+        sample['image'] = cv2.flip(sample['image'], 1)
+        sample['mask'] = cv2.flip(sample['mask'], 1)
+
+        label = sample['label']
+        w = label['img_width']
+        label['objpos'][0] = w - 1 - label['objpos'][0]
+        for keypoint in label['keypoints']:
+            keypoint[0] = w - 1 - keypoint[0]
+        label['keypoints'] = self._swap_left_right(label['keypoints'])
+
+        for other_annotation in label['processed_other_annotations']:
+            other_annotation['objpos'][0] = w - 1 - other_annotation['objpos'][0]
+            for keypoint in other_annotation['keypoints']:
+                keypoint[0] = w - 1 - keypoint[0]
+            other_annotation['keypoints'] = self._swap_left_right(other_annotation['keypoints'])
+
+        return sample
+
+    def _swap_left_right(self, keypoints):
+        right = [2, 3, 4, 8, 9, 10, 14, 16]
+        left = [5, 6, 7, 11, 12, 13, 15, 17]
+        for r, l in zip(right, left):
+            keypoints[r], keypoints[l] = keypoints[l], keypoints[r]
+        return keypoints
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet.py
new file mode 100644
index 0000000000..bf9880d157
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet.py
@@ -0,0 +1,126 @@
+import torch
+from torch import nn
+
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.conv import conv, conv_dw, conv_dw_no_bn
+
+
+class Cpm(nn.Module):
+    def __init__(self, in_channels, out_channels):
+        super().__init__()
+        self.align = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
+        self.trunk = nn.Sequential(
+            conv_dw_no_bn(out_channels, out_channels),
+            conv_dw_no_bn(out_channels, out_channels),
+            conv_dw_no_bn(out_channels, out_channels)
+        )
+        self.conv = conv(out_channels, out_channels, bn=False)
+
+    def forward(self, x):
+        x = self.align(x)
+        x = self.conv(x + self.trunk(x))
+        return x
+
+
+class InitialStage(nn.Module):
+    def __init__(self, num_channels, num_heatmaps, num_pafs):
+        super().__init__()
+        self.trunk = nn.Sequential(
+            conv(num_channels, num_channels, bn=False),
+            conv(num_channels, num_channels, bn=False),
+            conv(num_channels, num_channels, bn=False)
+        )
+        self.heatmaps = nn.Sequential(
+            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
+            conv(512, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+        self.pafs = nn.Sequential(
+            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
+            conv(512, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+
+    def forward(self, x):
+        trunk_features = self.trunk(x)
+        heatmaps = self.heatmaps(trunk_features)
+        pafs = self.pafs(trunk_features)
+        return [heatmaps, pafs]
+
+
+class RefinementStageBlock(nn.Module):
+    def __init__(self, in_channels, out_channels):
+        super().__init__()
+        self.initial = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
+        self.trunk = nn.Sequential(
+            conv(out_channels, out_channels),
+            conv(out_channels, out_channels, dilation=2, padding=2)
+        )
+
+    def forward(self, x):
+        initial_features = self.initial(x)
+        trunk_features = self.trunk(initial_features)
+        return initial_features + trunk_features
+
+
+class RefinementStage(nn.Module):
+    def __init__(self, in_channels, out_channels, num_heatmaps, num_pafs):
+        super().__init__()
+        self.trunk = nn.Sequential(
+            RefinementStageBlock(in_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels)
+        )
+        self.heatmaps = nn.Sequential(
+            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
+            conv(out_channels, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+        self.pafs = nn.Sequential(
+            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
+            conv(out_channels, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+
+    def forward(self, x):
+        trunk_features = self.trunk(x)
+        heatmaps = self.heatmaps(trunk_features)
+        pafs = self.pafs(trunk_features)
+        return [heatmaps, pafs]
+
+
+class PoseEstimationWithMobileNet(nn.Module):
+    def __init__(self, num_refinement_stages=1, num_channels=128, num_heatmaps=19, num_pafs=38, use_stride=False):
+        super().__init__()
+        stride_val = 1
+        if use_stride:
+            stride_val = 2
+        self.model = nn.Sequential(
+            conv(3, 32, stride=2, bias=False),
+            conv_dw(32, 64, stride=stride_val),
+            conv_dw(64, 128, stride=2),
+            conv_dw(128, 128),
+            conv_dw(128, 256, stride=2),
+            conv_dw(256, 256),
+            conv_dw(256, 512),  # conv4_2
+            conv_dw(512, 512, dilation=2, padding=2),
+            conv_dw(512, 512),
+            conv_dw(512, 512),
+            conv_dw(512, 512),
+            conv_dw(512, 512)  # conv5_5
+        )
+        self.cpm = Cpm(512, num_channels)
+
+        self.initial_stage = InitialStage(num_channels, num_heatmaps, num_pafs)
+        self.refinement_stages = nn.ModuleList()
+        for idx in range(num_refinement_stages):
+            self.refinement_stages.append(RefinementStage(num_channels + num_heatmaps + num_pafs, num_channels,
+                                                          num_heatmaps, num_pafs))
+
+    def forward(self, x):
+        backbone_features = self.model(x)
+        backbone_features = self.cpm(backbone_features)
+
+        stages_output = self.initial_stage(backbone_features)
+        for refinement_stage in self.refinement_stages:
+            stages_output.extend(
+                refinement_stage(torch.cat([backbone_features, stages_output[-2], stages_output[-1]], dim=1)))
+
+        return stages_output
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet_v2.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet_v2.py
new file mode 100644
index 0000000000..da3f2016f9
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet_v2.py
@@ -0,0 +1,252 @@
+# 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.
+
+# MobileNetV2 implementation taken from https://github.com/tonylins/pytorch-mobilenet-v2 and modified to work as a
+# backbone for Lightweight Open Pose.
+
+import torch
+from torch import nn
+
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.conv import conv, conv_dw_no_bn
+import math
+
+
+def conv_bn(inp, oup, stride):
+    return nn.Sequential(
+        nn.Conv2d(inp, oup, 3, stride, 1, bias=False),
+        nn.BatchNorm2d(oup),
+        nn.ReLU6(inplace=True)
+    )
+
+
+def conv_1x1_bn(inp, oup):
+    return nn.Sequential(
+        nn.Conv2d(inp, oup, 1, 1, 0, bias=False),
+        nn.BatchNorm2d(oup),
+        nn.ReLU6(inplace=True)
+    )
+
+
+def make_divisible(x, divisible_by=8):
+    import numpy as np
+    return int(np.ceil(x * 1. / divisible_by) * divisible_by)
+
+
+class InvertedResidual(nn.Module):
+    def __init__(self, inp, oup, stride, expand_ratio):
+        super(InvertedResidual, self).__init__()
+        self.stride = stride
+        assert stride in [1, 2]
+
+        hidden_dim = int(inp * expand_ratio)
+        self.use_res_connect = self.stride == 1 and inp == oup
+
+        if expand_ratio == 1:
+            self.conv = nn.Sequential(
+                # dw
+                nn.Conv2d(hidden_dim, hidden_dim, 3, stride, 1, groups=hidden_dim, bias=False),
+                nn.BatchNorm2d(hidden_dim),
+                nn.ReLU6(inplace=True),
+                # pw-linear
+                nn.Conv2d(hidden_dim, oup, 1, 1, 0, bias=False),
+                nn.BatchNorm2d(oup),
+            )
+        else:
+            self.conv = nn.Sequential(
+                # pw
+                nn.Conv2d(inp, hidden_dim, 1, 1, 0, bias=False),
+                nn.BatchNorm2d(hidden_dim),
+                nn.ReLU6(inplace=True),
+                # dw
+                nn.Conv2d(hidden_dim, hidden_dim, 3, stride, 1, groups=hidden_dim, bias=False),
+                nn.BatchNorm2d(hidden_dim),
+                nn.ReLU6(inplace=True),
+                # pw-linear
+                nn.Conv2d(hidden_dim, oup, 1, 1, 0, bias=False),
+                nn.BatchNorm2d(oup),
+            )
+
+    def forward(self, x):
+        if self.use_res_connect:
+            return x + self.conv(x)
+        else:
+            return self.conv(x)
+
+
+class MobileNetV2(nn.Module):
+    def __init__(self, input_size=224, width_mult=1.):
+        super(MobileNetV2, self).__init__()
+        block = InvertedResidual
+        input_channel = 32
+        last_channel = 1280
+        # To make MobileNetV2 output correct dimensions, we change two of the stride settings below according to these
+        # comments below
+        # https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch/issues/17#issuecomment-491518963
+        # https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch/issues/35#issuecomment-508866788
+        inverted_residual_setting = [
+            # t, c, n, s
+            [1, 16, 1, 1],
+            [6, 24, 2, 2],
+            [6, 32, 3, 2],
+            [6, 64, 4, 1],  # s reduced from 2
+            [6, 96, 3, 1],
+            [6, 160, 3, 1],  # s reduced from 2
+            [6, 320, 1, 1],
+        ]
+
+        # building first layer
+        assert input_size % 32 == 0
+        # input_channel = make_divisible(input_channel * width_mult)  # first channel is always 32!
+        self.last_channel = make_divisible(last_channel * width_mult) if width_mult > 1.0 else last_channel
+        self.features = [conv_bn(3, input_channel, 2)]
+        # building inverted residual blocks
+        for t, c, n, s in inverted_residual_setting:
+            output_channel = make_divisible(c * width_mult) if t > 1 else c
+            for i in range(n):
+                if i == 0:
+                    self.features.append(block(input_channel, output_channel, s, expand_ratio=t))
+                else:
+                    self.features.append(block(input_channel, output_channel, 1, expand_ratio=t))
+                input_channel = output_channel
+        # building last several layers
+        self.features.append(conv_1x1_bn(input_channel, self.last_channel))
+        # make it nn.Sequential
+        self.features = nn.Sequential(*self.features)
+
+        self._initialize_weights()
+
+    def forward(self, x):
+        x = self.features(x)
+        return x
+
+    def _initialize_weights(self):
+        for m in self.modules():
+            if isinstance(m, nn.Conv2d):
+                n = m.kernel_size[0] * m.kernel_size[1] * m.out_channels
+                m.weight.data.normal_(0, math.sqrt(2. / n))
+                if m.bias is not None:
+                    m.bias.data.zero_()
+            elif isinstance(m, nn.BatchNorm2d):
+                m.weight.data.fill_(1)
+                m.bias.data.zero_()
+            elif isinstance(m, nn.Linear):
+                n = m.weight.size(1)
+                m.weight.data.normal_(0, 0.01)
+                m.bias.data.zero_()
+
+
+class Cpm(nn.Module):
+    def __init__(self, in_channels, out_channels):
+        super().__init__()
+        self.align = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
+        self.trunk = nn.Sequential(
+            conv_dw_no_bn(out_channels, out_channels),
+            conv_dw_no_bn(out_channels, out_channels),
+            conv_dw_no_bn(out_channels, out_channels)
+        )
+        self.conv = conv(out_channels, out_channels, bn=False)
+
+    def forward(self, x):
+        x = self.align(x)
+        x = self.conv(x + self.trunk(x))
+        return x
+
+
+class InitialStage(nn.Module):
+    def __init__(self, num_channels, num_heatmaps, num_pafs):
+        super().__init__()
+        self.trunk = nn.Sequential(
+            conv(num_channels, num_channels, bn=False),
+            conv(num_channels, num_channels, bn=False),
+            conv(num_channels, num_channels, bn=False)
+        )
+        self.heatmaps = nn.Sequential(
+            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
+            conv(512, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+        self.pafs = nn.Sequential(
+            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
+            conv(512, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+
+    def forward(self, x):
+        trunk_features = self.trunk(x)
+        heatmaps = self.heatmaps(trunk_features)
+        pafs = self.pafs(trunk_features)
+        return [heatmaps, pafs]
+
+
+class RefinementStageBlock(nn.Module):
+    def __init__(self, in_channels, out_channels):
+        super().__init__()
+        self.initial = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
+        self.trunk = nn.Sequential(
+            conv(out_channels, out_channels),
+            conv(out_channels, out_channels, dilation=2, padding=2)
+        )
+
+    def forward(self, x):
+        initial_features = self.initial(x)
+        trunk_features = self.trunk(initial_features)
+        return initial_features + trunk_features
+
+
+class RefinementStage(nn.Module):
+    def __init__(self, in_channels, out_channels, num_heatmaps, num_pafs):
+        super().__init__()
+        self.trunk = nn.Sequential(
+            RefinementStageBlock(in_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels)
+        )
+        self.heatmaps = nn.Sequential(
+            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
+            conv(out_channels, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+        self.pafs = nn.Sequential(
+            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
+            conv(out_channels, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+
+    def forward(self, x):
+        trunk_features = self.trunk(x)
+        heatmaps = self.heatmaps(trunk_features)
+        pafs = self.pafs(trunk_features)
+        return [heatmaps, pafs]
+
+
+class PoseEstimationWithMobileNetV2(nn.Module):
+    def __init__(self, num_refinement_stages=1, num_channels=128, num_heatmaps=19, num_pafs=38, width_mult=1.0):
+        super().__init__()
+
+        self.model = MobileNetV2(width_mult=width_mult)
+        self.cpm = Cpm(1280, num_channels)
+
+        self.initial_stage = InitialStage(num_channels, num_heatmaps, num_pafs)
+        self.refinement_stages = nn.ModuleList()
+        for idx in range(num_refinement_stages):
+            self.refinement_stages.append(RefinementStage(num_channels + num_heatmaps + num_pafs, num_channels,
+                                                          num_heatmaps, num_pafs))
+
+    def forward(self, x):
+        backbone_features = self.model(x)
+        backbone_features = self.cpm(backbone_features)
+        stages_output = self.initial_stage(backbone_features)
+        for refinement_stage in self.refinement_stages:
+            stages_output.extend(
+                refinement_stage(torch.cat([backbone_features, stages_output[-2], stages_output[-1]], dim=1)))
+
+        return stages_output
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_shufflenet.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_shufflenet.py
new file mode 100644
index 0000000000..09ce1be3d7
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_shufflenet.py
@@ -0,0 +1,422 @@
+# 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.
+
+# ShuffleNet implementation taken from https://github.com/jaxony/ShuffleNet and modified to work as a backbone
+# for Lightweight Open Pose. It comes with the MIT license included below.
+
+# MIT License
+#
+# Copyright (c) 2017 Jackson Huang
+#
+# Permission is hereby granted, free of charge, to any person obtaining a copy
+# of this software and associated documentation files (the "Software"), to deal
+# in the Software without restriction, including without limitation the rights
+# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+# copies of the Software, and to permit persons to whom the Software is
+# furnished to do so, subject to the following conditions:
+#
+# The above copyright notice and this permission notice shall be included in all
+# copies or substantial portions of the Software.
+#
+# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+# SOFTWARE.
+
+import torch
+from torch import nn
+
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.conv import conv, conv_dw_no_bn
+from collections import OrderedDict
+import torch.nn.functional as F
+
+
+def conv3x3(in_channels, out_channels, stride=1,
+            padding=1, bias=True, groups=1):
+    """3x3 convolution with padding
+    """
+    return nn.Conv2d(
+        in_channels,
+        out_channels,
+        kernel_size=3,
+        stride=stride,
+        padding=padding,
+        bias=bias,
+        groups=groups)
+
+
+def conv1x1(in_channels, out_channels, groups=1):
+    """1x1 convolution with padding
+    - Normal pointwise convolution When groups == 1
+    - Grouped pointwise convolution when groups > 1
+    """
+    return nn.Conv2d(
+        in_channels,
+        out_channels,
+        kernel_size=1,
+        groups=groups,
+        stride=1)
+
+
+def channel_shuffle(x, groups):
+    batchsize, num_channels, height, width = x.data.size()
+
+    channels_per_group = num_channels // groups
+
+    # reshape
+    x = x.view(batchsize, groups,
+               channels_per_group, height, width)
+
+    # transpose
+    # - contiguous() required if transpose() is used before view().
+    #   See https://github.com/pytorch/pytorch/issues/764
+    x = torch.transpose(x, 1, 2).contiguous()
+
+    # flatten
+    x = x.view(batchsize, -1, height, width)
+
+    return x
+
+
+class ShuffleUnit(nn.Module):
+    def __init__(self, in_channels, out_channels, groups=3,
+                 grouped_conv=True, combine='add'):
+
+        super(ShuffleUnit, self).__init__()
+
+        self.in_channels = in_channels
+        self.out_channels = out_channels
+        self.grouped_conv = grouped_conv
+        self.combine = combine
+        self.groups = groups
+        self.bottleneck_channels = self.out_channels // 4
+
+        # define the type of ShuffleUnit
+        if self.combine == 'add':
+            # ShuffleUnit Figure 2b
+            self.depthwise_stride = 1
+            self._combine_func = self._add
+        elif self.combine == 'concat':
+            # ShuffleUnit Figure 2c
+            self.depthwise_stride = 2
+            self._combine_func = self._concat
+
+            # ensure output of concat has the same channels as
+            # original output channels.
+            self.out_channels -= self.in_channels
+        else:
+            raise ValueError(
+                "Cannot combine tensors with \"{}\" Only \"add\" and \"concat\" are supported".format(self.combine))
+
+        # Use a 1x1 grouped or non-grouped convolution to reduce input channels
+        # to bottleneck channels, as in a ResNet bottleneck module.
+        # NOTE: Do not use group convolution for the first conv1x1 in Stage 2.
+        self.first_1x1_groups = self.groups if grouped_conv else 1
+
+        self.g_conv_1x1_compress = self._make_grouped_conv1x1(
+            self.in_channels,
+            self.bottleneck_channels,
+            self.first_1x1_groups,
+            batch_norm=True,
+            relu=True
+        )
+
+        # 3x3 depthwise convolution followed by batch normalization
+        self.depthwise_conv3x3 = conv3x3(
+            self.bottleneck_channels, self.bottleneck_channels,
+            stride=self.depthwise_stride, groups=self.bottleneck_channels)
+        self.bn_after_depthwise = nn.BatchNorm2d(self.bottleneck_channels)
+
+        # Use 1x1 grouped convolution to expand from
+        # bottleneck_channels to out_channels
+        self.g_conv_1x1_expand = self._make_grouped_conv1x1(
+            self.bottleneck_channels,
+            self.out_channels,
+            self.groups,
+            batch_norm=True,
+            relu=False
+        )
+
+    @staticmethod
+    def _add(x, out):
+        # residual connection
+        return x + out
+
+    @staticmethod
+    def _concat(x, out):
+        # concatenate along channel axis
+        return torch.cat((x, out), 1)
+
+    @staticmethod
+    def _make_grouped_conv1x1(in_channels, out_channels, groups,
+                              batch_norm=True, relu=False):
+
+        modules = OrderedDict()
+
+        conv_ = conv1x1(in_channels, out_channels, groups=groups)
+        modules['conv1x1'] = conv_
+
+        if batch_norm:
+            modules['batch_norm'] = nn.BatchNorm2d(out_channels)
+        if relu:
+            modules['relu'] = nn.ReLU()
+        if len(modules) > 1:
+            return nn.Sequential(modules)
+        else:
+            return conv_
+
+    def forward(self, x):
+        # save for combining later with output
+        residual = x
+
+        if self.combine == 'concat':
+            residual = F.avg_pool2d(residual, kernel_size=3,
+                                    stride=2, padding=1)
+
+        out = self.g_conv_1x1_compress(x)
+        out = channel_shuffle(out, self.groups)
+        out = self.depthwise_conv3x3(out)
+        out = self.bn_after_depthwise(out)
+        out = self.g_conv_1x1_expand(out)
+
+        out = self._combine_func(residual, out)
+        return F.relu(out)
+
+
+class ShuffleNet(nn.Module):
+    """ShuffleNet implementation.
+    """
+
+    def __init__(self, groups=3, in_channels=3):
+        """ShuffleNet constructor.
+        Arguments:
+            groups (int, optional): number of groups to be used in grouped
+                1x1 convolutions in each ShuffleUnit. Default is 3 for best
+                performance according to original paper.
+            in_channels (int, optional): number of channels in the input tensor.
+                Default is 3 for RGB image inputs.
+        """
+        super(ShuffleNet, self).__init__()
+
+        self.groups = groups
+        self.stage_repeats = [3, 7, 3]
+        self.in_channels = in_channels
+
+        # index 0 is invalid and should never be called.
+        # only used for indexing convenience.
+        if groups == 1:
+            self.stage_out_channels = [-1, 24, 144, 288, 576]
+        elif groups == 2:
+            self.stage_out_channels = [-1, 24, 200, 400, 800]
+        elif groups == 3:
+            self.stage_out_channels = [-1, 24, 240, 480, 960]
+        elif groups == 4:
+            self.stage_out_channels = [-1, 24, 272, 544, 1088]
+        elif groups == 8:
+            self.stage_out_channels = [-1, 24, 384, 768, 1536]
+        else:
+            raise ValueError(
+                """{} groups is not supported for
+                   1x1 Grouped Convolutions""".format(groups))
+        # Same as MobileNetV2, to output correct dimensions, we change two of the stride settings below
+        # Stage 1 always has 24 output channels
+        self.conv1 = conv3x3(self.in_channels,
+                             self.stage_out_channels[1],  # stage 1
+                             stride=1)  # stride reduced from 2
+        self.maxpool = nn.MaxPool2d(kernel_size=3, stride=1, padding=1)  # stride reduced from 2
+
+        # Stage 2
+        self.stage2 = self._make_stage(2)
+        # Stage 3
+        self.stage3 = self._make_stage(3)
+        # Stage 4
+        self.stage4 = self._make_stage(4)
+
+        # Global pooling:
+        # Undefined as PyTorch's functional API can be used for on-the-fly
+        # shape inference if input size is not ImageNet's 224x224
+
+        self.init_params()
+
+    def init_params(self):
+        for m in self.modules():
+            if isinstance(m, nn.Conv2d):
+                nn.init.kaiming_normal_(m.weight, mode='fan_out')
+                if m.bias is not None:
+                    nn.init.constant_(m.bias, 0)
+            elif isinstance(m, nn.BatchNorm2d):
+                nn.init.constant_(m.weight, 1)
+                nn.init.constant_(m.bias, 0)
+            elif isinstance(m, nn.Linear):
+                nn.init.normal(m.weight, std=0.001)
+                if m.bias is not None:
+                    nn.init.constant_(m.bias, 0)
+
+    def _make_stage(self, stage):
+        modules = OrderedDict()
+        stage_name = "ShuffleUnit_Stage{}".format(stage)
+
+        # First ShuffleUnit in the stage
+        # 1. non-grouped 1x1 convolution (i.e. pointwise convolution)
+        #   is used in Stage 2. Group convolutions used everywhere else.
+        grouped_conv = stage > 2
+
+        # 2. concatenation unit is always used.
+        first_module = ShuffleUnit(
+            self.stage_out_channels[stage - 1],
+            self.stage_out_channels[stage],
+            groups=self.groups,
+            grouped_conv=grouped_conv,
+            combine='concat'
+        )
+        modules[stage_name + "_0"] = first_module
+
+        # add more ShuffleUnits depending on pre-defined number of repeats
+        for i in range(self.stage_repeats[stage - 2]):
+            name = stage_name + "_{}".format(i + 1)
+            module = ShuffleUnit(
+                self.stage_out_channels[stage],
+                self.stage_out_channels[stage],
+                groups=self.groups,
+                grouped_conv=True,
+                combine='add'
+            )
+            modules[name] = module
+
+        return nn.Sequential(modules)
+
+    def forward(self, x):
+        x = self.conv1(x)
+        x = self.maxpool(x)
+
+        x = self.stage2(x)
+        x = self.stage3(x)
+        x = self.stage4(x)
+
+        # Avg pooling is removed in favor of changing the stride of conv1 + maxpool
+        # With avg pooling, convergence is way too slow based on short tests, but we leave it here for reference
+        # between the original shufflenet and the modifications we made
+        # global average pooling layer
+        # x = F.avg_pool2d(x, x.data.size()[-2:])
+        return x
+
+
+class Cpm(nn.Module):
+    def __init__(self, in_channels, out_channels):
+        super().__init__()
+        self.align = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
+        self.trunk = nn.Sequential(
+            conv_dw_no_bn(out_channels, out_channels),
+            conv_dw_no_bn(out_channels, out_channels),
+            conv_dw_no_bn(out_channels, out_channels)
+        )
+        self.conv = conv(out_channels, out_channels, bn=False)
+
+    def forward(self, x):
+        x = self.align(x)
+        x = self.conv(x + self.trunk(x))
+        return x
+
+
+class InitialStage(nn.Module):
+    def __init__(self, num_channels, num_heatmaps, num_pafs):
+        super().__init__()
+        self.trunk = nn.Sequential(
+            conv(num_channels, num_channels, bn=False),
+            conv(num_channels, num_channels, bn=False),
+            conv(num_channels, num_channels, bn=False)
+        )
+        self.heatmaps = nn.Sequential(
+            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
+            conv(512, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+        self.pafs = nn.Sequential(
+            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
+            conv(512, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+
+    def forward(self, x):
+        trunk_features = self.trunk(x)
+        heatmaps = self.heatmaps(trunk_features)
+        pafs = self.pafs(trunk_features)
+        return [heatmaps, pafs]
+
+
+class RefinementStageBlock(nn.Module):
+    def __init__(self, in_channels, out_channels):
+        super().__init__()
+        self.initial = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
+        self.trunk = nn.Sequential(
+            conv(out_channels, out_channels),
+            conv(out_channels, out_channels, dilation=2, padding=2)
+        )
+
+    def forward(self, x):
+        initial_features = self.initial(x)
+        trunk_features = self.trunk(initial_features)
+        return initial_features + trunk_features
+
+
+class RefinementStage(nn.Module):
+    def __init__(self, in_channels, out_channels, num_heatmaps, num_pafs):
+        super().__init__()
+        self.trunk = nn.Sequential(
+            RefinementStageBlock(in_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels),
+            RefinementStageBlock(out_channels, out_channels)
+        )
+        self.heatmaps = nn.Sequential(
+            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
+            conv(out_channels, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+        self.pafs = nn.Sequential(
+            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
+            conv(out_channels, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
+        )
+
+    def forward(self, x):
+        trunk_features = self.trunk(x)
+        heatmaps = self.heatmaps(trunk_features)
+        pafs = self.pafs(trunk_features)
+        return [heatmaps, pafs]
+
+
+class PoseEstimationWithShuffleNet(nn.Module):
+    def __init__(self, num_refinement_stages=1, num_channels=128, num_heatmaps=19, num_pafs=38, groups=3):
+        super().__init__()
+
+        self.model = ShuffleNet(groups=groups, in_channels=3)
+        self.cpm = Cpm(self.model.stage_out_channels[-1], num_channels)
+
+        self.initial_stage = InitialStage(num_channels, num_heatmaps, num_pafs)
+        self.refinement_stages = nn.ModuleList()
+        for idx in range(num_refinement_stages):
+            self.refinement_stages.append(RefinementStage(num_channels + num_heatmaps + num_pafs, num_channels,
+                                                          num_heatmaps, num_pafs))
+
+    def forward(self, x):
+        backbone_features = self.model(x)
+        backbone_features = self.cpm(backbone_features)
+
+        stages_output = self.initial_stage(backbone_features)
+        for refinement_stage in self.refinement_stages:
+            stages_output.extend(
+                refinement_stage(torch.cat([backbone_features, stages_output[-2], stages_output[-1]], dim=1)))
+
+        return stages_output
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/conv.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/conv.py
new file mode 100644
index 0000000000..259e4aa021
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/conv.py
@@ -0,0 +1,32 @@
+from torch import nn
+
+
+def conv(in_channels, out_channels, kernel_size=3, padding=1, bn=True, dilation=1, stride=1, relu=True, bias=True):
+    modules = [nn.Conv2d(in_channels, out_channels, kernel_size, stride, padding, dilation, bias=bias)]
+    if bn:
+        modules.append(nn.BatchNorm2d(out_channels))
+    if relu:
+        modules.append(nn.ReLU(inplace=True))
+    return nn.Sequential(*modules)
+
+
+def conv_dw(in_channels, out_channels, kernel_size=3, padding=1, stride=1, dilation=1):
+    return nn.Sequential(
+        nn.Conv2d(in_channels, in_channels, kernel_size, stride, padding, dilation=dilation, groups=in_channels,
+                  bias=False),
+        nn.BatchNorm2d(in_channels),
+        nn.ReLU(inplace=True),
+        nn.Conv2d(in_channels, out_channels, 1, 1, 0, bias=False),
+        nn.BatchNorm2d(out_channels),
+        nn.ReLU(inplace=True),
+    )
+
+
+def conv_dw_no_bn(in_channels, out_channels, kernel_size=3, padding=1, stride=1, dilation=1):
+    return nn.Sequential(
+        nn.Conv2d(in_channels, in_channels, kernel_size, stride, padding, dilation=dilation, groups=in_channels,
+                  bias=False),
+        nn.ELU(inplace=True),
+        nn.Conv2d(in_channels, out_channels, 1, 1, 0, bias=False),
+        nn.ELU(inplace=True),
+    )
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/get_parameters.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/get_parameters.py
new file mode 100644
index 0000000000..bf5250b9de
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/get_parameters.py
@@ -0,0 +1,21 @@
+from torch import nn
+
+
+def get_parameters(model, predicate):
+    for module in model.modules():
+        for param_name, param in module.named_parameters():
+            if predicate(module, param_name):
+                yield param
+
+
+def get_parameters_conv(model, name):
+    return get_parameters(model, lambda m, p: isinstance(m, nn.Conv2d) and m.groups == 1 and p == name)
+
+
+def get_parameters_conv_depthwise(model, name):
+    return get_parameters(model, lambda m, p: isinstance(m, nn.Conv2d) and m.groups == m.in_channels and
+                          m.in_channels == m.out_channels and p == name)
+
+
+def get_parameters_bn(model, name):
+    return get_parameters(model, lambda m, p: isinstance(m, nn.BatchNorm2d) and p == name)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/keypoints.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/keypoints.py
new file mode 100644
index 0000000000..2a59ff7bda
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/keypoints.py
@@ -0,0 +1,159 @@
+import math
+import numpy as np
+from operator import itemgetter
+
+BODY_PARTS_KPT_IDS = [[1, 2], [1, 5], [2, 3], [3, 4], [5, 6], [6, 7], [1, 8], [8, 9], [9, 10], [1, 11],
+                      [11, 12], [12, 13], [1, 0], [0, 14], [14, 16], [0, 15], [15, 17], [2, 16], [5, 17]]
+BODY_PARTS_PAF_IDS = ([12, 13], [20, 21], [14, 15], [16, 17], [22, 23], [24, 25], [0, 1], [2, 3], [4, 5],
+                      [6, 7], [8, 9], [10, 11], [28, 29], [30, 31], [34, 35], [32, 33], [36, 37], [18, 19], [26, 27])
+
+
+def extract_keypoints(heatmap, all_keypoints, total_keypoint_num):
+    heatmap[heatmap < 0.1] = 0
+    heatmap_with_borders = np.pad(heatmap, [(2, 2), (2, 2)], mode='constant')
+    heatmap_center = heatmap_with_borders[1:heatmap_with_borders.shape[0] - 1, 1:heatmap_with_borders.shape[1] - 1]
+    heatmap_left = heatmap_with_borders[1:heatmap_with_borders.shape[0] - 1, 2:heatmap_with_borders.shape[1]]
+    heatmap_right = heatmap_with_borders[1:heatmap_with_borders.shape[0] - 1, 0:heatmap_with_borders.shape[1] - 2]
+    heatmap_up = heatmap_with_borders[2:heatmap_with_borders.shape[0], 1:heatmap_with_borders.shape[1] - 1]
+    heatmap_down = heatmap_with_borders[0:heatmap_with_borders.shape[0] - 2, 1:heatmap_with_borders.shape[1] - 1]
+
+    heatmap_peaks = (heatmap_center > heatmap_left) & \
+                    (heatmap_center > heatmap_right) & \
+                    (heatmap_center > heatmap_up) & \
+                    (heatmap_center > heatmap_down)
+    heatmap_peaks = heatmap_peaks[1:heatmap_center.shape[0] - 1, 1:heatmap_center.shape[1] - 1]
+    keypoints = list(zip(np.nonzero(heatmap_peaks)[1], np.nonzero(heatmap_peaks)[0]))  # (w, h)
+    keypoints = sorted(keypoints, key=itemgetter(0))
+
+    suppressed = np.zeros(len(keypoints), np.uint8)
+    keypoints_with_score_and_id = []
+    keypoint_num = 0
+    for i in range(len(keypoints)):
+        if suppressed[i]:
+            continue
+        for j in range(i + 1, len(keypoints)):
+            if math.sqrt((keypoints[i][0] - keypoints[j][0]) ** 2 +
+                         (keypoints[i][1] - keypoints[j][1]) ** 2) < 6:
+                suppressed[j] = 1
+        keypoint_with_score_and_id = (keypoints[i][0], keypoints[i][1], heatmap[keypoints[i][1], keypoints[i][0]],
+                                      total_keypoint_num + keypoint_num)
+        keypoints_with_score_and_id.append(keypoint_with_score_and_id)
+        keypoint_num += 1
+    all_keypoints.append(keypoints_with_score_and_id)
+    return keypoint_num
+
+
+def connections_nms(a_idx, b_idx, affinity_scores):
+    # From all retrieved connections that share the same starting/ending keypoints leave only the top-scoring ones.
+    order = affinity_scores.argsort()[::-1]
+    affinity_scores = affinity_scores[order]
+    a_idx = a_idx[order]
+    b_idx = b_idx[order]
+    idx = []
+    has_kpt_a = set()
+    has_kpt_b = set()
+    for t, (i, j) in enumerate(zip(a_idx, b_idx)):
+        if i not in has_kpt_a and j not in has_kpt_b:
+            idx.append(t)
+            has_kpt_a.add(i)
+            has_kpt_b.add(j)
+    idx = np.asarray(idx, dtype=np.int32)
+    return a_idx[idx], b_idx[idx], affinity_scores[idx]
+
+
+def group_keypoints(all_keypoints_by_type, pafs, pose_entry_size=20, min_paf_score=0.05):
+    pose_entries = []
+    all_keypoints = np.array([item for sublist in all_keypoints_by_type for item in sublist])
+    points_per_limb = 10
+    grid = np.arange(points_per_limb, dtype=np.float32).reshape(1, -1, 1)
+    all_keypoints_by_type = [np.array(keypoints, np.float32) for keypoints in all_keypoints_by_type]
+    for part_id in range(len(BODY_PARTS_PAF_IDS)):
+        part_pafs = pafs[:, :, BODY_PARTS_PAF_IDS[part_id]]
+        kpts_a = all_keypoints_by_type[BODY_PARTS_KPT_IDS[part_id][0]]
+        kpts_b = all_keypoints_by_type[BODY_PARTS_KPT_IDS[part_id][1]]
+        n = len(kpts_a)
+        m = len(kpts_b)
+        if n == 0 or m == 0:
+            continue
+
+        # Get vectors between all pairs of keypoints, i.e. candidate limb vectors.
+        a = kpts_a[:, :2]
+        a = np.broadcast_to(a[None], (m, n, 2))
+        b = kpts_b[:, :2]
+        vec_raw = (b[:, None, :] - a).reshape(-1, 1, 2)
+
+        # Sample points along every candidate limb vector.
+        steps = (1 / (points_per_limb - 1) * vec_raw)
+        points = steps * grid + a.reshape(-1, 1, 2)
+        points = points.round().astype(dtype=np.int32)
+        x = points[..., 0].ravel()
+        y = points[..., 1].ravel()
+
+        # Compute affinity score between candidate limb vectors and part affinity field.
+        field = part_pafs[y, x].reshape(-1, points_per_limb, 2)
+        vec_norm = np.linalg.norm(vec_raw, ord=2, axis=-1, keepdims=True)
+        vec = vec_raw / (vec_norm + 1e-6)
+        affinity_scores = (field * vec).sum(-1).reshape(-1, points_per_limb)
+        valid_affinity_scores = affinity_scores > min_paf_score
+        valid_num = valid_affinity_scores.sum(1)
+        affinity_scores = (affinity_scores * valid_affinity_scores).sum(1) / (valid_num + 1e-6)
+        success_ratio = valid_num / points_per_limb
+
+        # Get a list of limbs according to the obtained affinity score.
+        valid_limbs = np.where(np.logical_and(affinity_scores > 0, success_ratio > 0.8))[0]
+        if len(valid_limbs) == 0:
+            continue
+        b_idx, a_idx = np.divmod(valid_limbs, n)
+        affinity_scores = affinity_scores[valid_limbs]
+
+        # Suppress incompatible connections.
+        a_idx, b_idx, affinity_scores = connections_nms(a_idx, b_idx, affinity_scores)
+        connections = list(zip(kpts_a[a_idx, 3].astype(np.int32),
+                               kpts_b[b_idx, 3].astype(np.int32),
+                               affinity_scores))
+        if len(connections) == 0:
+            continue
+
+        if part_id == 0:
+            pose_entries = [np.ones(pose_entry_size) * -1 for _ in range(len(connections))]
+            for i in range(len(connections)):
+                pose_entries[i][BODY_PARTS_KPT_IDS[0][0]] = connections[i][0]
+                pose_entries[i][BODY_PARTS_KPT_IDS[0][1]] = connections[i][1]
+                pose_entries[i][-1] = 2
+                pose_entries[i][-2] = np.sum(all_keypoints[connections[i][0:2], 2]) + connections[i][2]
+        elif part_id == 17 or part_id == 18:
+            kpt_a_id = BODY_PARTS_KPT_IDS[part_id][0]
+            kpt_b_id = BODY_PARTS_KPT_IDS[part_id][1]
+            for i in range(len(connections)):
+                for j in range(len(pose_entries)):
+                    if pose_entries[j][kpt_a_id] == connections[i][0] and pose_entries[j][kpt_b_id] == -1:
+                        pose_entries[j][kpt_b_id] = connections[i][1]
+                    elif pose_entries[j][kpt_b_id] == connections[i][1] and pose_entries[j][kpt_a_id] == -1:
+                        pose_entries[j][kpt_a_id] = connections[i][0]
+            continue
+        else:
+            kpt_a_id = BODY_PARTS_KPT_IDS[part_id][0]
+            kpt_b_id = BODY_PARTS_KPT_IDS[part_id][1]
+            for i in range(len(connections)):
+                num = 0
+                for j in range(len(pose_entries)):
+                    if pose_entries[j][kpt_a_id] == connections[i][0]:
+                        pose_entries[j][kpt_b_id] = connections[i][1]
+                        num += 1
+                        pose_entries[j][-1] += 1
+                        pose_entries[j][-2] += all_keypoints[connections[i][1], 2] + connections[i][2]
+                if num == 0:
+                    pose_entry = np.ones(pose_entry_size) * -1
+                    pose_entry[kpt_a_id] = connections[i][0]
+                    pose_entry[kpt_b_id] = connections[i][1]
+                    pose_entry[-1] = 2
+                    pose_entry[-2] = np.sum(all_keypoints[connections[i][0:2], 2]) + connections[i][2]
+                    pose_entries.append(pose_entry)
+
+    filtered_entries = []
+    for i in range(len(pose_entries)):
+        if pose_entries[i][-1] < 3 or (pose_entries[i][-2] / pose_entries[i][-1] < 0.2):
+            continue
+        filtered_entries.append(pose_entries[i])
+    pose_entries = np.asarray(filtered_entries)
+    return pose_entries, all_keypoints
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/load_state.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/load_state.py
new file mode 100644
index 0000000000..d23bc0d2fd
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/load_state.py
@@ -0,0 +1,35 @@
+import collections
+
+
+def load_state(net, checkpoint):
+    try:
+        source_state = checkpoint['state_dict']
+    except KeyError:
+        source_state = checkpoint
+    target_state = net.state_dict()
+    new_target_state = collections.OrderedDict()
+    for target_key, target_value in target_state.items():
+        if target_key in source_state and source_state[target_key].size() == target_state[target_key].size():
+            new_target_state[target_key] = source_state[target_key]
+        else:
+            new_target_state[target_key] = target_state[target_key]
+            # print('[WARNING] Not found pre-trained parameters for {}'.format(target_key))
+
+    net.load_state_dict(new_target_state)
+
+
+def load_from_mobilenet(net, checkpoint):
+    source_state = checkpoint['state_dict']
+    target_state = net.state_dict()
+    new_target_state = collections.OrderedDict()
+    for target_key, target_value in target_state.items():
+        k = target_key
+        if k.find('model') != -1:
+            k = k.replace('model', 'module.model')
+        if k in source_state and source_state[k].size() == target_state[target_key].size():
+            new_target_state[target_key] = source_state[k]
+        else:
+            new_target_state[target_key] = target_state[target_key]
+            # print('[WARNING] Not found pre-trained parameters for {}'.format(target_key))
+
+    net.load_state_dict(new_target_state)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/loss.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/loss.py
new file mode 100644
index 0000000000..88930181ce
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/loss.py
@@ -0,0 +1,5 @@
+def l2_loss(input, target, mask, batch_size):
+    loss = (input - target) * mask
+    loss = (loss * loss) / 2 / batch_size
+
+    return loss.sum()
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/one_euro_filter.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/one_euro_filter.py
new file mode 100644
index 0000000000..4ef6ffc3f0
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/one_euro_filter.py
@@ -0,0 +1,51 @@
+import math
+
+
+def get_alpha(rate=30, cutoff=1):
+    tau = 1 / (2 * math.pi * cutoff)
+    te = 1 / rate
+    return 1 / (1 + tau / te)
+
+
+class LowPassFilter:
+    def __init__(self):
+        self.x_previous = None
+
+    def __call__(self, x, alpha=0.5):
+        if self.x_previous is None:
+            self.x_previous = x
+            return x
+        x_filtered = alpha * x + (1 - alpha) * self.x_previous
+        self.x_previous = x_filtered
+        return x_filtered
+
+
+class OneEuroFilter:
+    def __init__(self, freq=15, mincutoff=1, beta=0.05, dcutoff=1):
+        self.freq = freq
+        self.mincutoff = mincutoff
+        self.beta = beta
+        self.dcutoff = dcutoff
+        self.filter_x = LowPassFilter()
+        self.filter_dx = LowPassFilter()
+        self.x_previous = None
+        self.dx = None
+
+    def __call__(self, x):
+        if self.dx is None:
+            self.dx = 0
+        else:
+            self.dx = (x - self.x_previous) * self.freq
+        dx_smoothed = self.filter_dx(self.dx, get_alpha(self.freq, self.dcutoff))
+        cutoff = self.mincutoff + self.beta * abs(dx_smoothed)
+        x_filtered = self.filter_x(x, get_alpha(self.freq, cutoff))
+        self.x_previous = x
+        return x_filtered
+
+
+if __name__ == '__main__':
+    filter = OneEuroFilter(freq=15, beta=0.1)
+    for val in range(10):
+        x = val + (-1) ** (val % 2)
+        x_filtered = filter(x)
+        print(x_filtered, x)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/make_val_subset.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/make_val_subset.py
new file mode 100644
index 0000000000..7b02609268
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/make_val_subset.py
@@ -0,0 +1,43 @@
+import json
+import random
+
+
+def make_val_subset(labels, output_path="val_subset.json", num_images=250):
+    """
+    :param labels: path to json with keypoints val labels
+    :param output_path: name of output file with subset of val labels, defaults to "val_subset.json"
+    :param num_images: number of images in subset, defaults to 250
+    """
+    with open(labels, 'r') as f:
+        data = json.load(f)
+
+    random.seed(0)
+    total_val_images = 5000
+    idxs = list(range(total_val_images))
+    random.shuffle(idxs)
+
+    images_by_id = {}
+    for idx in idxs[:num_images]:
+        images_by_id[data['images'][idx]['id']] = data['images'][idx]
+
+    annotations_by_image_id = {}
+    for annotation in data['annotations']:
+        if annotation['image_id'] in images_by_id:
+            if not annotation['image_id'] in annotations_by_image_id:
+                annotations_by_image_id[annotation['image_id']] = []
+            annotations_by_image_id[annotation['image_id']].append(annotation)
+
+    subset = {
+        'info': data['info'],
+        'licenses': data['licenses'],
+        'images': [],
+        'annotations': [],
+        'categories': data['categories']
+    }
+    for image_id, image in images_by_id.items():
+        subset['images'].append(image)
+        if image_id in annotations_by_image_id:  # image has at least 1 annotation
+            subset['annotations'].extend(annotations_by_image_id[image_id])
+
+    with open(output_path, 'w') as f:
+        json.dump(subset, f, indent=4)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/prepare_train_labels.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/prepare_train_labels.py
new file mode 100644
index 0000000000..8fe1e36a4e
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/prepare_train_labels.py
@@ -0,0 +1,122 @@
+import json
+import pickle
+
+
+def prepare_annotations(annotations_per_image, images_info, net_input_size):
+    """Prepare labels for training. For each annotated person calculates center
+    to perform crop around it during the training. Also converts data to the internal format.
+
+    :param annotations_per_image: all annotations for specified image id
+    :param images_info: auxiliary information about all images
+    :param net_input_size: network input size during training
+    :return: list of prepared annotations
+    """
+    prepared_annotations = []
+    for _, annotations in annotations_per_image.items():
+        previous_centers = []
+        for annotation in annotations[0]:
+            if annotation['num_keypoints'] < 5 or annotation['area'] < 32 * 32:
+                continue
+            person_center = [annotation['bbox'][0] + annotation['bbox'][2] / 2,
+                             annotation['bbox'][1] + annotation['bbox'][3] / 2]
+            is_close = False
+            for previous_center in previous_centers:
+                distance_to_previous = ((person_center[0] - previous_center[0]) ** 2 +
+                                        (person_center[1] - previous_center[1]) ** 2) ** 0.5
+                if distance_to_previous < previous_center[2] * 0.3:
+                    is_close = True
+                    break
+            if is_close:
+                continue
+
+            prepared_annotation = {
+                'img_paths': images_info[annotation['image_id']]['file_name'],
+                'img_width': images_info[annotation['image_id']]['width'],
+                'img_height': images_info[annotation['image_id']]['height'],
+                'objpos': person_center,
+                'image_id': annotation['image_id'],
+                'bbox': annotation['bbox'],
+                'segment_area': annotation['area'],
+                'scale_provided': annotation['bbox'][3] / net_input_size,
+                'num_keypoints': annotation['num_keypoints'],
+                'segmentations': annotations[1]
+            }
+
+            keypoints = []
+            for i in range(len(annotation['keypoints']) // 3):
+                keypoint = [annotation['keypoints'][i * 3], annotation['keypoints'][i * 3 + 1], 2]
+                if annotation['keypoints'][i * 3 + 2] == 1:
+                    keypoint[2] = 0
+                elif annotation['keypoints'][i * 3 + 2] == 2:
+                    keypoint[2] = 1
+                keypoints.append(keypoint)
+            prepared_annotation['keypoints'] = keypoints
+
+            prepared_other_annotations = []
+            for other_annotation in annotations[0]:
+                if other_annotation == annotation:
+                    continue
+
+                prepared_other_annotation = {
+                    'objpos': [other_annotation['bbox'][0] + other_annotation['bbox'][2] / 2,
+                               other_annotation['bbox'][1] + other_annotation['bbox'][3] / 2],
+                    'bbox': other_annotation['bbox'],
+                    'segment_area': other_annotation['area'],
+                    'scale_provided': other_annotation['bbox'][3] / net_input_size,
+                    'num_keypoints': other_annotation['num_keypoints']
+                }
+
+                keypoints = []
+                for i in range(len(other_annotation['keypoints']) // 3):
+                    keypoint = [other_annotation['keypoints'][i * 3], other_annotation['keypoints'][i * 3 + 1], 2]
+                    if other_annotation['keypoints'][i * 3 + 2] == 1:
+                        keypoint[2] = 0
+                    elif other_annotation['keypoints'][i * 3 + 2] == 2:
+                        keypoint[2] = 1
+                    keypoints.append(keypoint)
+                prepared_other_annotation['keypoints'] = keypoints
+                prepared_other_annotations.append(prepared_other_annotation)
+
+            prepared_annotation['processed_other_annotations'] = prepared_other_annotations
+            prepared_annotations.append(prepared_annotation)
+
+            previous_centers.append((person_center[0], person_center[1], annotation['bbox'][2], annotation['bbox'][3]))
+    return prepared_annotations
+
+
+def convert_annotations(labels, output_path="prepared_train_annotation.pkl", net_input_size=368):
+    """
+    :param labels: path to json with keypoints train labels
+    :param output_path: name of output file with prepared keypoints annotation, defaults to
+     "prepared_train_annotation.pkl"
+    :param net_input_size: network input size, defaults to 368
+    """
+    with open(labels, 'r') as f:
+        data = json.load(f)
+
+    annotations_per_image_mapping = {}
+    for annotation in data['annotations']:
+        if annotation['num_keypoints'] != 0 and not annotation['iscrowd']:
+            if annotation['image_id'] not in annotations_per_image_mapping:
+                annotations_per_image_mapping[annotation['image_id']] = [[], []]
+            annotations_per_image_mapping[annotation['image_id']][0].append(annotation)
+
+    crowd_segmentations_per_image_mapping = {}
+    for annotation in data['annotations']:
+        if annotation['iscrowd']:
+            if annotation['image_id'] not in crowd_segmentations_per_image_mapping:
+                crowd_segmentations_per_image_mapping[annotation['image_id']] = []
+            crowd_segmentations_per_image_mapping[annotation['image_id']].append(annotation['segmentation'])
+
+    for image_id, crowd_segmentations in crowd_segmentations_per_image_mapping.items():
+        if image_id in annotations_per_image_mapping:
+            annotations_per_image_mapping[image_id][1] = crowd_segmentations
+
+    images_info = {}
+    for image_info in data['images']:
+        images_info[image_info['id']] = image_info
+
+    prepared_annotations = prepare_annotations(annotations_per_image_mapping, images_info, net_input_size)
+
+    with open(output_path, 'wb') as f:
+        pickle.dump(prepared_annotations, f)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/val.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/val.py
new file mode 100644
index 0000000000..0958170791
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/val.py
@@ -0,0 +1,161 @@
+import cv2
+import json
+import math
+import numpy as np
+from pycocotools.coco import COCO
+from pycocotools.cocoeval import COCOeval
+
+import torch
+
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.datasets.coco import CocoValDataset
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.keypoints import \
+    extract_keypoints, group_keypoints
+
+
+def run_coco_eval(gt_file_path, dt_file_path, verbose=False):
+    annotation_type = 'keypoints'
+    if verbose:
+        print('Running test for {} results.'.format(annotation_type))
+
+    coco_gt = COCO(gt_file_path)
+    coco_dt = coco_gt.loadRes(dt_file_path)
+
+    result = COCOeval(coco_gt, coco_dt, annotation_type)
+    result.evaluate()
+    result.accumulate()
+    result.summarize()
+    return result
+
+
+def normalize(img, img_mean, img_scale):
+    img = np.array(img, dtype=np.float32)
+    img = (img - img_mean) * img_scale
+    return img
+
+
+def pad_width(img, stride, pad_value, min_dims):
+    h, w, _ = img.shape
+    h = min(min_dims[0], h)
+    min_dims[0] = math.ceil(min_dims[0] / float(stride)) * stride
+    min_dims[1] = max(min_dims[1], w)
+    min_dims[1] = math.ceil(min_dims[1] / float(stride)) * stride
+    pad = []
+    pad.append(int(math.floor((min_dims[0] - h) / 2.0)))
+    pad.append(int(math.floor((min_dims[1] - w) / 2.0)))
+    pad.append(int(min_dims[0] - h - pad[0]))
+    pad.append(int(min_dims[1] - w - pad[1]))
+    padded_img = cv2.copyMakeBorder(img, pad[0], pad[2], pad[1], pad[3],
+                                    cv2.BORDER_CONSTANT, value=pad_value)
+    return padded_img, pad
+
+
+def convert_to_coco_format(pose_entries, all_keypoints):
+    coco_keypoints = []
+    scores = []
+    for n in range(len(pose_entries)):
+        if len(pose_entries[n]) == 0:
+            continue
+        keypoints = [0] * 17 * 3
+        to_coco_map = [0, -1, 6, 8, 10, 5, 7, 9, 12, 14, 16, 11, 13, 15, 2, 1, 4, 3]
+        person_score = pose_entries[n][-2]
+        position_id = -1
+        for keypoint_id in pose_entries[n][:-2]:
+            position_id += 1
+            if position_id == 1:  # no 'neck' in COCO
+                continue
+
+            cx, cy, score, visibility = 0, 0, 0, 0  # keypoint not found
+            if keypoint_id != -1:
+                cx, cy, score = all_keypoints[int(keypoint_id), 0:3]
+                cx = cx + 0.5
+                cy = cy + 0.5
+                visibility = 1
+            keypoints[to_coco_map[position_id] * 3 + 0] = cx
+            keypoints[to_coco_map[position_id] * 3 + 1] = cy
+            keypoints[to_coco_map[position_id] * 3 + 2] = visibility
+        coco_keypoints.append(keypoints)
+        scores.append(person_score * max(0, (pose_entries[n][-1] - 1)))  # -1 for 'neck'
+    return coco_keypoints, scores
+
+
+def infer(net, img, scales, base_height, stride, pad_value=(0, 0, 0), img_mean=(128, 128, 128), img_scale=1 / 256):
+    normed_img = normalize(img, img_mean, img_scale)
+    height, width, _ = normed_img.shape
+    scales_ratios = [scale * base_height / float(height) for scale in scales]
+    avg_heatmaps = np.zeros((height, width, 19), dtype=np.float32)
+    avg_pafs = np.zeros((height, width, 38), dtype=np.float32)
+
+    for ratio in scales_ratios:
+        scaled_img = cv2.resize(normed_img, (0, 0), fx=ratio, fy=ratio, interpolation=cv2.INTER_CUBIC)
+        min_dims = [base_height, max(scaled_img.shape[1], base_height)]
+        padded_img, pad = pad_width(scaled_img, stride, pad_value, min_dims)
+
+        tensor_img = torch.from_numpy(padded_img).permute(2, 0, 1).unsqueeze(0).float().cuda()
+        stages_output = net(tensor_img)
+
+        stage2_heatmaps = stages_output[-2]
+        heatmaps = np.transpose(stage2_heatmaps.squeeze().cpu().data.numpy(), (1, 2, 0))
+        heatmaps = cv2.resize(heatmaps, (0, 0), fx=stride, fy=stride, interpolation=cv2.INTER_CUBIC)
+        heatmaps = heatmaps[pad[0]:heatmaps.shape[0] - pad[2], pad[1]:heatmaps.shape[1] - pad[3]:, :]
+        heatmaps = cv2.resize(heatmaps, (width, height), interpolation=cv2.INTER_CUBIC)
+        avg_heatmaps = avg_heatmaps + heatmaps / len(scales_ratios)
+
+        stage2_pafs = stages_output[-1]
+        pafs = np.transpose(stage2_pafs.squeeze().cpu().data.numpy(), (1, 2, 0))
+        pafs = cv2.resize(pafs, (0, 0), fx=stride, fy=stride, interpolation=cv2.INTER_CUBIC)
+        pafs = pafs[pad[0]:pafs.shape[0] - pad[2], pad[1]:pafs.shape[1] - pad[3], :]
+        pafs = cv2.resize(pafs, (width, height), interpolation=cv2.INTER_CUBIC)
+        avg_pafs = avg_pafs + pafs / len(scales_ratios)
+
+    return avg_heatmaps, avg_pafs
+
+
+def evaluate(labels, output_name, images_folder, net, multiscale=False, visualize=False):
+    net = net.cuda().eval()
+    base_height = 368
+    scales = [1]
+    if multiscale:
+        scales = [0.5, 1.0, 1.5, 2.0]
+    stride = 8
+
+    dataset = CocoValDataset(labels, images_folder)
+    coco_result = []
+    for sample in dataset:
+        file_name = sample['file_name']
+        img = sample['img']
+
+        avg_heatmaps, avg_pafs = infer(net, img, scales, base_height, stride)
+
+        total_keypoints_num = 0
+        all_keypoints_by_type = []
+        for kpt_idx in range(18):  # 19th for bg
+            total_keypoints_num += extract_keypoints(avg_heatmaps[:, :, kpt_idx], all_keypoints_by_type,
+                                                     total_keypoints_num)
+
+        pose_entries, all_keypoints = group_keypoints(all_keypoints_by_type, avg_pafs)
+        coco_keypoints, scores = convert_to_coco_format(pose_entries, all_keypoints)
+
+        image_id = int(file_name[0:file_name.rfind('.')])
+        for idx in range(len(coco_keypoints)):
+            coco_result.append({
+                'image_id': image_id,
+                'category_id': 1,  # person
+                'keypoints': coco_keypoints[idx],
+                'score': scores[idx]
+            })
+
+        if visualize:
+            for keypoints in coco_keypoints:
+                for idx in range(len(keypoints) // 3):
+                    cv2.circle(img, (int(keypoints[idx * 3]), int(keypoints[idx * 3 + 1])),
+                               3, (255, 0, 255), -1)
+            print(coco_keypoints)
+            cv2.imshow('keypoints', img)
+            key = cv2.waitKey()
+            if key == 27:  # esc
+                return
+
+    with open(output_name, 'w') as f:
+        json.dump(coco_result, f, indent=4)
+
+    run_coco_eval(labels, output_name)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/filtered_pose.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/filtered_pose.py
new file mode 100644
index 0000000000..680acb428a
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/filtered_pose.py
@@ -0,0 +1,22 @@
+# 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.engine.target import Pose
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.one_euro_filter import OneEuroFilter
+
+
+class FilteredPose(Pose):
+    def __init__(self, keypoints, confidence):
+        super().__init__(keypoints, confidence)
+        self.filters = [[OneEuroFilter(), OneEuroFilter()] for _ in range(self.num_kpts)]
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/utilities.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/utilities.py
new file mode 100644
index 0000000000..d26dc49a0e
--- /dev/null
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/utilities.py
@@ -0,0 +1,153 @@
+# 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 numpy as np
+import cv2
+from opendr.engine.target import Pose
+
+# More information on body-part id naming on target.py - Pose class.
+# For in-depth explanation of BODY_PARTS_KPT_IDS and BODY_PARTS_PAF_IDS see
+#  https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch/blob/master/TRAIN-ON-CUSTOM-DATASET.md
+BODY_PARTS_KPT_IDS = [[1, 2], [1, 5], [2, 3], [3, 4], [5, 6], [6, 7], [1, 8], [8, 9], [9, 10], [1, 11],
+                      [11, 12], [12, 13], [1, 0], [0, 14], [14, 16], [0, 15], [15, 17], [2, 16], [5, 17]]
+BODY_PARTS_PAF_IDS = ([12, 13], [20, 21], [14, 15], [16, 17], [22, 23], [24, 25], [0, 1], [2, 3], [4, 5],
+                      [6, 7], [8, 9], [10, 11], [28, 29], [30, 31], [34, 35], [32, 33], [36, 37], [18, 19],
+                      [26, 27])
+sigmas = np.array([.26, .79, .79, .72, .62, .79, .72, .62, 1.07, .87, .89, 1.07, .87, .89, .25, .25, .35, .35],
+                  dtype=np.float32) / 10.0
+vars_ = (sigmas * 2) ** 2
+last_id = -1
+color = [0, 224, 255]
+
+
+def get_bbox(pose):
+    """
+    Return a cv2 bounding box based on the keypoints of the pose provided.
+
+    :param pose: Pose class object
+    :return: bounding box as cv2.boundingRect object
+    """
+    found_keypoints = np.zeros((np.count_nonzero(pose.data[:, 0] != -1), 2), dtype=np.int32)
+    found_kpt_id = 0
+    for kpt_id in range(Pose.num_kpts):
+        if pose.data[kpt_id, 0] == -1:
+            continue
+        found_keypoints[found_kpt_id] = pose.data[kpt_id]
+        found_kpt_id += 1
+    bbox = cv2.boundingRect(found_keypoints)
+    return bbox
+
+
+def update_id(pose, id_=None):
+    """
+    Increments or updates the id of the provided pose.
+
+    :param pose: Pose class object
+    :param id_: id to set, leave None to increment pose.id by one
+    """
+    pose.id = id_
+    if pose.id is None:
+        pose.id = Pose.last_id + 1
+        Pose.last_id += 1
+
+
+def draw(img, pose):
+    """
+    Draws the provided pose on the provided image.
+
+    :param img: the image to draw the pose on
+    :param pose: the pose to draw on the image
+    """
+    assert pose.data.shape == (Pose.num_kpts, 2)
+
+    for part_id in range(len(BODY_PARTS_PAF_IDS) - 2):
+        kpt_a_id = BODY_PARTS_KPT_IDS[part_id][0]
+        global_kpt_a_id = pose.data[kpt_a_id, 0]
+        x_a, y_a, x_b, y_b = 0, 0, 0, 0
+        if global_kpt_a_id != -1:
+            x_a, y_a = pose.data[kpt_a_id]
+            cv2.circle(img, (int(x_a), int(y_a)), 3, color, -1)
+        kpt_b_id = BODY_PARTS_KPT_IDS[part_id][1]
+        global_kpt_b_id = pose.data[kpt_b_id, 0]
+        if global_kpt_b_id != -1:
+            x_b, y_b = pose.data[kpt_b_id]
+            cv2.circle(img, (int(x_b), int(y_b)), 3, color, -1)
+        if global_kpt_a_id != -1 and global_kpt_b_id != -1:
+            cv2.line(img, (int(x_a), int(y_a)), (int(x_b), int(y_b)), color, 2)
+
+
+def get_similarity(a, b, threshold=0.5):
+    """
+    Calculates the Keypoint Similarity, explained in detail on the official COCO dataset site
+    https://cocodataset.org/#keypoints-eval
+
+    :param a: first pose
+    :param b: second pose
+    :param threshold: the similarity threshold to consider the keypoints similar
+    :return: number of similar keypoints
+    :rtype: int
+    """
+    bbox_a = get_bbox(a)
+    bbox_b = get_bbox(b)
+    num_similar_kpt = 0
+    for kpt_id in range(Pose.num_kpts):
+        if a.data[kpt_id, 0] != -1 and b.data[kpt_id, 0] != -1:
+            distance = np.sum((a.data[kpt_id] - b.data[kpt_id]) ** 2)
+            area = max(bbox_a[2] * bbox_a[3], bbox_b[2] * bbox_b[3])
+            similarity = np.exp(-distance / (2 * (area + np.spacing(1)) * vars_[kpt_id]))
+            if similarity > threshold:
+                num_similar_kpt += 1
+    return num_similar_kpt
+
+
+def track_poses(previous_poses, current_poses, threshold=3, smooth=False):
+    """
+    Propagate poses ids from previous frame results. Id is propagated,
+    if there are at least `threshold` similar keypoints between pose from previous frame and current.
+    If correspondence between pose on previous and current frame was established, pose keypoints are smoothed.
+
+    :param previous_poses: poses from previous frame with ids
+    :param current_poses: poses from current frame to assign ids
+    :param threshold: minimal number of similar keypoints between poses
+    :param smooth: smooth pose keypoints between frames
+    """
+    current_poses = sorted(current_poses, key=lambda pose: pose.confidence, reverse=True)  # match confident poses first
+    mask = np.ones(len(previous_poses), dtype=np.int32)
+    for current_pose in current_poses:
+        best_matched_id = None
+        best_matched_pose_id = None
+        best_matched_iou = 0
+        for id_, previous_pose in enumerate(previous_poses):
+            if not mask[id_]:
+                continue
+            iou = get_similarity(current_pose, previous_pose)
+            if iou > best_matched_iou:
+                best_matched_iou = iou
+                best_matched_pose_id = previous_pose.id
+                best_matched_id = id_
+        if best_matched_iou >= threshold:
+            mask[best_matched_id] = 0
+        else:  # pose not similar to any previous
+            best_matched_pose_id = None
+        update_id(current_pose, best_matched_pose_id)
+
+        if smooth:
+            for kpt_id in range(Pose.num_kpts):
+                if current_pose.data[kpt_id, 0] == -1:
+                    continue
+                # reuse filter if previous pose has valid filter
+                if best_matched_pose_id is not None and previous_poses[best_matched_id].data[kpt_id, 0] != -1:
+                    current_pose.filters[kpt_id] = previous_poses[best_matched_id].filters[kpt_id]
+                current_pose.data[kpt_id, 0] = current_pose.filters[kpt_id][0](current_pose.data[kpt_id, 0])
+                current_pose.data[kpt_id, 1] = current_pose.filters[kpt_id][1](current_pose.data[kpt_id, 1])

From 3d2612f28549dd65bbd0c0e708e8045f5a4b2d1a Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Thu, 1 Dec 2022 14:47:29 +0200
Subject: [PATCH 02/27] changes on path for 1080pi image input

---
 .../demos/benchmarking_demo.py                       |  2 +-
 .../demos/eval_demo.py                               | 12 ++----------
 .../demos/inference_demo.py                          |  6 +++---
 3 files changed, 6 insertions(+), 14 deletions(-)

diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
index 1aa259a233..1eb06750ae 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
@@ -55,7 +55,7 @@
 
     # Download one sample image
     pose_estimator.download(path=".", mode="test_data")
-    image_path = join("temp2", "dataset", "image", "000000000785_1440.jpg")
+    image_path = join("temp", "dataset", "image", "000000000785_1080.jpg")
     img = cv2.imread(image_path)
 
     if onnx:
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
index 9a35becb66..bd5766f48c 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
@@ -12,21 +12,13 @@
                         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)
-    parser.add_argument("--hrdata", help="Select the image resolution for inference", default=1440)
+    parser.add_argument("--hrdata", help="Select the image resolution for inference", default=1080)
 
     args = parser.parse_args()
 
     onnx, device, accelerate,base_height1,base_height2,hrdata = args.onnx, args.device, args.accelerate, args.height1, args.height2,args.hrdata
 
 
-    if hrdata == 1440:
-        data_file="data_1440"
-    elif hrdata == 1080:
-        data_file="data_1080"
-    elif hrdata == 720:
-        data_file="data_720"
-    else:
-        raise Exception("The inference image resolution is not valid")
 
 
     if accelerate:
@@ -50,7 +42,7 @@
     # Download a sample dataset
     pose_estimator.download(path=".", mode="test_data")
 
-    eval_dataset = ExternalDataset(path=join("temp2", "dataset",data_file), dataset_type="COCO")
+    eval_dataset = ExternalDataset(path=join("temp", "dataset"), dataset_type="COCO")
 
     t0=time.time()
     results_dict = pose_estimator.eval(eval_dataset,base_height1,base_height2, use_subset=False, verbose=True, silent=True,
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
index dab85bbd5b..fad6b80178 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
@@ -14,9 +14,9 @@
     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=540)
+    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)
-    parser.add_argument("--hrdata",help="Select the image resolution for inference",default=1440)
+    parser.add_argument("--hrdata",help="Select the image resolution for inference",default=1080)
 
     args = parser.parse_args()
 
@@ -48,7 +48,7 @@
     # Download one sample image
     pose_estimator.download(path=".", mode="test_data")
 
-    image_path = join("temp2", "dataset", "image", image_file)
+    image_path = join("temp", "dataset", "image", image_file)
 
     img = Image.open(image_path)
 

From d3756c2062181e8e6e7e23a5e61b5aa0dd13c391 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Fri, 2 Dec 2022 12:39:43 +0200
Subject: [PATCH 03/27] adding height1 height2 as params to learner

---
 .../demos/benchmarking_demo.py                |  5 ++-
 .../demos/eval_demo.py                        |  5 ++-
 .../demos/inference_demo.py                   | 15 ++++----
 .../HighResolutionLearner.py                  | 38 +++++++++++++------
 4 files changed, 40 insertions(+), 23 deletions(-)

diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
index 1eb06750ae..aaaa63c820 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
@@ -49,7 +49,8 @@
         half_precision = False
 
     pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
-                                                mobilenet_use_stride=stride, half_precision=half_precision)
+                                                mobilenet_use_stride=stride, half_precision=half_precision,
+                                                first_pass_height=base_height1,second_pass_height=base_height2)
     pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
@@ -67,7 +68,7 @@
         start_time = time.perf_counter()
         # Perform inference
 
-        poses = pose_estimator.infer(img, base_height1, base_height2)
+        poses = pose_estimator.infer(img)
 
         end_time = time.perf_counter()
         fps_list.append(1.0 / (end_time - start_time))
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
index bd5766f48c..3b43e98bec 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
@@ -32,7 +32,8 @@
 
     pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
                                                 mobilenet_use_stride=stride,
-                                                half_precision=half_precision)
+                                                half_precision=half_precision,
+                                                first_pass_height=base_height1, second_pass_height=base_height2)
     pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
@@ -45,7 +46,7 @@
     eval_dataset = ExternalDataset(path=join("temp", "dataset"), dataset_type="COCO")
 
     t0=time.time()
-    results_dict = pose_estimator.eval(eval_dataset,base_height1,base_height2, use_subset=False, verbose=True, silent=True,
+    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")
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
index fad6b80178..54b74184ed 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
@@ -16,18 +16,16 @@
                         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)
-    parser.add_argument("--hrdata",help="Select the image resolution for inference",default=1080)
+    parser.add_argument("--hrdata", help="Select the image resolution (1080 or 1440) for inference", default=1080)
 
     args = parser.parse_args()
 
-    onnx, device, accelerate,base_height1,base_height2,hrdata = args.onnx, args.device, args.accelerate, args.height1, args.height2,args.hrdata
+    onnx, device, accelerate, base_height1, base_height2, hrdata = args.onnx, args.device, args.accelerate, args.height1, args.height2, args.hrdata
 
     if hrdata == 1440:
-        image_file="000000000785_1440.jpg"
+        image_file = "000000000785_1440.jpg"
     elif hrdata == 1080:
-        image_file="000000000785_1080.jpg"
-    elif hrdata == 720:
-        image_file="000000000785_720.jpg"
+        image_file = "000000000785_1080.jpg"
     else:
         raise Exception("The inference image resolution is not valid")
 
@@ -41,7 +39,8 @@
         half_precision = False
 
     pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
-                                                mobilenet_use_stride=stride, half_precision=half_precision)
+                                                mobilenet_use_stride=stride, half_precision=half_precision,
+                                                first_pass_height=base_height1, second_pass_height= base_height2, img_resol=hrdata)
     pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
@@ -55,7 +54,7 @@
     if onnx:
         pose_estimator.optimize()
 
-    poses = pose_estimator.infer(img,base_height1,base_height2)
+    poses = pose_estimator.infer(img)
 
     img_cv = img.opencv()
     for pose in poses:
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
index 64e08f3031..235fbe7ee4 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
@@ -47,13 +47,19 @@ class HighResolutionPoseEstimationLearner(Learner):
 
     def __init__(self, device='cuda', backbone='mobilenet',
                  temp_path='temp', mobilenet_use_stride=True, mobilenetv2_width=1.0, shufflenet_groups=3,
-                 num_refinement_stages=2, batches_per_iter=1,base_height=256,
+                 num_refinement_stages=2, batches_per_iter=1,base_height=256, first_pass_height = 360, second_pass_height = 540,
+                 img_resol=1080,
                  experiment_name='default', num_workers=8, weights_only=True, output_name='detections.json',
                  multiscale=False, scales=None, visualize=False,
                  img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256), pad_value=(0, 0, 0),
                  half_precision=False):
 
         super(HighResolutionPoseEstimationLearner, self).__init__(temp_path=temp_path, device=device, backbone=backbone)
+
+        self.first_pass_height = first_pass_height
+        self.second_pass_height = second_pass_height
+        self.img_resol=img_resol
+
         self.parent_dir = temp_path  # Parent dir should be filled by the user according to README
 
         self.num_refinement_stages = num_refinement_stages  # How many extra refinement stages to add
@@ -250,7 +256,7 @@ def save(self, path, verbose=False):
         with open(os.path.join(full_path_to_model_folder, folder_name_no_ext + ".json"), 'w') as outfile:
             json.dump(model_metadata, outfile)
 
-    def eval(self, dataset, first_pass_height, second_pass_height, silent=False, verbose=True, use_subset=True,
+    def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
              subset_size=250,
              images_folder_name="val2017", annotations_filename="person_keypoints_val2017.json"):
 
@@ -321,7 +327,7 @@ def eval(self, dataset, first_pass_height, second_pass_height, silent=False, ver
             img = sample['img']
             h, w, _ = img.shape
             max_width = w
-            kernel = int(h / first_pass_height)
+            kernel = int(h / self.first_pass_height)
             if kernel > 0:
                 pool_img = HighResolutionPoseEstimationLearner.Pooling(self, img, kernel)
                 base_height = pool_img.shape[0]
@@ -383,7 +389,7 @@ def eval(self, dataset, first_pass_height, second_pass_height, silent=False, ver
                 # ------- Second pass of the image, inference for pose estimation -------
                 avg_heatmaps, avg_pafs, scale, pad = HighResolutionPoseEstimationLearner.second_pass_infer(self, self.net,
                                                                                                            crop_img,
-                                                                                                           second_pass_height,
+                                                                                                           self.second_pass_height,
                                                                                                            max_width,
                                                                                                            self.stride,
                                                                                                            self.upsample_ratio,
@@ -437,7 +443,7 @@ def eval(self, dataset, first_pass_height, second_pass_height, silent=False, ver
             if self.visualize:
                 for keypoints in coco_keypoints:
                     for idx in range(len(keypoints) // 3):
-                        cv2.circle(img, (int(keypoints[idx * 3]), int(keypoints[idx * 3 + 1])),
+                        cv2.circle(img, (int(keypoints[idx * 3]+offset), int(keypoints[idx * 3 + 1])+offset),
                                    3, (255, 0, 255), -1)
                 cv2.imshow('keypoints', img)
                 key = cv2.waitKey()
@@ -461,7 +467,7 @@ def eval(self, dataset, first_pass_height, second_pass_height, silent=False, ver
                 print("Evaluation ended with no detections.")
             return {"average_precision": [0.0 for _ in range(5)], "average_recall": [0.0 for _ in range(5)]}
 
-    def infer(self, img, first_pass_height, second_pass_height, upsample_ratio=4, stride=8, track=True, smooth=True,
+    def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
               multiscale=False, visualize=False):
         self.net = self.model
         current_poses = []
@@ -477,7 +483,7 @@ def infer(self, img, first_pass_height, second_pass_height, upsample_ratio=4, st
 
         h, w, _ = img.shape
         max_width = w
-        kernel = int(h / first_pass_height)
+        kernel = int(h / self.first_pass_height)
         if kernel > 0:
             pool_img = HighResolutionPoseEstimationLearner.Pooling(self, img, kernel)
             base_height = pool_img.shape[0]
@@ -539,7 +545,7 @@ def infer(self, img, first_pass_height, second_pass_height, upsample_ratio=4, st
             # ------- Second pass of the image, inference for pose estimation -------
             avg_heatmaps, avg_pafs, scale, pad = HighResolutionPoseEstimationLearner.second_pass_infer(self, self.net,
                                                                                                        crop_img,
-                                                                                                       second_pass_height,
+                                                                                                       self.second_pass_height,
                                                                                                        max_width,
                                                                                                        stride,
                                                                                                        upsample_ratio,
@@ -860,13 +866,23 @@ def download(self, path=None, mode="pretrained", verbose=False,
                 os.makedirs(os.path.join(self.temp_path, "dataset"))
             if not os.path.exists(os.path.join(self.temp_path, "dataset", "image")):
                 os.makedirs(os.path.join(self.temp_path, "dataset", "image"))
+            # Path for high resolution data
+            url = OPENDR_SERVER_URL + "perception/pose_estimation/high_resolution_pose_estimation/"
             # Download annotation file
             file_url = os.path.join(url, "dataset", "annotation.json")
             urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "annotation.json"))
             # Download test image
-            url=OPENDR_SERVER_URL + "/perception/pose_estimation/high_resolution_pose_estimation/"
-            file_url = os.path.join(url, "dataset", "image", "000000000785_1080.jpg")
-            urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "image", "000000000785_1080.jpg"))
+            if self.img_resol == 1080:
+                file_url = os.path.join(url, "dataset", "image", "000000000785_1080.jpg")
+                urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "image", "000000000785_1080.jpg"))
+            elif self.img_resol == 1440:
+                file_url = os.path.join(url, "dataset", "image", "000000000785_1440.jpg")
+                urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "image", "000000000785_1440.jpg"))
+            else:
+                raise UserWarning("There are no data for this image resolution")
+
+
+
 
             if verbose:
                 print("Test data download complete.")

From 9a8fe2b5289e7cdf77bd64eca66b032d06350fdf Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Fri, 2 Dec 2022 15:09:16 +0200
Subject: [PATCH 04/27] typos

---
 .../high_resolution_pose_estimation/demos/inference_demo.py     | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
index 54b74184ed..51fe2db322 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
@@ -16,7 +16,7 @@
                         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)
-    parser.add_argument("--hrdata", help="Select the image resolution (1080 or 1440) for inference", default=1080)
+    parser.add_argument("--hrdata", help="Select the image resolution (1080 or 1440) for inference", type=int, default=1080)
 
     args = parser.parse_args()
 

From a0d90e796baa01c1cfe8ba247e564be6cbcabfa6 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Fri, 2 Dec 2022 15:11:48 +0200
Subject: [PATCH 05/27] fixed tests

---
 .../__init__.py                               |   0
 .../test_high_resolution_pose_estimation.py   | 108 ++++++++++++++++++
 2 files changed, 108 insertions(+)
 create mode 100644 tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/__init__.py
 create mode 100644 tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py

diff --git a/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/__init__.py b/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/__init__.py
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py b/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py
new file mode 100644
index 0000000000..bf8e499aa3
--- /dev/null
+++ b/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py
@@ -0,0 +1,108 @@
+# 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 unittest
+import shutil
+import torch
+from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
+
+from opendr.engine.datasets import ExternalDataset
+from opendr.engine.data import Image
+import warnings
+import os
+
+device = os.getenv('TEST_DEVICE') if os.getenv('TEST_DEVICE') else 'cpu'
+
+
+def rmfile(path):
+    try:
+        os.remove(path)
+    except OSError as e:
+        print("Error: %s - %s." % (e.filename, e.strerror))
+
+
+def rmdir(_dir):
+    try:
+        shutil.rmtree(_dir)
+    except OSError as e:
+        print("Error: %s - %s." % (e.filename, e.strerror))
+
+
+class TestLightweightOpenPoseLearner(unittest.TestCase):
+
+    @classmethod
+    def setUpClass(cls):
+        print("\n\n**********************************\nTEST High Resolution Pose Estimation Learner\n"
+              "**********************************")
+
+        cls.temp_dir = os.path.join(".", "tests", "sources", "tools", "perception", "pose_estimation",
+                                                                "high_resolution_pose_estimation", "hr_pose_estim_temp")
+        cls.pose_estimator = HighResolutionPoseEstimationLearner(device=device, temp_path=cls.temp_dir,  num_workers=1)
+
+        # Download all required files for testing
+        cls.pose_estimator.download(mode="pretrained")
+        cls.pose_estimator.download(mode="test_data")
+
+    @classmethod
+    def tearDownClass(cls):
+        # Clean up downloaded files
+        rmdir(os.path.join(cls.temp_dir, "openpose_default"))
+        rmdir(os.path.join(cls.temp_dir, "dataset"))
+
+        rmdir(os.path.join(cls.temp_dir))
+
+
+    def test_eval(self):
+        # Test eval will issue resource warnings due to some files left open in pycoco tools,
+        # as well as a deprecation warning due to a cast of a float to integer (hopefully they will be fixed in a future
+        # version)
+        warnings.simplefilter("ignore", ResourceWarning)
+        warnings.simplefilter("ignore", DeprecationWarning)
+
+        eval_dataset = ExternalDataset(path=os.path.join(self.temp_dir, "dataset"), dataset_type="COCO")
+        self.pose_estimator.load(os.path.join(self.temp_dir, "openpose_default"))
+        results_dict = self.pose_estimator.eval(eval_dataset, use_subset=False, verbose=True, silent=True,
+             images_folder_name="image", annotations_filename="annotation.json")
+        self.assertNotEqual(len(results_dict['average_precision']), 0,
+                            msg="Eval results dictionary contains empty list.")
+        self.assertNotEqual(len(results_dict['average_recall']), 0,
+                            msg="Eval results dictionary contains empty list.")
+        # Cleanup
+        rmfile(os.path.join(self.temp_dir, "detections.json"))
+        warnings.simplefilter("default", ResourceWarning)
+        warnings.simplefilter("default", DeprecationWarning)
+
+    def test_infer(self):
+        self.pose_estimator.model = None
+        self.pose_estimator.load(os.path.join(self.temp_dir, "openpose_default"))
+
+        img = Image.open(os.path.join(self.temp_dir, "dataset", "image", "000000000785_1080.jpg"))
+        # Default pretrained mobilenet model detects 18 keypoints on img with id 785
+        self.assertGreater(len(self.pose_estimator.infer(img)[0].data), 0,
+                           msg="Returned pose must have non-zero number of keypoints.")
+
+    def test_save_load(self):
+        self.pose_estimator.model = None
+        self.pose_estimator.ort_session = None
+        self.pose_estimator.init_model()
+        self.pose_estimator.save(os.path.join(self.temp_dir, "test_model"))
+        self.pose_estimator.model = None
+        self.pose_estimator.load(os.path.join(self.temp_dir, "test_model"))
+        self.assertIsNotNone(self.pose_estimator.model, "model is None after loading pth model.")
+        # Cleanup
+        rmdir(os.path.join(self.temp_dir, "test_model"))
+
+
+if __name__ == "__main__":
+    unittest.main()

From e45ba3ae89ac9fc7950feb4c5991ada17fce8941 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Tue, 6 Dec 2022 14:35:44 +0200
Subject: [PATCH 06/27] edit Readme files, edit files(PEP8 changes) to pass
 tests

---
 .../high_resolution_pose_estimation.md        |  39 +++----
 .../demos/benchmarking_demo.py                |   9 +-
 .../demos/eval_demo.py                        |  34 ++++--
 .../demos/inference_demo.py                   |  33 +++---
 .../perception/pose_estimation/__init__.py    |   2 +-
 .../HighResolutionLearner.py                  | 110 ++++++++++--------
 .../hr_pose_estimation/algorithm/README.md    |   4 +-
 .../test_high_resolution_pose_estimation.py   |   8 +-
 tests/test_license.py                         |   1 +
 9 files changed, 134 insertions(+), 106 deletions(-)

diff --git a/docs/reference/high_resolution_pose_estimation.md b/docs/reference/high_resolution_pose_estimation.md
index 00c21cc9ef..f5353d7c05 100644
--- a/docs/reference/high_resolution_pose_estimation.md
+++ b/docs/reference/high_resolution_pose_estimation.md
@@ -13,7 +13,7 @@ following public methods:
 
 #### `HighResolutionPoseEstimationLearner` constructor
 ```python
-HighResolutionPoseEstimationLearner(self,device, backbone, temp_path, mobilenet_use_stride, mobilenetv2_width, shufflenet_groups, num_refinement_stages, batches_per_iter, experiment_name, num_workers, weights_only, output_name, multiscale, scales, visualize,  img_mean, img_scale, pad_value)
+HighResolutionPoseEstimationLearner(self,device, backbone, temp_path, mobilenet_use_stride, mobilenetv2_width, shufflenet_groups, num_refinement_stages, batches_per_iter, base_height, first_pass_height, second_pass_height, img_resol, experiment_name, num_workers, weights_only, output_name, multiscale, scales, visualize,  img_mean, img_scale, pad_value)
 ```
 
 Constructor parameters:
@@ -36,6 +36,10 @@ Constructor parameters:
   Specifies per how many batches a backward optimizer step is performed.
 - **base_height**: *int, default=256*\
   Specifies the height, based on which the images will be resized before performing the forward pass when using the Lightweight OpenPose.
+- **first_pass_height**: *int, default=360*\
+  Specifies the height that the input image will be resized during the heatmap generation procedure.
+- **second_pass_heght**: *int, default=540*\
+  Specifies the height of the image on the second inference for pose estimation procedure.
 - **experiment_name**: *str, default='default'*\
   String name to attach to checkpoints.
 - **num_workers**: *int, default=8*\
@@ -62,9 +66,9 @@ Constructor parameters:
 
 
 
-#### `LightweightOpenPoseLearner.eval`
+#### `HighResolutionPoseEstimationLearner.eval`
 ```python
-HighResolutionPoseEstimationLearner.eval(self, dataset, first_pass_height, second_pass_height, silent, verbose, use_subset, subset_size, images_folder_name, annotations_filename)
+HighResolutionPoseEstimationLearner.eval(self, dataset, silent, verbose, use_subset, subset_size, images_folder_name, annotations_filename)
 ```
 
 This method is used to evaluate a trained model on an evaluation dataset.
@@ -75,10 +79,6 @@ Parameters:
 - **dataset**: *object*\
   Object that holds the evaluation dataset.
   Can be of type `ExternalDataset` or a custom dataset inheriting from `DatasetIterator`.
-- **first_pass_height**: *int*\
-    It is the height that the input image is resized during the heatmap generation procedure.
-- **second_pass_height**: *int*\
-    It is the base height that is used for resizing on the pose estimation procedure.
 - **silent**: *bool, default=False*\
   If set to True, disables all printing of evaluation progress reports and other information to STDOUT.
 - **verbose**: *bool, default=True*\
@@ -97,7 +97,7 @@ Parameters:
 
 #### `HighResolutionPoseEstimation.infer`
 ```python
-HighResolutionPoseEstimation.infer(img, fisrt_pass_height, second_pass_height, upsample_ratio, track, smooth)
+HighResolutionPoseEstimation.infer(img, upsample_ratio, track, smooth)
 ```
 
 This method is used to perform pose estimation on an image.
@@ -107,10 +107,6 @@ Parameters:
 
 - **img**: *object***\
   Object of type engine.data.Image.
-- **first_height**: *int*\
-    It is the height that the input image is resized during the heatmap generation procedure.
-- **second height**: *int*\
-    It is the base height that is used for resizing on the pose estimation procedure.
 - **upsample_ratio**: *int, default=4*\
   Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing.
 - **track**: *bool, default=True*\
@@ -119,7 +115,7 @@ Parameters:
   If True, smoothing is performed on pose keypoints between frames.
 
 
-#### `LightweightOpenPoseLearner.first_pass`
+#### `HighResolutionPoseEstimationLearner.first_pass`
 ```python
 HighResolutionPoseEstimationLearner.first_pass(self, net,img)
 ```
@@ -131,7 +127,7 @@ Parameters:
 - **net**: *object*\
   The model that is used for creating the heatmap.
 
-#### `LightweightOpenPoseLearner.second_pass`
+#### `HighResolutionPoseEstimationLearner.second_pass`
 ```python
 HighResolutionPoseEstimationLearner.second_pass_infer(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, device,
                           pad_value=(0, 0, 0),
@@ -255,18 +251,19 @@ Parameters:
   from opendr.perception.pose_estimation import draw
   from opendr.engine.data import Image
   
-
-  pose_estimator = HighResolutionPoseEstimationLearner(device="cuda", temp_path='./parent_dir')
+  pose_estimator = HighResolutionPoseEstimationLearner(device='cuda', num_refinement_stages=2,
+                                                           mobilenet_use_stride=False, half_precision=False,
+                                                           first_pass_height=360,
+                                                           second_pass_height=540,
+                                                           img_resol=1080)
   pose_estimator.download()  # Download the default pretrained mobilenet model in the temp_path
-  pose_estimator.load("./parent_dir/mobilenet_openpose")
+  
+  pose_estimator.load("./parent_dir/openpose_default")
   pose_estimator.download(mode="test_data")  # Download a test data taken from COCO2017
   
-  first_pass_height = 360
-  second_pass_height = 540
-   
   img = Image.open('./parent_dir/dataset/image/000000000785_1080.jpg')
   orig_img = img.opencv()  # Keep original image
-  current_poses = pose_estimator.infer(img,  first_pass_height, second_pass_height)
+  current_poses = pose_estimator.infer(img)
   img_opencv = img.opencv()
   for pose in current_poses:
       draw(img_opencv, pose)
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
index aaaa63c820..ffe56ccb52 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
@@ -31,14 +31,14 @@
 
     args = parser.parse_args()
 
-    onnx, device, accelerate,base_height1,base_height2 = args.onnx, args.device, args.accelerate, args.height1, args.height2
+    onnx, device, accelerate, base_height1, base_height2 = args.onnx, 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
@@ -49,8 +49,9 @@
         half_precision = False
 
     pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
-                                                mobilenet_use_stride=stride, half_precision=half_precision,
-                                                first_pass_height=base_height1,second_pass_height=base_height2)
+                                                         mobilenet_use_stride=stride, half_precision=half_precision,
+                                                         first_pass_height=base_height1,
+                                                         second_pass_height=base_height2)
     pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
index 3b43e98bec..f5fbe75d7e 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
@@ -1,4 +1,18 @@
 
+# 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
@@ -12,14 +26,11 @@
                         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)
-    parser.add_argument("--hrdata", help="Select the image resolution for inference", default=1080)
 
     args = parser.parse_args()
 
-    onnx, device, accelerate,base_height1,base_height2,hrdata = args.onnx, args.device, args.accelerate, args.height1, args.height2,args.hrdata
-
-
-
+    onnx, device, accelerate, base_height1, base_height2 = args.onnx, args.device, args.accelerate,\
+        args.height1, args.height2
 
     if accelerate:
         stride = True
@@ -31,9 +42,10 @@
         half_precision = True
 
     pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
-                                                mobilenet_use_stride=stride,
-                                                half_precision=half_precision,
-                                                first_pass_height=base_height1, second_pass_height=base_height2)
+                                                         mobilenet_use_stride=stride,
+                                                         half_precision=half_precision,
+                                                         first_pass_height=base_height1,
+                                                         second_pass_height=base_height2)
     pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
@@ -45,9 +57,9 @@
 
     eval_dataset = ExternalDataset(path=join("temp", "dataset"), dataset_type="COCO")
 
-    t0=time.time()
+    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)
\ No newline at end of file
+    print("\n Evaluation time:  ", t1 - t0, "seconds")
+    print("Evaluation results = ", results_dict)
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
index 51fe2db322..22dbe53521 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
@@ -1,4 +1,18 @@
 
+# 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
 from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
 
@@ -16,18 +30,11 @@
                         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)
-    parser.add_argument("--hrdata", help="Select the image resolution (1080 or 1440) for inference", type=int, default=1080)
 
     args = parser.parse_args()
 
-    onnx, device, accelerate, base_height1, base_height2, hrdata = args.onnx, args.device, args.accelerate, args.height1, args.height2, args.hrdata
-
-    if hrdata == 1440:
-        image_file = "000000000785_1440.jpg"
-    elif hrdata == 1080:
-        image_file = "000000000785_1080.jpg"
-    else:
-        raise Exception("The inference image resolution is not valid")
+    onnx, device, accelerate, base_height1, base_height2 = args.onnx, args.device, args.accelerate,\
+        args.height1, args.height2
 
     if accelerate:
         stride = True
@@ -39,15 +46,16 @@
         half_precision = False
 
     pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
-                                                mobilenet_use_stride=stride, half_precision=half_precision,
-                                                first_pass_height=base_height1, second_pass_height= base_height2, img_resol=hrdata)
+                                                         mobilenet_use_stride=stride, half_precision=half_precision,
+                                                         first_pass_height=base_height1,
+                                                         second_pass_height=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", image_file)
+    image_path = join("temp", "dataset", "image", "000000000785_1080.jpg")
 
     img = Image.open(image_path)
 
@@ -61,4 +69,3 @@
         draw(img_cv, pose)
     cv2.imshow('Results', img_cv)
     cv2.waitKey(0)
-
diff --git a/src/opendr/perception/pose_estimation/__init__.py b/src/opendr/perception/pose_estimation/__init__.py
index e483312051..dc42947a02 100644
--- a/src/opendr/perception/pose_estimation/__init__.py
+++ b/src/opendr/perception/pose_estimation/__init__.py
@@ -5,4 +5,4 @@
 
 from opendr.perception.pose_estimation.lightweight_open_pose.utilities import draw, get_bbox
 
-__all__ = ['LightweightOpenPoseLearner', 'draw', 'get_bbox','HighResolutionPoseEstimationLearner']
+__all__ = ['LightweightOpenPoseLearner', 'draw', 'get_bbox', 'HighResolutionPoseEstimationLearner']
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
index 235fbe7ee4..7f3fce3882 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
@@ -1,3 +1,18 @@
+
+"""# 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."""
+
 # General imports
 # General imports
 import torchvision.transforms
@@ -47,8 +62,8 @@ class HighResolutionPoseEstimationLearner(Learner):
 
     def __init__(self, device='cuda', backbone='mobilenet',
                  temp_path='temp', mobilenet_use_stride=True, mobilenetv2_width=1.0, shufflenet_groups=3,
-                 num_refinement_stages=2, batches_per_iter=1,base_height=256, first_pass_height = 360, second_pass_height = 540,
-                 img_resol=1080,
+                 num_refinement_stages=2, batches_per_iter=1, base_height=256,
+                 first_pass_height=360, second_pass_height=540,
                  experiment_name='default', num_workers=8, weights_only=True, output_name='detections.json',
                  multiscale=False, scales=None, visualize=False,
                  img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256), pad_value=(0, 0, 0),
@@ -58,7 +73,7 @@ def __init__(self, device='cuda', backbone='mobilenet',
 
         self.first_pass_height = first_pass_height
         self.second_pass_height = second_pass_height
-        self.img_resol=img_resol
+        self.img_resol = 1080  # default value for sample image in OpenDr server
 
         self.parent_dir = temp_path  # Parent dir should be filled by the user according to README
 
@@ -135,7 +150,7 @@ def first_pass(self, net, img):
         avg_pafs = pafs
         return avg_pafs
 
-    def second_pass_infer(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, device,
+    def second_pass_infer(self, net, img, net_input_height_size, max_width, stride, upsample_ratio,
                           pad_value=(0, 0, 0),
                           img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256)):
         height, width, _ = img.shape
@@ -194,7 +209,6 @@ def fit(self, val_dataset=None, logging_path='', logging_flush_secs=30,
     def optimize(self, do_constant_folding=False):
         raise NotImplementedError
 
-
     def reset(self):
         """This method is not used in this implementation."""
         return NotImplementedError
@@ -304,7 +318,6 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
         if self.multiscale:
             self.scales = [0.5, 1.0, 1.5, 2.0]
 
-        self.net = self.model
         coco_result = []
         num_keypoints = Pose.num_kpts
 
@@ -330,17 +343,16 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
             kernel = int(h / self.first_pass_height)
             if kernel > 0:
                 pool_img = HighResolutionPoseEstimationLearner.Pooling(self, img, kernel)
-                base_height = pool_img.shape[0]
+
             else:
                 pool_img = img
-                base_height = img.shape[0]
 
             perc = 0.3  # percentage around cropping
 
             thresshold = 0.1  # thresshold for heatmap
 
             # ------- Heatmap Generation -------
-            avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.net, pool_img)
+            avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.model, pool_img)
             avg_pafs = avg_pafs.astype(np.float32)
 
             pafs_map = cv2.blur(avg_pafs, (5, 5))
@@ -353,6 +365,7 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
 
             contours, hierarchy = cv2.findContours(heatmap, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
             count = []
+            coco_keypoints = []
 
             if len(contours) > 0:
                 for x in contours:
@@ -374,10 +387,14 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
                 extra_pad_x = int(perc * (xmax - xmin))  # Adding an extra pad around cropped image
                 extra_pad_y = int(perc * (ymax - ymin))
 
-                if xmin - extra_pad_x > 0: xmin = xmin - extra_pad_x
-                if xmax + extra_pad_x < img.shape[1]: xmax = xmax + extra_pad_x
-                if ymin - extra_pad_y > 0: ymin = ymin - extra_pad_y
-                if ymax + extra_pad_y < img.shape[0]: ymax = ymax + extra_pad_y
+                if xmin - extra_pad_x > 0:
+                    xmin = xmin - extra_pad_x
+                if xmax + extra_pad_x < img.shape[1]:
+                    xmax = xmax + extra_pad_x
+                if ymin - extra_pad_y > 0:
+                    ymin = ymin - extra_pad_y
+                if ymax + extra_pad_y < img.shape[0]:
+                    ymax = ymax + extra_pad_y
 
                 if (xmax - xmin) > 40 and (ymax - ymin) > 40:
                     crop_img = img[ymin:ymax, xmin:xmax]
@@ -387,13 +404,11 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
                 h, w, _ = crop_img.shape
 
                 # ------- Second pass of the image, inference for pose estimation -------
-                avg_heatmaps, avg_pafs, scale, pad = HighResolutionPoseEstimationLearner.second_pass_infer(self, self.net,
-                                                                                                           crop_img,
-                                                                                                           self.second_pass_height,
-                                                                                                           max_width,
-                                                                                                           self.stride,
-                                                                                                           self.upsample_ratio,
-                                                                                                           self.device)
+                avg_heatmaps, avg_pafs, scale, pad = \
+                    HighResolutionPoseEstimationLearner.second_pass_infer(self,
+                                                                          self.model, crop_img,
+                                                                          self.second_pass_height, max_width,
+                                                                          self.stride, self.upsample_ratio)
                 total_keypoints_num = 0
                 all_keypoints_by_type = []
                 for kpt_idx in range(18):
@@ -410,10 +425,10 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
 
                 for i in range(all_keypoints.shape[0]):
                     for j in range(all_keypoints.shape[1]):
-                        if j == 0:
-                            all_keypoints[i][j] = round((all_keypoints[i][j] + xmin) - offset)  # Adjust offset if needed for evaluation on our HR datasets
-                        if j == 1:
-                            all_keypoints[i][j] = round((all_keypoints[i][j] + ymin) - offset)  # Adjust offset if needed for evaluation on our HR datasets
+                        if j == 0:  # Adjust offset if needed for evaluation on our HR datasets
+                            all_keypoints[i][j] = round((all_keypoints[i][j] + xmin) - offset)
+                        if j == 1:  # Adjust offset if needed for evaluation on our HR datasets
+                            all_keypoints[i][j] = round((all_keypoints[i][j] + ymin) - offset)
 
                 current_poses = []
                 for n in range(len(pose_entries)):
@@ -436,8 +451,7 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
                         'image_id': image_id,
                         'category_id': 1,  # person
                         'keypoints': coco_keypoints[idx],
-                        'score': scores[idx],
-                        'person': idx
+                        'score': scores[idx]
                     })
 
             if self.visualize:
@@ -469,10 +483,10 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
 
     def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
               multiscale=False, visualize=False):
-        self.net = self.model
         current_poses = []
 
         offset = 0
+
         num_keypoints = Pose.num_kpts
 
         if not isinstance(img, Image):
@@ -483,20 +497,19 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
         h, w, _ = img.shape
         max_width = w
+
         kernel = int(h / self.first_pass_height)
         if kernel > 0:
             pool_img = HighResolutionPoseEstimationLearner.Pooling(self, img, kernel)
-            base_height = pool_img.shape[0]
         else:
             pool_img = img
-            base_height = img.shape[0]
 
         perc = 0.3  # percentage around cropping
 
         thresshold = 0.1  # threshold for heatmap
 
         # ------- Heatmap Generation -------
-        avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.net, pool_img)
+        avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.model, pool_img)
         avg_pafs = avg_pafs.astype(np.float32)
         pafs_map = cv2.blur(avg_pafs, (5, 5))
 
@@ -530,10 +543,14 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
             extra_pad_x = int(perc * (xmax - xmin))  # Adding an extra pad around cropped image
             extra_pad_y = int(perc * (ymax - ymin))
 
-            if xmin - extra_pad_x > 0: xmin = xmin - extra_pad_x
-            if xmax + extra_pad_x < img.shape[1]: xmax = xmax + extra_pad_x
-            if ymin - extra_pad_y > 0: ymin = ymin - extra_pad_y
-            if ymax + extra_pad_y < img.shape[0]: ymax = ymax + extra_pad_y
+            if xmin - extra_pad_x > 0:
+                xmin = xmin - extra_pad_x
+            if xmax + extra_pad_x < img.shape[1]:
+                xmax = xmax + extra_pad_x
+            if ymin - extra_pad_y > 0:
+                ymin = ymin - extra_pad_y
+            if ymax + extra_pad_y < img.shape[0]:
+                ymax = ymax + extra_pad_y
 
             if (xmax - xmin) > 40 and (ymax - ymin) > 40:
                 crop_img = img[ymin:ymax, xmin:xmax]
@@ -543,13 +560,11 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
             h, w, _ = crop_img.shape
 
             # ------- Second pass of the image, inference for pose estimation -------
-            avg_heatmaps, avg_pafs, scale, pad = HighResolutionPoseEstimationLearner.second_pass_infer(self, self.net,
-                                                                                                       crop_img,
-                                                                                                       self.second_pass_height,
-                                                                                                       max_width,
-                                                                                                       stride,
-                                                                                                       upsample_ratio,
-                                                                                                       self.device)
+            avg_heatmaps, avg_pafs, scale, pad = \
+                HighResolutionPoseEstimationLearner.second_pass_infer(self, self.model, crop_img,
+                                                                      self.second_pass_height,
+                                                                      max_width, stride, upsample_ratio)
+
             total_keypoints_num = 0
             all_keypoints_by_type = []
             for kpt_idx in range(18):
@@ -564,10 +579,10 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
             for i in range(all_keypoints.shape[0]):
                 for j in range(all_keypoints.shape[1]):
-                    if j == 0:
-                        all_keypoints[i][j] = round((all_keypoints[i][j] + xmin) - offset)  # Adjust offset if needed for evaluation on our HR datasets
-                    if j == 1:
-                        all_keypoints[i][j] = round((all_keypoints[i][j] + ymin) - offset)  # Adjust offset if needed for evaluation on our HR datasets
+                    if j == 0:  # Adjust offset if needed for evaluation on our HR datasets
+                        all_keypoints[i][j] = round((all_keypoints[i][j] + xmin) - offset)
+                    if j == 1:  # Adjust offset if needed for evaluation on our HR datasets
+                        all_keypoints[i][j] = round((all_keypoints[i][j] + ymin) - offset)
 
             current_poses = []
             for n in range(len(pose_entries)):
@@ -583,7 +598,7 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
         return current_poses
 
-    def infer_light_odr(self, img, upsample_ratio=4, track=True, smooth=True):      #LwOP from OpenDR implementation
+    def infer_light_odr(self, img, upsample_ratio=4, track=True, smooth=True):  # LwOP from OpenDR implementation
         """
         This method is used to perform pose estimation on an image.
 
@@ -881,9 +896,6 @@ def download(self, path=None, mode="pretrained", verbose=False,
             else:
                 raise UserWarning("There are no data for this image resolution")
 
-
-
-
             if verbose:
                 print("Test data download complete.")
 
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md
index 3299138ac4..eeaed7e202 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md
@@ -1,6 +1,6 @@
-# OpenDR Pose Estimation - Lightweight Open Pose
+# OpenDR High Resolution Pose Estimation
 
-This folder contains the Open Pose[1] algorithm implementation for pose estimation in the OpenDR Toolkit, 
+This folder contains the Open Pose[1] algorithm implementation for high resolution pose estimation in the OpenDR Toolkit, 
 in the form of Lightweight Open Pose [2].
 
 ## Sources
diff --git a/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py b/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py
index bf8e499aa3..b8a1096b84 100644
--- a/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py
+++ b/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py
@@ -14,7 +14,6 @@
 
 import unittest
 import shutil
-import torch
 from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
 
 from opendr.engine.datasets import ExternalDataset
@@ -46,8 +45,8 @@ def setUpClass(cls):
         print("\n\n**********************************\nTEST High Resolution Pose Estimation Learner\n"
               "**********************************")
 
-        cls.temp_dir = os.path.join(".", "tests", "sources", "tools", "perception", "pose_estimation",
-                                                                "high_resolution_pose_estimation", "hr_pose_estim_temp")
+        cls.temp_dir = os.path.join(".", "tests", "sources", "tools", "perception",
+                                    "pose_estimation", "high_resolution_pose_estimation", "hr_pose_estim_temp")
         cls.pose_estimator = HighResolutionPoseEstimationLearner(device=device, temp_path=cls.temp_dir,  num_workers=1)
 
         # Download all required files for testing
@@ -62,7 +61,6 @@ def tearDownClass(cls):
 
         rmdir(os.path.join(cls.temp_dir))
 
-
     def test_eval(self):
         # Test eval will issue resource warnings due to some files left open in pycoco tools,
         # as well as a deprecation warning due to a cast of a float to integer (hopefully they will be fixed in a future
@@ -73,7 +71,7 @@ def test_eval(self):
         eval_dataset = ExternalDataset(path=os.path.join(self.temp_dir, "dataset"), dataset_type="COCO")
         self.pose_estimator.load(os.path.join(self.temp_dir, "openpose_default"))
         results_dict = self.pose_estimator.eval(eval_dataset, use_subset=False, verbose=True, silent=True,
-             images_folder_name="image", annotations_filename="annotation.json")
+                                                images_folder_name="image", annotations_filename="annotation.json")
         self.assertNotEqual(len(results_dict['average_precision']), 0,
                             msg="Eval results dictionary contains empty list.")
         self.assertNotEqual(len(results_dict['average_recall']), 0,
diff --git a/tests/test_license.py b/tests/test_license.py
index 6452095449..1f1a0eb6b6 100755
--- a/tests/test_license.py
+++ b/tests/test_license.py
@@ -86,6 +86,7 @@ def setUp(self):
         ]
 
         skippedDirectoryPaths = [
+            'src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm',
             'src/opendr/perception/pose_estimation/lightweight_open_pose/algorithm',
             'src/opendr/perception/object_detection_3d/voxel_object_detection_3d/second_detector',
             'src/opendr/perception/face_recognition/algorithm',

From 0081557db88b3cae3dfca55dc5ab35ddbdc24626 Mon Sep 17 00:00:00 2001
From: ad-daniel <daniel.dias@epfl.ch>
Date: Sun, 11 Dec 2022 23:01:48 +0100
Subject: [PATCH 07/27] fix formatting

---
 .../high_resolution_pose_estimation.md        | 72 ++++++++++---------
 1 file changed, 37 insertions(+), 35 deletions(-)

diff --git a/docs/reference/high_resolution_pose_estimation.md b/docs/reference/high_resolution_pose_estimation.md
index f5353d7c05..af0664d939 100644
--- a/docs/reference/high_resolution_pose_estimation.md
+++ b/docs/reference/high_resolution_pose_estimation.md
@@ -5,11 +5,13 @@ The *high_resolution_pose_estimation* module contains the *HighResolutionPoseEst
 ### Class HighResolutionPoseEstimationLearner
 Bases: `engine.learners.Learner`
 
-The *HighResolutionLightweightOpenPose* class is an implementation for pose estimation in high resolution images. This method is creating a heatmap of a resized version of the input image. Using this heatmap, the input image is being cropped keeping the area of interest and then it isused for pose estimation. The pose estimation is based on the Lightweight OpenPose algorithm. 
-In this method there are two important variables which are responsible for the increase in speed and in accuracy in high resolution images. These variables are the *first_pass_height* and the *second height* that the image is resized in this procedure.
+The *HighResolutionLightweightOpenPose* class is an implementation for pose estimation in high resolution images.
+This method is creating a heatmap of a resized version of the input image.
+Using this heatmap, the input image is being cropped keeping the area of interest and then it isused for pose estimation. The pose estimation is based on the Lightweight OpenPose algorithm.
+In this method there are two important variables which are responsible for the increase in speed and in accuracy in high resolution images.
+These variables are the *first_pass_height* and the *second height* that the image is resized in this procedure.
 
-The [HighResolutionPoseEstiamtionLearner](/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py) class has the
-following public methods:
+The [HighResolutionPoseEstiamtionLearner](/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py) class has the following public methods:
 
 #### `HighResolutionPoseEstimationLearner` constructor
 ```python
@@ -21,7 +23,7 @@ Constructor parameters:
 - **device**: *{'cpu', 'cuda'}, default='cuda'*\
   Specifies the device to be used.
 - **backbone**: *{'mobilenet, 'mobilenetv2', 'shufflenet'}, default='mobilenet'*\
-    Specifies the backbone architecture.
+  Specifies the backbone architecture.
 - **temp_path**: *str, default='temp'*\
   Specifies a path where the algorithm looks for pretrained backbone weights, the checkpoints are saved along with the logging files. Moreover the JSON file that contains the evaluation detections is saved here.
 - **mobilenet_use_stride**: *bool, default=True*\
@@ -54,7 +56,6 @@ Constructor parameters:
   A list of integer scales that define the multiscale evaluation setup. Used to manually set the scales instead of going for the predefined multiscale setup.
 - **visualize**: *bool, default=False*\
   Specifies whether the images along with the poses will be shown, one by one during evaluation.
-
 - **img_mean**: *list, default=(128, 128, 128)]*\
   Specifies the mean based on which the images are normalized.
 - **img_scale**: *float, default=1/256*\
@@ -119,6 +120,7 @@ Parameters:
 ```python
 HighResolutionPoseEstimationLearner.first_pass(self, net,img)
 ```
+
 This method is used for extracting from the input image a heatmap about human locations in the picture.
 
 Parameters:
@@ -133,22 +135,24 @@ HighResolutionPoseEstimationLearner.second_pass_infer(self, net, img, net_input_
                           pad_value=(0, 0, 0),
                           img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256))
 ```
-On this method it is carried out the second inference step which estimates the human poses on the image that is inserted. Following the steps of the proposed method this image should be the cropped part of the initial high resolution image that came out from taking into account the area of interest of heatmap generation.
+
+On this method it is carried out the second inference step which estimates the human poses on the image that is inserted.
+Following the steps of the proposed method this image should be the cropped part of the initial high resolution image that came out from taking into account the area of interest of heatmap generation.
 
 Parameters:
+
 - **net**: *object*\
   The model that is used for creating the heatmap.
 - **img**: *object***\
   Object of type engine.data.Image.
 - **net_input_height_size**: *int*\
-    It is the height that is used for resizing the image on the pose estimation procedure.
+  It is the height that is used for resizing the image on the pose estimation procedure.
 - **max_width**: *int*\
-   It is the max width that the cropped image should have in order to keep the height-width ratio below a certain value.
+  It is the max width that the cropped image should have in order to keep the height-width ratio below a certain value.
 - **stride**: *int*\
-   Is the stride value of mobilenet which reduces accuracy but increases inference speed.
+  Is the stride value of mobilenet which reduces accuracy but increases inference speed.
 - **upsample_ratio**: *int, default=4*\
   Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing.
-
 - **device**: *{'cpu', 'cuda'}, default='cuda'*\
   Specifies the device to be used.
 - **pad_value**: *list, default=(0, 0, 0)*\
@@ -162,7 +166,9 @@ Parameters:
 ```python
 HighResolutionPoseEstimation.Pooling(self, img, kernel)
 ```
+
 Parameters:
+
 - **img**: *object***\
   Object of type engine.data.Image.
 - **kernel**: *int*\
@@ -172,6 +178,7 @@ Parameters:
 ```python
 HighResolutionPoseEstimation.infer_light_odr(self, img, upsample_ratio=4, track=True, smooth=True)
 ```
+
 This method is an inference function of OpenDR LightWeight OpenPose pose estiamtion.
 
 Parameters:
@@ -191,11 +198,8 @@ HighResolutionPoseEstimation.save(self, path, verbose)
 ```
 
 This method is used to save a trained model.
-Provided with the path "/my/path/name" (absolute or relative), it creates the "name" directory, if it does not already
-exist. Inside this folder, the model is saved as "name.pth" and the metadata file as "name.json". If the directory
-already exists, the "name.pth" and "name.json" files are overwritten.
-
-
+Provided with the path "/my/path/name" (absolute or relative), it creates the "name" directory, if it does not already exist.
+Inside this folder, the model is saved as "name.pth" and the metadata file as "name.json". If the directory already exists, the "name.pth" and "name.json" files are overwritten.
 
 Parameters:
 
@@ -224,8 +228,9 @@ Parameters:
 HighResolutionPoseEstimation.download(self, path, mode, verbose, url)
 ```
 
-Download utility for various Lightweight Open Pose components. Downloads files depending on mode and
-saves them in the path provided. It supports downloading:
+Download utility for various Lightweight Open Pose components.
+Downloads files depending on mode and saves them in the path provided.
+It supports downloading:
 1. the default mobilenet pretrained model
 2. mobilenet, mobilenetv2 and shufflenet weights needed for training
 3. a test dataset with a single COCO image and its annotation
@@ -250,17 +255,17 @@ Parameters:
   from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
   from opendr.perception.pose_estimation import draw
   from opendr.engine.data import Image
-  
+
   pose_estimator = HighResolutionPoseEstimationLearner(device='cuda', num_refinement_stages=2,
                                                            mobilenet_use_stride=False, half_precision=False,
                                                            first_pass_height=360,
                                                            second_pass_height=540,
                                                            img_resol=1080)
   pose_estimator.download()  # Download the default pretrained mobilenet model in the temp_path
-  
+
   pose_estimator.load("./parent_dir/openpose_default")
   pose_estimator.download(mode="test_data")  # Download a test data taken from COCO2017
-  
+
   img = Image.open('./parent_dir/dataset/image/000000000785_1080.jpg')
   orig_img = img.opencv()  # Keep original image
   current_poses = pose_estimator.infer(img)
@@ -291,6 +296,7 @@ The experiments are conducted on a 1080p image.
 | OpenDR - Baseline | 0.05               | 2.6             | 0.3              | 0.5             |
 | OpenDR - Full     | 0.2                | 10.8            | 1.4              | 3.1             |
 
+
 #### High-Resolution Pose Estimation
 | Method                 | CPU i7-9700K (FPS) | RTX 2070 (FPS) | Jetson TX2 (FPS) | Xavier NX (FPS) |
 |------------------------|--------------------|----------------|------------------|-----------------|
@@ -301,8 +307,8 @@ The experiments are conducted on a 1080p image.
 | HRPoseEstim - H+S      | 8.2                | 25.9           | 3.6              | 5.5             |
 | HRPoseEstim - Full     | 10.9               | 31.7           | 4.8              | 6.9             |
 
-
-As it is shown in the previous Table, OpenDr Lightweight OpenPose achieves higher FPS when it is resing the input image into 256 pixels. It is easier to process that image but as it is shown in the next tables the method falls apart when it comes to accuracy and there are no detections.
+As it is shown in the previous Table, OpenDr Lightweight OpenPose achieves higher FPS when it is resing the input image into 256 pixels.
+It is easier to process that image but as it is shown in the next tables the method falls apart when it comes to accuracy and there are no detections.
 
 We have evaluated the effect of using different inference settings, namely:
 - *HRPoseEstim - Baseline*, which refers to directly using the High Resolution Pose Estimation method,which is based in Lightweight OpenPose,
@@ -311,9 +317,11 @@ We have evaluated the effect of using different inference settings, namely:
 - *HRPoseEstim - Stages*, which refers to removing the refinement stages,
 - *HRPoseEstim - H+S*, which uses both half precision and increased stride, and
 - *HRPoseEstim - Full*, which refers to combining all three available optimization.
-was used as input to the models. 
+was used as input to the models.
 
 The average precision and average recall on the COCO evaluation split is also reported in the Table below:
+
+
 #### Lightweight OpenPose
 | Method            | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) | Evaluation time (sec) |
 |-------------------|------------------------------|---------------------------|-----------------------|
@@ -330,8 +338,6 @@ The average precision and average recall on the COCO evaluation split is also re
 | HRPoseEstim - H+S      | 0.254                        | 0.267                     | 165                   |
 | HRPoseEstim - Full     | 0.259                        | 0.272                     | 145                   |
 
-
-
 The average precision and the average recall have been calculated on a 1080p version of COCO2017 validation dataset and the results are reported in the table below:
 
 | Method | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) |
@@ -343,16 +349,14 @@ The average precision and the average recall have been calculated on a 1080p ver
 | HRPoseEstim - H+S      | 0.134                        | 0.139                     |
 | HRPoseEstim - Full     | 0.141                        | 0.150                     |
 
-For measuring the precision and recall we used the standard approach proposed for COCO, using an Intersection of Union (IoU) metric at 0.5. 
+For measuring the precision and recall we used the standard approach proposed for COCO, using an Intersection of Union (IoU) metric at 0.5.
 
 
 #### Notes
 
-For the metrics of the algorithm the COCO dataset evaluation scores are used as explained [here](
-https://cocodataset.org/#keypoints-eval).
+For the metrics of the algorithm the COCO dataset evaluation scores are used as explained [here](https://cocodataset.org/#keypoints-eval).
 
-Keypoints and how poses are constructed is according to the original method described [here](
-https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch/blob/master/TRAIN-ON-CUSTOM-DATASET.md).
+Keypoints and how poses are constructed is according to the original method described [here](https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch/blob/master/TRAIN-ON-CUSTOM-DATASET.md).
 
 Pose keypoints ids are matched as:
 
@@ -379,7 +383,5 @@ Pose keypoints ids are matched as:
 
 
 #### References
-<a name="open-pose-1" href="https://arxiv.org/abs/1812.08008">[1]</a> OpenPose: Realtime Multi-Person 2D Pose Estimation using Part Affinity Fields,
-[arXiv](https://arxiv.org/abs/1812.08008).
-<a name="open-pose-2" href="https://arxiv.org/abs/1811.12004">[2]</a> Real-time 2D Multi-Person Pose Estimation on CPU: Lightweight OpenPose,
-[arXiv](https://arxiv.org/abs/1811.12004).
+<a name="open-pose-1" href="https://arxiv.org/abs/1812.08008">[1]</a> OpenPose: Realtime Multi-Person 2D Pose Estimation using Part Affinity Fields, [arXiv](https://arxiv.org/abs/1812.08008).
+<a name="open-pose-2" href="https://arxiv.org/abs/1811.12004">[2]</a> Real-time 2D Multi-Person Pose Estimation on CPU: Lightweight OpenPose, [arXiv](https://arxiv.org/abs/1811.12004).

From 6ba580c41dd20650b1022a7092f638dba24a655f Mon Sep 17 00:00:00 2001
From: mthodoris <45919203+mthodoris@users.noreply.github.com>
Date: Mon, 12 Dec 2022 11:56:32 +0200
Subject: [PATCH 08/27] Apply suggestions from code review

Co-authored-by: ad-daniel <44834743+ad-daniel@users.noreply.github.com>
Co-authored-by: Nikolaos Passalis <passalis@users.noreply.github.com>
---
 .../perception/high_resolution_pose_estimation/README.md   | 6 +++---
 .../high_resolution_pose_estimation/demos/eval_demo.py     | 1 -
 .../demos/inference_demo.py                                | 1 -
 .../hr_pose_estimation/HighResolutionLearner.py            | 7 ++-----
 4 files changed, 5 insertions(+), 10 deletions(-)

diff --git a/projects/python/perception/high_resolution_pose_estimation/README.md b/projects/python/perception/high_resolution_pose_estimation/README.md
index 8342848ad2..75e19ef104 100644
--- a/projects/python/perception/high_resolution_pose_estimation/README.md
+++ b/projects/python/perception/high_resolution_pose_estimation/README.md
@@ -1,11 +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.
+This folder contains sample applications that demonstrate various parts of the functionality provided by the High Resolution Pose Estimation algorithm provided by OpenDR.
 
-More specific, the applications provided are:
+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 a 720p, 1080p, 1440p dataset. 
+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.py: A simple benchmarking tool for measuring the performance of High Resolution Pose Estimation in various platforms.
 
 
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
index f5fbe75d7e..097c8eafbc 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
@@ -1,4 +1,3 @@
-
 # Copyright 2020-2022 OpenDR European Project
 #
 # Licensed under the Apache License, Version 2.0 (the "License");
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
index 22dbe53521..41e953a4c3 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
@@ -1,4 +1,3 @@
-
 # Copyright 2020-2022 OpenDR European Project
 #
 # Licensed under the Apache License, Version 2.0 (the "License");
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
index 7f3fce3882..08cc1928dd 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
@@ -1,5 +1,4 @@
-
-"""# Copyright 2020-2022 OpenDR European Project
+# 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.
@@ -13,7 +12,6 @@
 # See the License for the specific language governing permissions and
 # limitations under the License."""
 
-# General imports
 # General imports
 import torchvision.transforms
 import onnxruntime as ort
@@ -47,7 +45,7 @@
     PoseEstimationWithShuffleNet
 
 from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.modules.load_state import \
-    load_state  # , load_from_mobilenet
+    load_state
 from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.modules.keypoints import \
     extract_keypoints, group_keypoints
 from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.datasets.coco import CocoValDataset
@@ -125,7 +123,6 @@ def __init__(self, device='cuda', backbone='mobilenet',
         self.model_train_state = True
 
     def first_pass(self, net, img):
-        height, width, _ = img.shape
 
         if 'cuda' in self.device:
             tensor_img = torch.from_numpy(img).permute(2, 0, 1).unsqueeze(0).float().cuda()

From 8d906b38eb121a19d0e34ebc8aa7fd87f478fb92 Mon Sep 17 00:00:00 2001
From: tsampazk <27914645+tsampazk@users.noreply.github.com>
Date: Mon, 12 Dec 2022 17:14:17 +0200
Subject: [PATCH 09/27] Minor fix in comments of original pose estimation node

---
 .../src/opendr_perception/scripts/pose_estimation_node.py     | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/projects/opendr_ws/src/opendr_perception/scripts/pose_estimation_node.py b/projects/opendr_ws/src/opendr_perception/scripts/pose_estimation_node.py
index 7aa661f14c..13aecca307 100755
--- a/projects/opendr_ws/src/opendr_perception/scripts/pose_estimation_node.py
+++ b/projects/opendr_ws/src/opendr_perception/scripts/pose_estimation_node.py
@@ -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:
@@ -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'))
 
 

From 5334c7e14053df8265978f3b39dff6ebdf5445ae Mon Sep 17 00:00:00 2001
From: tsampazk <27914645+tsampazk@users.noreply.github.com>
Date: Mon, 12 Dec 2022 17:15:33 +0200
Subject: [PATCH 10/27] HR pose estimation ros1 node

---
 .../src/opendr_perception/CMakeLists.txt      |   1 +
 .../scripts/hr_pose_estimation_node.py        | 164 ++++++++++++++++++
 2 files changed, 165 insertions(+)
 create mode 100755 projects/opendr_ws/src/opendr_perception/scripts/hr_pose_estimation_node.py

diff --git a/projects/opendr_ws/src/opendr_perception/CMakeLists.txt b/projects/opendr_ws/src/opendr_perception/CMakeLists.txt
index a83d022b81..95914816b1 100644
--- a/projects/opendr_ws/src/opendr_perception/CMakeLists.txt
+++ b/projects/opendr_ws/src/opendr_perception/CMakeLists.txt
@@ -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
diff --git a/projects/opendr_ws/src/opendr_perception/scripts/hr_pose_estimation_node.py b/projects/opendr_ws/src/opendr_perception/scripts/hr_pose_estimation_node.py
new file mode 100755
index 0000000000..a820c91b1c
--- /dev/null
+++ b/projects/opendr_ws/src/opendr_perception/scripts/hr_pose_estimation_node.py
@@ -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_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()

From 7ea8c7a08a318d1b0b04db1ca23a74d2d20c8913 Mon Sep 17 00:00:00 2001
From: mthodoris <45919203+mthodoris@users.noreply.github.com>
Date: Tue, 13 Dec 2022 03:21:02 +0200
Subject: [PATCH 11/27] Apply suggestions from code review

Co-authored-by: ad-daniel <44834743+ad-daniel@users.noreply.github.com>
Co-authored-by: Kostas Tsampazis <27914645+tsampazk@users.noreply.github.com>
---
 .../high_resolution_pose_estimation.md        | 70 ++++++++++---------
 .../demos/benchmarking_demo.py                |  1 +
 .../demos/eval_demo.py                        |  2 +
 .../HighResolutionLearner.py                  | 16 ++---
 4 files changed, 47 insertions(+), 42 deletions(-)

diff --git a/docs/reference/high_resolution_pose_estimation.md b/docs/reference/high_resolution_pose_estimation.md
index af0664d939..dd9d675347 100644
--- a/docs/reference/high_resolution_pose_estimation.md
+++ b/docs/reference/high_resolution_pose_estimation.md
@@ -6,16 +6,17 @@ The *high_resolution_pose_estimation* module contains the *HighResolutionPoseEst
 Bases: `engine.learners.Learner`
 
 The *HighResolutionLightweightOpenPose* class is an implementation for pose estimation in high resolution images.
-This method is creating a heatmap of a resized version of the input image.
-Using this heatmap, the input image is being cropped keeping the area of interest and then it isused for pose estimation. The pose estimation is based on the Lightweight OpenPose algorithm.
-In this method there are two important variables which are responsible for the increase in speed and in accuracy in high resolution images.
-These variables are the *first_pass_height* and the *second height* that the image is resized in this procedure.
+This method creates a heatmap of a resized version of the input image.
+Using this heatmap, the input image is cropped keeping the area of interest and then it is used for pose estimation.
+The pose estimation is based on the Lightweight OpenPose algorithm.
+In this method there are two important variables which are responsible for the increase in speed and accuracy in high resolution images.
+These variables are the *first_pass_height* and the *second_pass_height* that the image is resized in this procedure.
 
-The [HighResolutionPoseEstiamtionLearner](/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py) class has the following public methods:
+The [HighResolutionPoseEstimationLearner](/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py) class has the following public methods:
 
 #### `HighResolutionPoseEstimationLearner` constructor
 ```python
-HighResolutionPoseEstimationLearner(self,device, backbone, temp_path, mobilenet_use_stride, mobilenetv2_width, shufflenet_groups, num_refinement_stages, batches_per_iter, base_height, first_pass_height, second_pass_height, img_resol, experiment_name, num_workers, weights_only, output_name, multiscale, scales, visualize,  img_mean, img_scale, pad_value)
+HighResolutionPoseEstimationLearner(self, device, backbone, temp_path, mobilenet_use_stride, mobilenetv2_width, shufflenet_groups, num_refinement_stages, batches_per_iter, base_height, first_pass_height, second_pass_height, img_resol, experiment_name, num_workers, weights_only, output_name, multiscale, scales, visualize,  img_mean, img_scale, pad_value, half_precision)
 ```
 
 Constructor parameters:
@@ -25,11 +26,12 @@ Constructor parameters:
 - **backbone**: *{'mobilenet, 'mobilenetv2', 'shufflenet'}, default='mobilenet'*\
   Specifies the backbone architecture.
 - **temp_path**: *str, default='temp'*\
-  Specifies a path where the algorithm looks for pretrained backbone weights, the checkpoints are saved along with the logging files. Moreover the JSON file that contains the evaluation detections is saved here.
+  Specifies a path where the algorithm looks for pretrained backbone weights, the checkpoints are saved along with the logging files.
+  Moreover the JSON file that contains the evaluation detections is saved here.
 - **mobilenet_use_stride**: *bool, default=True*\
-  Whether to add an additional stride value in the mobilenet model, which reduces accuracy but increases inference speed.
+  Whether to add a stride value in the mobilenet model, which reduces accuracy but increases inference speed.
 - **mobilenetv2_width**: *[0.0 - 1.0], default=1.0*\
-  If the mobilenetv2 backbone is used, this parameter specified its size.
+  If the mobilenetv2 backbone is used, this parameter specifies its size.
 - **shufflenet_groups**: *int, default=3*\
   If the shufflenet backbone is used, it specifies the number of groups to be used in grouped 1x1 convolutions in each ShuffleUnit.
 - **num_refinement_stages**: *int, default=2*\
@@ -40,7 +42,7 @@ Constructor parameters:
   Specifies the height, based on which the images will be resized before performing the forward pass when using the Lightweight OpenPose.
 - **first_pass_height**: *int, default=360*\
   Specifies the height that the input image will be resized during the heatmap generation procedure.
-- **second_pass_heght**: *int, default=540*\
+- **second_pass_height**: *int, default=540*\
   Specifies the height of the image on the second inference for pose estimation procedure.
 - **experiment_name**: *str, default='default'*\
   String name to attach to checkpoints.
@@ -49,13 +51,15 @@ Constructor parameters:
 - **weights_only**: *bool, default=True*\
   If True, only the model weights will be loaded; it won't load optimizer, scheduler, num_iter, current_epoch information.
 - **output_name**: *str, default='detections.json'*\
-  The name of the json files where the evaluation detections are stored, inside the temp_path.
+  The name of the json file where the evaluation detections are stored, inside the temp_path.
 - **multiscale**: *bool, default=False*\
-  Specifies whether evaluation will run in the predefined multiple scales setup or not. It overwrites self.scales to [0.5, 1.0, 1.5, 2.0].
+  Specifies whether evaluation will run in the predefined multiple scales setup or not.
+  It overwrites self.scales to [0.5, 1.0, 1.5, 2.0].
 - **scales**: *list, default=None*\
-  A list of integer scales that define the multiscale evaluation setup. Used to manually set the scales instead of going for the predefined multiscale setup.
+  A list of integer scales that define the multiscale evaluation setup.
+  Used to manually set the scales instead of going for the predefined multiscale setup.
 - **visualize**: *bool, default=False*\
-  Specifies whether the images along with the poses will be shown, one by one during evaluation.
+  Specifies whether the images along with the poses will be shown, one by one, during evaluation.
 - **img_mean**: *list, default=(128, 128, 128)]*\
   Specifies the mean based on which the images are normalized.
 - **img_scale**: *float, default=1/256*\
@@ -66,14 +70,13 @@ Constructor parameters:
   Enables inference using half (fp16) precision instead of single (fp32) precision. Valid only for GPU-based inference.
 
 
-
 #### `HighResolutionPoseEstimationLearner.eval`
 ```python
 HighResolutionPoseEstimationLearner.eval(self, dataset, silent, verbose, use_subset, subset_size, images_folder_name, annotations_filename)
 ```
 
 This method is used to evaluate a trained model on an evaluation dataset.
-Returns a dictionary containing stats regarding evaluation.
+Returns a dictionary containing statistics regarding evaluation.
 
 Parameters:
 
@@ -84,7 +87,7 @@ Parameters:
   If set to True, disables all printing of evaluation progress reports and other information to STDOUT.
 - **verbose**: *bool, default=True*\
   If set to True, enables the maximum verbosity.
-- **val_subset**: *bool, default=True*\
+- **use_subset**: *bool, default=True*\
   If set to True, a subset of the validation dataset is created and used in evaluation.
 - **subset_size**: *int, default=250*\
   Controls the size of the validation subset.
@@ -98,7 +101,7 @@ Parameters:
 
 #### `HighResolutionPoseEstimation.infer`
 ```python
-HighResolutionPoseEstimation.infer(img, upsample_ratio, track, smooth)
+HighResolutionPoseEstimation.infer(self, img, upsample_ratio, stride, track, smooth, multiscale, visualize)
 ```
 
 This method is used to perform pose estimation on an image.
@@ -118,12 +121,13 @@ Parameters:
 
 #### `HighResolutionPoseEstimationLearner.first_pass`
 ```python
-HighResolutionPoseEstimationLearner.first_pass(self, net,img)
+HighResolutionPoseEstimationLearner.first_pass(self, net, img)
 ```
 
 This method is used for extracting from the input image a heatmap about human locations in the picture.
 
 Parameters:
+
 - **img**: *object***\
   Object of type engine.data.Image.
 - **net**: *object*\
@@ -131,9 +135,7 @@ Parameters:
 
 #### `HighResolutionPoseEstimationLearner.second_pass`
 ```python
-HighResolutionPoseEstimationLearner.second_pass_infer(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, device,
-                          pad_value=(0, 0, 0),
-                          img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256))
+HighResolutionPoseEstimationLearner.second_pass_infer(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, pad_value, img_mean, img_scale)
 ```
 
 On this method it is carried out the second inference step which estimates the human poses on the image that is inserted.
@@ -153,8 +155,6 @@ Parameters:
   Is the stride value of mobilenet which reduces accuracy but increases inference speed.
 - **upsample_ratio**: *int, default=4*\
   Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing.
-- **device**: *{'cpu', 'cuda'}, default='cuda'*\
-  Specifies the device to be used.
 - **pad_value**: *list, default=(0, 0, 0)*\
   Specifies the pad value based on which the images' width is padded.
 - **img_mean**: *list, default=(128, 128, 128)]*\
@@ -162,7 +162,7 @@ Parameters:
 - **img_scale**: *float, default=1/256*\
   Specifies the scale based on which the images are normalized.
 
-#### `HighResolutionPoseEstimation.Pooling`
+#### `HighResolutionPoseEstimation.pooling`
 ```python
 HighResolutionPoseEstimation.Pooling(self, img, kernel)
 ```
@@ -176,7 +176,7 @@ Parameters:
 
 #### `HighResolutionPoseEstimation.infer_light_odr()`
 ```python
-HighResolutionPoseEstimation.infer_light_odr(self, img, upsample_ratio=4, track=True, smooth=True)
+HighResolutionPoseEstimation.infer_light_odr(self, img, upsample_ratio, track, smooth)
 ```
 
 This method is an inference function of OpenDR LightWeight OpenPose pose estiamtion.
@@ -192,7 +192,7 @@ Parameters:
 - **smooth**: *bool, default=True*\
   If True, smoothing is performed on pose keypoints between frames.
 
-#### `HighResolutionPoseEstiamtion.save`
+#### `HighResolutionPoseEstimation.save`
 ```python
 HighResolutionPoseEstimation.save(self, path, verbose)
 ```
@@ -257,10 +257,10 @@ Parameters:
   from opendr.engine.data import Image
 
   pose_estimator = HighResolutionPoseEstimationLearner(device='cuda', num_refinement_stages=2,
-                                                           mobilenet_use_stride=False, half_precision=False,
-                                                           first_pass_height=360,
-                                                           second_pass_height=540,
-                                                           img_resol=1080)
+                                                       mobilenet_use_stride=False, half_precision=False,
+                                                       first_pass_height=360,
+                                                       second_pass_height=540,
+                                                       img_resol=1080)
   pose_estimator.download()  # Download the default pretrained mobilenet model in the temp_path
 
   pose_estimator.load("./parent_dir/openpose_default")
@@ -281,8 +281,10 @@ Parameters:
 #### Performance Evaluation
 
 
-In order to check the performance of the *HighResolutionPoseEstimationLearner* it had been tested on various platforms and with different optimizations that Lightweight OpenPose offers.
+In order to check the performance of the *HighResolutionPoseEstimationLearner* it has been tested on various platforms and with different optimizations that Lightweight OpenPose offers.
 The experiments are conducted on a 1080p image.
+
+
 #### Lightweight OpenPose With resizing on 256 pixels
 |                    **Method**                    | **CPU i7-9700K (FPS)** | **RTX 2070 (FPS)** | **Jetson TX2 (FPS)** | **Xavier NX (FPS)** |
 |:------------------------------------------------:|-----------------------|-------------------|----------------------|---------------------|
@@ -307,8 +309,8 @@ The experiments are conducted on a 1080p image.
 | HRPoseEstim - H+S      | 8.2                | 25.9           | 3.6              | 5.5             |
 | HRPoseEstim - Full     | 10.9               | 31.7           | 4.8              | 6.9             |
 
-As it is shown in the previous Table, OpenDr Lightweight OpenPose achieves higher FPS when it is resing the input image into 256 pixels.
-It is easier to process that image but as it is shown in the next tables the method falls apart when it comes to accuracy and there are no detections.
+As it is shown in the previous Table, OpenDR Lightweight OpenPose achieves higher FPS when it is resing the input image into 256 pixels.
+It is easier to process that image, but as it is shown in the next tables the method falls apart when it comes to accuracy and there are no detections.
 
 We have evaluated the effect of using different inference settings, namely:
 - *HRPoseEstim - Baseline*, which refers to directly using the High Resolution Pose Estimation method,which is based in Lightweight OpenPose,
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
index ffe56ccb52..7fc66de1f0 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
@@ -20,6 +20,7 @@
 from tqdm import tqdm
 import numpy as np
 
+
 if __name__ == '__main__':
     parser = argparse.ArgumentParser()
     parser.add_argument("--onnx", help="Use ONNX", default=False, action="store_true")
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
index 097c8eafbc..5c1c9100ff 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
@@ -17,6 +17,8 @@
 from os.path import join
 from opendr.engine.datasets import ExternalDataset
 import time
+
+
 if __name__ == '__main__':
     parser = argparse.ArgumentParser()
     parser.add_argument("--onnx", help="Use ONNX", default=False, action="store_true")
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
index 08cc1928dd..bb7b53d25f 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
@@ -320,8 +320,8 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
 
         pbar_eval = None
         if not silent:
-            pbarDesc = "Evaluation progress"
-            pbar_eval = tqdm(desc=pbarDesc, total=len(data), bar_format="{l_bar}%s{bar}{r_bar}" % '\x1b[38;5;231m')
+            pbar_desc = "Evaluation progress"
+            pbar_eval = tqdm(desc=pbar_desc, total=len(data), bar_format="{l_bar}%s{bar}{r_bar}" % '\x1b[38;5;231m')
 
         img_height = data[0]['img'].shape[0]
 
@@ -346,14 +346,14 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
 
             perc = 0.3  # percentage around cropping
 
-            thresshold = 0.1  # thresshold for heatmap
+            threshold = 0.1  # threshold for heatmap
 
             # ------- Heatmap Generation -------
             avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.model, pool_img)
             avg_pafs = avg_pafs.astype(np.float32)
 
             pafs_map = cv2.blur(avg_pafs, (5, 5))
-            pafs_map[pafs_map < thresshold] = 0
+            pafs_map[pafs_map < threshold] = 0
 
             heatmap = pafs_map.sum(axis=2)
             heatmap = heatmap * 100
@@ -489,7 +489,7 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
         if not isinstance(img, Image):
             img = Image(img)
 
-            # Bring image into the appropriate format for the implementation
+        # Bring image into the appropriate format for the implementation
         img = img.convert(format='channels_last', channel_order='bgr')
 
         h, w, _ = img.shape
@@ -503,14 +503,14 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
         perc = 0.3  # percentage around cropping
 
-        thresshold = 0.1  # threshold for heatmap
+        threshold = 0.1  # threshold for heatmap
 
         # ------- Heatmap Generation -------
         avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.model, pool_img)
         avg_pafs = avg_pafs.astype(np.float32)
         pafs_map = cv2.blur(avg_pafs, (5, 5))
 
-        pafs_map[pafs_map < thresshold] = 0
+        pafs_map[pafs_map < threshold] = 0
 
         heatmap = pafs_map.sum(axis=2)
         heatmap = heatmap * 100
@@ -761,7 +761,7 @@ def __load_from_onnx(self, path):
         # # Check that the IR is well formed
         # onnx.checker.check_model(self.model)
         #
-        # # Print a human readable representation of the graph
+        # # Print a human-readable representation of the graph
         # onnx.helper.printable_graph(self.model.graph)
 
     @staticmethod

From c209bfe5f131f66261acc08eddf4969090f70f00 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Tue, 13 Dec 2022 03:38:05 +0200
Subject: [PATCH 12/27] suggestions from review (edit functions, code
 duplication,typos,etc)

---
 .../demos/inference_demo.py                   |   1 -
 .../perception/pose_estimation/__init__.py    |   2 +-
 .../hr_pose_estimation/algorithm/README.md    |  44 --
 .../hr_pose_estimation/algorithm/__init__.py  |   0
 .../algorithm/datasets/__init__.py            |   0
 .../algorithm/datasets/coco.py                | 180 --------
 .../algorithm/datasets/transformations.py     | 249 -----------
 .../algorithm/models/__init__.py              |   0
 .../algorithm/models/with_mobilenet.py        | 126 ------
 .../algorithm/models/with_mobilenet_v2.py     | 252 -----------
 .../algorithm/models/with_shufflenet.py       | 422 ------------------
 .../algorithm/modules/__init__.py             |   0
 .../algorithm/modules/conv.py                 |  32 --
 .../algorithm/modules/get_parameters.py       |  21 -
 .../algorithm/modules/keypoints.py            | 159 -------
 .../algorithm/modules/load_state.py           |  35 --
 .../algorithm/modules/loss.py                 |   5 -
 .../algorithm/modules/one_euro_filter.py      |  51 ---
 .../algorithm/scripts/__init__.py             |   0
 .../algorithm/scripts/make_val_subset.py      |  43 --
 .../algorithm/scripts/prepare_train_labels.py | 122 -----
 .../hr_pose_estimation/algorithm/val.py       | 161 -------
 .../hr_pose_estimation/filtered_pose.py       |  22 -
 ...nLearner.py => high_resolution_learner.py} | 293 ++++--------
 .../hr_pose_estimation/utilities.py           | 153 -------
 tests/test_license.py                         |   1 -
 26 files changed, 90 insertions(+), 2284 deletions(-)
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/__init__.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/__init__.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/coco.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/transformations.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/__init__.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet_v2.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_shufflenet.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/__init__.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/conv.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/get_parameters.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/keypoints.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/load_state.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/loss.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/one_euro_filter.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/__init__.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/make_val_subset.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/prepare_train_labels.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/val.py
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/filtered_pose.py
 rename src/opendr/perception/pose_estimation/hr_pose_estimation/{HighResolutionLearner.py => high_resolution_learner.py} (77%)
 delete mode 100644 src/opendr/perception/pose_estimation/hr_pose_estimation/utilities.py

diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
index 41e953a4c3..df6d62df6f 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
@@ -14,7 +14,6 @@
 
 import cv2
 from opendr.perception.pose_estimation import HighResolutionPoseEstimationLearner
-
 from opendr.perception.pose_estimation import draw
 from opendr.engine.data import Image
 import argparse
diff --git a/src/opendr/perception/pose_estimation/__init__.py b/src/opendr/perception/pose_estimation/__init__.py
index dc42947a02..66e9725a6a 100644
--- a/src/opendr/perception/pose_estimation/__init__.py
+++ b/src/opendr/perception/pose_estimation/__init__.py
@@ -1,6 +1,6 @@
 from opendr.perception.pose_estimation.lightweight_open_pose.lightweight_open_pose_learner import \
     LightweightOpenPoseLearner
-from opendr.perception.pose_estimation.hr_pose_estimation.HighResolutionLearner import \
+from opendr.perception.pose_estimation.hr_pose_estimation.high_resolution_learner import \
     HighResolutionPoseEstimationLearner
 
 from opendr.perception.pose_estimation.lightweight_open_pose.utilities import draw, get_bbox
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md
deleted file mode 100644
index eeaed7e202..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/README.md
+++ /dev/null
@@ -1,44 +0,0 @@
-# OpenDR High Resolution Pose Estimation
-
-This folder contains the Open Pose[1] algorithm implementation for high resolution pose estimation in the OpenDR Toolkit, 
-in the form of Lightweight Open Pose [2].
-
-## Sources
-
-The algorithms files are copied from [Daniil-Osokin/lightweight-human-pose-estimation.pytorch](
-https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch) with minor modifications listed below:
-
-1. `datasets/coco.py`: PEP8 changes
-2. `datasets/transformations.py`: PEP8 changes
-3. `models/with_mobilenet`: PEP8 changes
-4. `modules/conv.py`: PEP8 changes
-5. `modules/get_parameters.py`: PEP8 changes
-6. `modules/keypoints.py`: PEP8 changes
-7. `modules/load_state.py`: 
-    - Modified `load_state()` by adding a try/except block
-    - Commented out warning prints from both functions
-8. `modules/loss.py`: PEP8 changes
-9. `one_euro_filter.py`:  PEP8 changes
-10. `scripts/make_val_subset.py`: Modified to work as a callable function
-11. `scripts/prepare_train_labels.py`:
-    - PEP8 changes
-    - Modified to work as a callable function
-12. `val.py`: 
-    - PEP8 changes
-    - Removed `main`
-    - Added verbose conditionals in `run_coco_eval()`
-
-## Added Files
-Two additional backbone models were added in the `models` directory.
-
-- `models/with_mobilenet_v2.py`: Copied from [tonylins/pytorch-mobilenet-v2](
-https://github.com/tonylins/pytorch-mobilenet-v2) and modified to work as a backbone for pose estimation.
-- `models/with_shufflenet.py`: Copied from [jaxony/ShuffleNet](https://github.com/jaxony/ShuffleNet) and modified to 
-work as a backbone for pose estimation. 
-
-## References
-
-- [1]: OpenPose: Realtime Multi-Person 2D Pose Estimation using Part Affinity Fields, 
-[arXiv](https://arxiv.org/abs/1812.08008).
-- [2]: Real-time 2D Multi-Person Pose Estimation on CPU: Lightweight OpenPose, 
-[arXiv](https://arxiv.org/abs/1811.12004).
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/__init__.py
deleted file mode 100644
index e69de29bb2..0000000000
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/__init__.py
deleted file mode 100644
index e69de29bb2..0000000000
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/coco.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/coco.py
deleted file mode 100644
index a9551d37aa..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/coco.py
+++ /dev/null
@@ -1,180 +0,0 @@
-import copy
-import json
-import math
-import os
-import pickle
-
-import cv2
-import numpy as np
-import pycocotools
-
-from torch.utils.data.dataset import Dataset
-
-BODY_PARTS_KPT_IDS = [[1, 8], [8, 9], [9, 10], [1, 11], [11, 12], [12, 13], [1, 2], [2, 3], [3, 4], [2, 16],
-                      [1, 5], [5, 6], [6, 7], [5, 17], [1, 0], [0, 14], [0, 15], [14, 16], [15, 17]]
-
-
-def get_mask(segmentations, mask):
-    for segmentation in segmentations:
-        rle = pycocotools.mask.frPyObjects(segmentation, mask.shape[0], mask.shape[1])
-        mask[pycocotools.mask.decode(rle) > 0.5] = 0
-    return mask
-
-
-class CocoTrainDataset(Dataset):
-    def __init__(self, labels, images_folder, stride, sigma, paf_thickness, transform=None):
-        super().__init__()
-        self._images_folder = images_folder
-        self._stride = stride
-        self._sigma = sigma
-        self._paf_thickness = paf_thickness
-        self._transform = transform
-        with open(labels, 'rb') as f:
-            self._labels = pickle.load(f)
-
-    def __getitem__(self, idx):
-        label = copy.deepcopy(self._labels[idx])  # label modified in transform
-        image = cv2.imread(os.path.join(self._images_folder, label['img_paths']), cv2.IMREAD_COLOR)
-        mask = np.ones(shape=(label['img_height'], label['img_width']), dtype=np.float32)
-        mask = get_mask(label['segmentations'], mask)
-        sample = {
-            'label': label,
-            'image': image,
-            'mask': mask
-        }
-        if self._transform:
-            sample = self._transform(sample)
-
-        mask = cv2.resize(sample['mask'], dsize=None, fx=1 / self._stride, fy=1 / self._stride,
-                          interpolation=cv2.INTER_AREA)
-        keypoint_maps = self._generate_keypoint_maps(sample)
-        sample['keypoint_maps'] = keypoint_maps
-        keypoint_mask = np.zeros(shape=keypoint_maps.shape, dtype=np.float32)
-        for idx in range(keypoint_mask.shape[0]):
-            keypoint_mask[idx] = mask
-        sample['keypoint_mask'] = keypoint_mask
-
-        paf_maps = self._generate_paf_maps(sample)
-        sample['paf_maps'] = paf_maps
-        paf_mask = np.zeros(shape=paf_maps.shape, dtype=np.float32)
-        for idx in range(paf_mask.shape[0]):
-            paf_mask[idx] = mask
-        sample['paf_mask'] = paf_mask
-
-        image = sample['image'].astype(np.float32)
-        image = (image - 128) / 256
-        sample['image'] = image.transpose((2, 0, 1))
-        del sample['label']
-        return sample
-
-    def __len__(self):
-        return len(self._labels)
-
-    def _generate_keypoint_maps(self, sample):
-        n_keypoints = 18
-        n_rows, n_cols, _ = sample['image'].shape
-        keypoint_maps = np.zeros(shape=(n_keypoints + 1,
-                                        n_rows // self._stride, n_cols // self._stride), dtype=np.float32)  # +1 for bg
-
-        label = sample['label']
-        for keypoint_idx in range(n_keypoints):
-            keypoint = label['keypoints'][keypoint_idx]
-            if keypoint[2] <= 1:
-                self._add_gaussian(keypoint_maps[keypoint_idx], keypoint[0], keypoint[1], self._stride, self._sigma)
-            for another_annotation in label['processed_other_annotations']:
-                keypoint = another_annotation['keypoints'][keypoint_idx]
-                if keypoint[2] <= 1:
-                    self._add_gaussian(keypoint_maps[keypoint_idx], keypoint[0], keypoint[1], self._stride, self._sigma)
-        keypoint_maps[-1] = 1 - keypoint_maps.max(axis=0)
-        return keypoint_maps
-
-    def _add_gaussian(self, keypoint_map, x, y, stride, sigma):
-        n_sigma = 4
-        tl = [int(x - n_sigma * sigma), int(y - n_sigma * sigma)]
-        tl[0] = max(tl[0], 0)
-        tl[1] = max(tl[1], 0)
-
-        br = [int(x + n_sigma * sigma), int(y + n_sigma * sigma)]
-        map_h, map_w = keypoint_map.shape
-        br[0] = min(br[0], map_w * stride)
-        br[1] = min(br[1], map_h * stride)
-
-        shift = stride / 2 - 0.5
-        for map_y in range(tl[1] // stride, br[1] // stride):
-            for map_x in range(tl[0] // stride, br[0] // stride):
-                d2 = (map_x * stride + shift - x) * (map_x * stride + shift - x) + \
-                     (map_y * stride + shift - y) * (map_y * stride + shift - y)
-                exponent = d2 / 2 / sigma / sigma
-                if exponent > 4.6052:  # threshold, ln(100), ~0.01
-                    continue
-                keypoint_map[map_y, map_x] += math.exp(-exponent)
-                if keypoint_map[map_y, map_x] > 1:
-                    keypoint_map[map_y, map_x] = 1
-
-    def _generate_paf_maps(self, sample):
-        n_pafs = len(BODY_PARTS_KPT_IDS)
-        n_rows, n_cols, _ = sample['image'].shape
-        paf_maps = np.zeros(shape=(n_pafs * 2, n_rows // self._stride, n_cols // self._stride), dtype=np.float32)
-
-        label = sample['label']
-        for paf_idx in range(n_pafs):
-            keypoint_a = label['keypoints'][BODY_PARTS_KPT_IDS[paf_idx][0]]
-            keypoint_b = label['keypoints'][BODY_PARTS_KPT_IDS[paf_idx][1]]
-            if keypoint_a[2] <= 1 and keypoint_b[2] <= 1:
-                self._set_paf(paf_maps[paf_idx * 2:paf_idx * 2 + 2],
-                              keypoint_a[0], keypoint_a[1], keypoint_b[0], keypoint_b[1],
-                              self._stride, self._paf_thickness)
-            for another_annotation in label['processed_other_annotations']:
-                keypoint_a = another_annotation['keypoints'][BODY_PARTS_KPT_IDS[paf_idx][0]]
-                keypoint_b = another_annotation['keypoints'][BODY_PARTS_KPT_IDS[paf_idx][1]]
-                if keypoint_a[2] <= 1 and keypoint_b[2] <= 1:
-                    self._set_paf(paf_maps[paf_idx * 2:paf_idx * 2 + 2],
-                                  keypoint_a[0], keypoint_a[1], keypoint_b[0], keypoint_b[1],
-                                  self._stride, self._paf_thickness)
-        return paf_maps
-
-    def _set_paf(self, paf_map, x_a, y_a, x_b, y_b, stride, thickness):
-        x_a /= stride
-        y_a /= stride
-        x_b /= stride
-        y_b /= stride
-        x_ba = x_b - x_a
-        y_ba = y_b - y_a
-        _, h_map, w_map = paf_map.shape
-        x_min = int(max(min(x_a, x_b) - thickness, 0))
-        x_max = int(min(max(x_a, x_b) + thickness, w_map))
-        y_min = int(max(min(y_a, y_b) - thickness, 0))
-        y_max = int(min(max(y_a, y_b) + thickness, h_map))
-        norm_ba = (x_ba * x_ba + y_ba * y_ba) ** 0.5
-        if norm_ba < 1e-7:  # Same points, no paf
-            return
-        x_ba /= norm_ba
-        y_ba /= norm_ba
-
-        for y in range(y_min, y_max):
-            for x in range(x_min, x_max):
-                x_ca = x - x_a
-                y_ca = y - y_a
-                d = math.fabs(x_ca * y_ba - y_ca * x_ba)
-                if d <= thickness:
-                    paf_map[0, y, x] = x_ba
-                    paf_map[1, y, x] = y_ba
-
-
-class CocoValDataset(Dataset):
-    def __init__(self, labels, images_folder):
-        super().__init__()
-        with open(labels, 'r') as f:
-            self._labels = json.load(f)
-        self._images_folder = images_folder
-
-    def __getitem__(self, idx):
-        file_name = self._labels['images'][idx]['file_name']
-        img = cv2.imread(os.path.join(self._images_folder, file_name), cv2.IMREAD_COLOR)
-        return {
-            'img': img,
-            'file_name': file_name
-        }
-
-    def __len__(self):
-        return len(self._labels['images'])
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/transformations.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/transformations.py
deleted file mode 100644
index 99295f8e76..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/datasets/transformations.py
+++ /dev/null
@@ -1,249 +0,0 @@
-import random
-
-import cv2
-import numpy as np
-
-
-class ConvertKeypoints:
-    def __call__(self, sample):
-        label = sample['label']
-        h, w, _ = sample['image'].shape
-        keypoints = label['keypoints']
-        for keypoint in keypoints:  # keypoint[2] == 0: occluded, == 1: visible, == 2: not in image
-            if keypoint[0] == keypoint[1] == 0:
-                keypoint[2] = 2
-            if keypoint[0] < 0 or keypoint[0] >= w or keypoint[1] < 0 or keypoint[1] >= h:
-                keypoint[2] = 2
-        for other_label in label['processed_other_annotations']:
-            keypoints = other_label['keypoints']
-            for keypoint in keypoints:
-                if keypoint[0] == keypoint[1] == 0:
-                    keypoint[2] = 2
-                if keypoint[0] < 0 or keypoint[0] >= w or keypoint[1] < 0 or keypoint[1] >= h:
-                    keypoint[2] = 2
-        label['keypoints'] = self._convert(label['keypoints'], w, h)
-
-        for other_label in label['processed_other_annotations']:
-            other_label['keypoints'] = self._convert(other_label['keypoints'], w, h)
-        return sample
-
-    def _convert(self, keypoints, w, h):
-        # Nose, Neck, R hand, L hand, R leg, L leg, Eyes, Ears
-        reorder_map = [1, 7, 9, 11, 6, 8, 10, 13, 15, 17, 12, 14, 16, 3, 2, 5, 4]
-        converted_keypoints = list(keypoints[i - 1] for i in reorder_map)
-        converted_keypoints.insert(1, [(keypoints[5][0] + keypoints[6][0]) / 2,
-                                       (keypoints[5][1] + keypoints[6][1]) / 2, 0])  # Add neck as a mean of shoulders
-        if keypoints[5][2] == 2 or keypoints[6][2] == 2:
-            converted_keypoints[1][2] = 2
-        elif keypoints[5][2] == 1 and keypoints[6][2] == 1:
-            converted_keypoints[1][2] = 1
-        if converted_keypoints[1][0] < 0 or converted_keypoints[1][0] >= w or converted_keypoints[1][1] < 0 or \
-                converted_keypoints[1][1] >= h:
-            converted_keypoints[1][2] = 2
-        return converted_keypoints
-
-
-class Scale:
-    def __init__(self, prob=1, min_scale=0.5, max_scale=1.1, target_dist=0.6):
-        self._prob = prob
-        self._min_scale = min_scale
-        self._max_scale = max_scale
-        self._target_dist = target_dist
-
-    def __call__(self, sample):
-        prob = random.random()
-        scale_multiplier = 1
-        if prob <= self._prob:
-            prob = random.random()
-            scale_multiplier = (self._max_scale - self._min_scale) * prob + self._min_scale
-        label = sample['label']
-        scale_abs = self._target_dist / label['scale_provided']
-        scale = scale_abs * scale_multiplier
-        sample['image'] = cv2.resize(sample['image'], dsize=(0, 0), fx=scale, fy=scale)
-        label['img_height'], label['img_width'], _ = sample['image'].shape
-        sample['mask'] = cv2.resize(sample['mask'], dsize=(0, 0), fx=scale, fy=scale)
-
-        label['objpos'][0] *= scale
-        label['objpos'][1] *= scale
-        for keypoint in sample['label']['keypoints']:
-            keypoint[0] *= scale
-            keypoint[1] *= scale
-        for other_annotation in sample['label']['processed_other_annotations']:
-            other_annotation['objpos'][0] *= scale
-            other_annotation['objpos'][1] *= scale
-            for keypoint in other_annotation['keypoints']:
-                keypoint[0] *= scale
-                keypoint[1] *= scale
-        return sample
-
-
-class Rotate:
-    def __init__(self, pad, max_rotate_degree=40):
-        self._pad = pad
-        self._max_rotate_degree = max_rotate_degree
-
-    def __call__(self, sample):
-        prob = random.random()
-        degree = (prob - 0.5) * 2 * self._max_rotate_degree
-        h, w, _ = sample['image'].shape
-        img_center = (w / 2, h / 2)
-        R = cv2.getRotationMatrix2D(img_center, degree, 1)
-
-        abs_cos = abs(R[0, 0])
-        abs_sin = abs(R[0, 1])
-
-        bound_w = int(h * abs_sin + w * abs_cos)
-        bound_h = int(h * abs_cos + w * abs_sin)
-        dsize = (bound_w, bound_h)
-
-        R[0, 2] += dsize[0] / 2 - img_center[0]
-        R[1, 2] += dsize[1] / 2 - img_center[1]
-        sample['image'] = cv2.warpAffine(sample['image'], R, dsize=dsize,
-                                         borderMode=cv2.BORDER_CONSTANT, borderValue=self._pad)
-        sample['label']['img_height'], sample['label']['img_width'], _ = sample['image'].shape
-        sample['mask'] = cv2.warpAffine(sample['mask'], R, dsize=dsize,
-                                        borderMode=cv2.BORDER_CONSTANT, borderValue=(1, 1, 1))  # border is ok
-        label = sample['label']
-        label['objpos'] = self._rotate(label['objpos'], R)
-        for keypoint in label['keypoints']:
-            point = [keypoint[0], keypoint[1]]
-            point = self._rotate(point, R)
-            keypoint[0], keypoint[1] = point[0], point[1]
-        for other_annotation in label['processed_other_annotations']:
-            for keypoint in other_annotation['keypoints']:
-                point = [keypoint[0], keypoint[1]]
-                point = self._rotate(point, R)
-                keypoint[0], keypoint[1] = point[0], point[1]
-        return sample
-
-    def _rotate(self, point, R):
-        return [R[0, 0] * point[0] + R[0, 1] * point[1] + R[0, 2],
-                R[1, 0] * point[0] + R[1, 1] * point[1] + R[1, 2]]
-
-
-class CropPad:
-    def __init__(self, pad, center_perterb_max=40, crop_x=368, crop_y=368):
-        self._pad = pad
-        self._center_perterb_max = center_perterb_max
-        self._crop_x = crop_x
-        self._crop_y = crop_y
-
-    def __call__(self, sample):
-        prob_x = random.random()
-        prob_y = random.random()
-
-        offset_x = int((prob_x - 0.5) * 2 * self._center_perterb_max)
-        offset_y = int((prob_y - 0.5) * 2 * self._center_perterb_max)
-        label = sample['label']
-        shifted_center = (label['objpos'][0] + offset_x, label['objpos'][1] + offset_y)
-        offset_left = -int(shifted_center[0] - self._crop_x / 2)
-        offset_up = -int(shifted_center[1] - self._crop_y / 2)
-
-        cropped_image = np.empty(shape=(self._crop_y, self._crop_x, 3), dtype=np.uint8)
-        for i in range(3):
-            cropped_image[:, :, i].fill(self._pad[i])
-        cropped_mask = np.empty(shape=(self._crop_y, self._crop_x), dtype=np.uint8)
-        cropped_mask.fill(1)
-
-        image_x_start = int(shifted_center[0] - self._crop_x / 2)
-        image_y_start = int(shifted_center[1] - self._crop_y / 2)
-        image_x_finish = image_x_start + self._crop_x
-        image_y_finish = image_y_start + self._crop_y
-        crop_x_start = 0
-        crop_y_start = 0
-        crop_x_finish = self._crop_x
-        crop_y_finish = self._crop_y
-
-        w, h = label['img_width'], label['img_height']
-        should_crop = True
-        if image_x_start < 0:  # Adjust crop area
-            crop_x_start -= image_x_start
-            image_x_start = 0
-        if image_x_start >= w:
-            should_crop = False
-
-        if image_y_start < 0:
-            crop_y_start -= image_y_start
-            image_y_start = 0
-        if image_y_start >= h:
-            should_crop = False
-
-        if image_x_finish > w:
-            diff = image_x_finish - w
-            image_x_finish -= diff
-            crop_x_finish -= diff
-        if image_x_finish < 0:
-            should_crop = False
-
-        if image_y_finish > h:
-            diff = image_y_finish - h
-            image_y_finish -= diff
-            crop_y_finish -= diff
-        if image_y_finish < 0:
-            should_crop = False
-
-        if should_crop:
-            cropped_image[crop_y_start:crop_y_finish, crop_x_start:crop_x_finish, :] = \
-                sample['image'][image_y_start:image_y_finish, image_x_start:image_x_finish, :]
-            cropped_mask[crop_y_start:crop_y_finish, crop_x_start:crop_x_finish] = \
-                sample['mask'][image_y_start:image_y_finish, image_x_start:image_x_finish]
-
-        sample['image'] = cropped_image
-        sample['mask'] = cropped_mask
-        label['img_width'] = self._crop_x
-        label['img_height'] = self._crop_y
-
-        label['objpos'][0] += offset_left
-        label['objpos'][1] += offset_up
-        for keypoint in label['keypoints']:
-            keypoint[0] += offset_left
-            keypoint[1] += offset_up
-        for other_annotation in label['processed_other_annotations']:
-            for keypoint in other_annotation['keypoints']:
-                keypoint[0] += offset_left
-                keypoint[1] += offset_up
-
-        return sample
-
-    def _inside(self, point, width, height):
-        if point[0] < 0 or point[1] < 0:
-            return False
-        if point[0] >= width or point[1] >= height:
-            return False
-        return True
-
-
-class Flip:
-    def __init__(self, prob=0.5):
-        self._prob = prob
-
-    def __call__(self, sample):
-        prob = random.random()
-        do_flip = prob <= self._prob
-        if not do_flip:
-            return sample
-
-        sample['image'] = cv2.flip(sample['image'], 1)
-        sample['mask'] = cv2.flip(sample['mask'], 1)
-
-        label = sample['label']
-        w = label['img_width']
-        label['objpos'][0] = w - 1 - label['objpos'][0]
-        for keypoint in label['keypoints']:
-            keypoint[0] = w - 1 - keypoint[0]
-        label['keypoints'] = self._swap_left_right(label['keypoints'])
-
-        for other_annotation in label['processed_other_annotations']:
-            other_annotation['objpos'][0] = w - 1 - other_annotation['objpos'][0]
-            for keypoint in other_annotation['keypoints']:
-                keypoint[0] = w - 1 - keypoint[0]
-            other_annotation['keypoints'] = self._swap_left_right(other_annotation['keypoints'])
-
-        return sample
-
-    def _swap_left_right(self, keypoints):
-        right = [2, 3, 4, 8, 9, 10, 14, 16]
-        left = [5, 6, 7, 11, 12, 13, 15, 17]
-        for r, l in zip(right, left):
-            keypoints[r], keypoints[l] = keypoints[l], keypoints[r]
-        return keypoints
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/__init__.py
deleted file mode 100644
index e69de29bb2..0000000000
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet.py
deleted file mode 100644
index bf9880d157..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet.py
+++ /dev/null
@@ -1,126 +0,0 @@
-import torch
-from torch import nn
-
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.conv import conv, conv_dw, conv_dw_no_bn
-
-
-class Cpm(nn.Module):
-    def __init__(self, in_channels, out_channels):
-        super().__init__()
-        self.align = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
-        self.trunk = nn.Sequential(
-            conv_dw_no_bn(out_channels, out_channels),
-            conv_dw_no_bn(out_channels, out_channels),
-            conv_dw_no_bn(out_channels, out_channels)
-        )
-        self.conv = conv(out_channels, out_channels, bn=False)
-
-    def forward(self, x):
-        x = self.align(x)
-        x = self.conv(x + self.trunk(x))
-        return x
-
-
-class InitialStage(nn.Module):
-    def __init__(self, num_channels, num_heatmaps, num_pafs):
-        super().__init__()
-        self.trunk = nn.Sequential(
-            conv(num_channels, num_channels, bn=False),
-            conv(num_channels, num_channels, bn=False),
-            conv(num_channels, num_channels, bn=False)
-        )
-        self.heatmaps = nn.Sequential(
-            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
-            conv(512, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-        self.pafs = nn.Sequential(
-            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
-            conv(512, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-
-    def forward(self, x):
-        trunk_features = self.trunk(x)
-        heatmaps = self.heatmaps(trunk_features)
-        pafs = self.pafs(trunk_features)
-        return [heatmaps, pafs]
-
-
-class RefinementStageBlock(nn.Module):
-    def __init__(self, in_channels, out_channels):
-        super().__init__()
-        self.initial = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
-        self.trunk = nn.Sequential(
-            conv(out_channels, out_channels),
-            conv(out_channels, out_channels, dilation=2, padding=2)
-        )
-
-    def forward(self, x):
-        initial_features = self.initial(x)
-        trunk_features = self.trunk(initial_features)
-        return initial_features + trunk_features
-
-
-class RefinementStage(nn.Module):
-    def __init__(self, in_channels, out_channels, num_heatmaps, num_pafs):
-        super().__init__()
-        self.trunk = nn.Sequential(
-            RefinementStageBlock(in_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels)
-        )
-        self.heatmaps = nn.Sequential(
-            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
-            conv(out_channels, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-        self.pafs = nn.Sequential(
-            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
-            conv(out_channels, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-
-    def forward(self, x):
-        trunk_features = self.trunk(x)
-        heatmaps = self.heatmaps(trunk_features)
-        pafs = self.pafs(trunk_features)
-        return [heatmaps, pafs]
-
-
-class PoseEstimationWithMobileNet(nn.Module):
-    def __init__(self, num_refinement_stages=1, num_channels=128, num_heatmaps=19, num_pafs=38, use_stride=False):
-        super().__init__()
-        stride_val = 1
-        if use_stride:
-            stride_val = 2
-        self.model = nn.Sequential(
-            conv(3, 32, stride=2, bias=False),
-            conv_dw(32, 64, stride=stride_val),
-            conv_dw(64, 128, stride=2),
-            conv_dw(128, 128),
-            conv_dw(128, 256, stride=2),
-            conv_dw(256, 256),
-            conv_dw(256, 512),  # conv4_2
-            conv_dw(512, 512, dilation=2, padding=2),
-            conv_dw(512, 512),
-            conv_dw(512, 512),
-            conv_dw(512, 512),
-            conv_dw(512, 512)  # conv5_5
-        )
-        self.cpm = Cpm(512, num_channels)
-
-        self.initial_stage = InitialStage(num_channels, num_heatmaps, num_pafs)
-        self.refinement_stages = nn.ModuleList()
-        for idx in range(num_refinement_stages):
-            self.refinement_stages.append(RefinementStage(num_channels + num_heatmaps + num_pafs, num_channels,
-                                                          num_heatmaps, num_pafs))
-
-    def forward(self, x):
-        backbone_features = self.model(x)
-        backbone_features = self.cpm(backbone_features)
-
-        stages_output = self.initial_stage(backbone_features)
-        for refinement_stage in self.refinement_stages:
-            stages_output.extend(
-                refinement_stage(torch.cat([backbone_features, stages_output[-2], stages_output[-1]], dim=1)))
-
-        return stages_output
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet_v2.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet_v2.py
deleted file mode 100644
index da3f2016f9..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_mobilenet_v2.py
+++ /dev/null
@@ -1,252 +0,0 @@
-# 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.
-
-# MobileNetV2 implementation taken from https://github.com/tonylins/pytorch-mobilenet-v2 and modified to work as a
-# backbone for Lightweight Open Pose.
-
-import torch
-from torch import nn
-
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.conv import conv, conv_dw_no_bn
-import math
-
-
-def conv_bn(inp, oup, stride):
-    return nn.Sequential(
-        nn.Conv2d(inp, oup, 3, stride, 1, bias=False),
-        nn.BatchNorm2d(oup),
-        nn.ReLU6(inplace=True)
-    )
-
-
-def conv_1x1_bn(inp, oup):
-    return nn.Sequential(
-        nn.Conv2d(inp, oup, 1, 1, 0, bias=False),
-        nn.BatchNorm2d(oup),
-        nn.ReLU6(inplace=True)
-    )
-
-
-def make_divisible(x, divisible_by=8):
-    import numpy as np
-    return int(np.ceil(x * 1. / divisible_by) * divisible_by)
-
-
-class InvertedResidual(nn.Module):
-    def __init__(self, inp, oup, stride, expand_ratio):
-        super(InvertedResidual, self).__init__()
-        self.stride = stride
-        assert stride in [1, 2]
-
-        hidden_dim = int(inp * expand_ratio)
-        self.use_res_connect = self.stride == 1 and inp == oup
-
-        if expand_ratio == 1:
-            self.conv = nn.Sequential(
-                # dw
-                nn.Conv2d(hidden_dim, hidden_dim, 3, stride, 1, groups=hidden_dim, bias=False),
-                nn.BatchNorm2d(hidden_dim),
-                nn.ReLU6(inplace=True),
-                # pw-linear
-                nn.Conv2d(hidden_dim, oup, 1, 1, 0, bias=False),
-                nn.BatchNorm2d(oup),
-            )
-        else:
-            self.conv = nn.Sequential(
-                # pw
-                nn.Conv2d(inp, hidden_dim, 1, 1, 0, bias=False),
-                nn.BatchNorm2d(hidden_dim),
-                nn.ReLU6(inplace=True),
-                # dw
-                nn.Conv2d(hidden_dim, hidden_dim, 3, stride, 1, groups=hidden_dim, bias=False),
-                nn.BatchNorm2d(hidden_dim),
-                nn.ReLU6(inplace=True),
-                # pw-linear
-                nn.Conv2d(hidden_dim, oup, 1, 1, 0, bias=False),
-                nn.BatchNorm2d(oup),
-            )
-
-    def forward(self, x):
-        if self.use_res_connect:
-            return x + self.conv(x)
-        else:
-            return self.conv(x)
-
-
-class MobileNetV2(nn.Module):
-    def __init__(self, input_size=224, width_mult=1.):
-        super(MobileNetV2, self).__init__()
-        block = InvertedResidual
-        input_channel = 32
-        last_channel = 1280
-        # To make MobileNetV2 output correct dimensions, we change two of the stride settings below according to these
-        # comments below
-        # https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch/issues/17#issuecomment-491518963
-        # https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch/issues/35#issuecomment-508866788
-        inverted_residual_setting = [
-            # t, c, n, s
-            [1, 16, 1, 1],
-            [6, 24, 2, 2],
-            [6, 32, 3, 2],
-            [6, 64, 4, 1],  # s reduced from 2
-            [6, 96, 3, 1],
-            [6, 160, 3, 1],  # s reduced from 2
-            [6, 320, 1, 1],
-        ]
-
-        # building first layer
-        assert input_size % 32 == 0
-        # input_channel = make_divisible(input_channel * width_mult)  # first channel is always 32!
-        self.last_channel = make_divisible(last_channel * width_mult) if width_mult > 1.0 else last_channel
-        self.features = [conv_bn(3, input_channel, 2)]
-        # building inverted residual blocks
-        for t, c, n, s in inverted_residual_setting:
-            output_channel = make_divisible(c * width_mult) if t > 1 else c
-            for i in range(n):
-                if i == 0:
-                    self.features.append(block(input_channel, output_channel, s, expand_ratio=t))
-                else:
-                    self.features.append(block(input_channel, output_channel, 1, expand_ratio=t))
-                input_channel = output_channel
-        # building last several layers
-        self.features.append(conv_1x1_bn(input_channel, self.last_channel))
-        # make it nn.Sequential
-        self.features = nn.Sequential(*self.features)
-
-        self._initialize_weights()
-
-    def forward(self, x):
-        x = self.features(x)
-        return x
-
-    def _initialize_weights(self):
-        for m in self.modules():
-            if isinstance(m, nn.Conv2d):
-                n = m.kernel_size[0] * m.kernel_size[1] * m.out_channels
-                m.weight.data.normal_(0, math.sqrt(2. / n))
-                if m.bias is not None:
-                    m.bias.data.zero_()
-            elif isinstance(m, nn.BatchNorm2d):
-                m.weight.data.fill_(1)
-                m.bias.data.zero_()
-            elif isinstance(m, nn.Linear):
-                n = m.weight.size(1)
-                m.weight.data.normal_(0, 0.01)
-                m.bias.data.zero_()
-
-
-class Cpm(nn.Module):
-    def __init__(self, in_channels, out_channels):
-        super().__init__()
-        self.align = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
-        self.trunk = nn.Sequential(
-            conv_dw_no_bn(out_channels, out_channels),
-            conv_dw_no_bn(out_channels, out_channels),
-            conv_dw_no_bn(out_channels, out_channels)
-        )
-        self.conv = conv(out_channels, out_channels, bn=False)
-
-    def forward(self, x):
-        x = self.align(x)
-        x = self.conv(x + self.trunk(x))
-        return x
-
-
-class InitialStage(nn.Module):
-    def __init__(self, num_channels, num_heatmaps, num_pafs):
-        super().__init__()
-        self.trunk = nn.Sequential(
-            conv(num_channels, num_channels, bn=False),
-            conv(num_channels, num_channels, bn=False),
-            conv(num_channels, num_channels, bn=False)
-        )
-        self.heatmaps = nn.Sequential(
-            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
-            conv(512, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-        self.pafs = nn.Sequential(
-            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
-            conv(512, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-
-    def forward(self, x):
-        trunk_features = self.trunk(x)
-        heatmaps = self.heatmaps(trunk_features)
-        pafs = self.pafs(trunk_features)
-        return [heatmaps, pafs]
-
-
-class RefinementStageBlock(nn.Module):
-    def __init__(self, in_channels, out_channels):
-        super().__init__()
-        self.initial = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
-        self.trunk = nn.Sequential(
-            conv(out_channels, out_channels),
-            conv(out_channels, out_channels, dilation=2, padding=2)
-        )
-
-    def forward(self, x):
-        initial_features = self.initial(x)
-        trunk_features = self.trunk(initial_features)
-        return initial_features + trunk_features
-
-
-class RefinementStage(nn.Module):
-    def __init__(self, in_channels, out_channels, num_heatmaps, num_pafs):
-        super().__init__()
-        self.trunk = nn.Sequential(
-            RefinementStageBlock(in_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels)
-        )
-        self.heatmaps = nn.Sequential(
-            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
-            conv(out_channels, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-        self.pafs = nn.Sequential(
-            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
-            conv(out_channels, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-
-    def forward(self, x):
-        trunk_features = self.trunk(x)
-        heatmaps = self.heatmaps(trunk_features)
-        pafs = self.pafs(trunk_features)
-        return [heatmaps, pafs]
-
-
-class PoseEstimationWithMobileNetV2(nn.Module):
-    def __init__(self, num_refinement_stages=1, num_channels=128, num_heatmaps=19, num_pafs=38, width_mult=1.0):
-        super().__init__()
-
-        self.model = MobileNetV2(width_mult=width_mult)
-        self.cpm = Cpm(1280, num_channels)
-
-        self.initial_stage = InitialStage(num_channels, num_heatmaps, num_pafs)
-        self.refinement_stages = nn.ModuleList()
-        for idx in range(num_refinement_stages):
-            self.refinement_stages.append(RefinementStage(num_channels + num_heatmaps + num_pafs, num_channels,
-                                                          num_heatmaps, num_pafs))
-
-    def forward(self, x):
-        backbone_features = self.model(x)
-        backbone_features = self.cpm(backbone_features)
-        stages_output = self.initial_stage(backbone_features)
-        for refinement_stage in self.refinement_stages:
-            stages_output.extend(
-                refinement_stage(torch.cat([backbone_features, stages_output[-2], stages_output[-1]], dim=1)))
-
-        return stages_output
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_shufflenet.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_shufflenet.py
deleted file mode 100644
index 09ce1be3d7..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/models/with_shufflenet.py
+++ /dev/null
@@ -1,422 +0,0 @@
-# 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.
-
-# ShuffleNet implementation taken from https://github.com/jaxony/ShuffleNet and modified to work as a backbone
-# for Lightweight Open Pose. It comes with the MIT license included below.
-
-# MIT License
-#
-# Copyright (c) 2017 Jackson Huang
-#
-# Permission is hereby granted, free of charge, to any person obtaining a copy
-# of this software and associated documentation files (the "Software"), to deal
-# in the Software without restriction, including without limitation the rights
-# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
-# copies of the Software, and to permit persons to whom the Software is
-# furnished to do so, subject to the following conditions:
-#
-# The above copyright notice and this permission notice shall be included in all
-# copies or substantial portions of the Software.
-#
-# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
-# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
-# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
-# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
-# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
-# SOFTWARE.
-
-import torch
-from torch import nn
-
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.conv import conv, conv_dw_no_bn
-from collections import OrderedDict
-import torch.nn.functional as F
-
-
-def conv3x3(in_channels, out_channels, stride=1,
-            padding=1, bias=True, groups=1):
-    """3x3 convolution with padding
-    """
-    return nn.Conv2d(
-        in_channels,
-        out_channels,
-        kernel_size=3,
-        stride=stride,
-        padding=padding,
-        bias=bias,
-        groups=groups)
-
-
-def conv1x1(in_channels, out_channels, groups=1):
-    """1x1 convolution with padding
-    - Normal pointwise convolution When groups == 1
-    - Grouped pointwise convolution when groups > 1
-    """
-    return nn.Conv2d(
-        in_channels,
-        out_channels,
-        kernel_size=1,
-        groups=groups,
-        stride=1)
-
-
-def channel_shuffle(x, groups):
-    batchsize, num_channels, height, width = x.data.size()
-
-    channels_per_group = num_channels // groups
-
-    # reshape
-    x = x.view(batchsize, groups,
-               channels_per_group, height, width)
-
-    # transpose
-    # - contiguous() required if transpose() is used before view().
-    #   See https://github.com/pytorch/pytorch/issues/764
-    x = torch.transpose(x, 1, 2).contiguous()
-
-    # flatten
-    x = x.view(batchsize, -1, height, width)
-
-    return x
-
-
-class ShuffleUnit(nn.Module):
-    def __init__(self, in_channels, out_channels, groups=3,
-                 grouped_conv=True, combine='add'):
-
-        super(ShuffleUnit, self).__init__()
-
-        self.in_channels = in_channels
-        self.out_channels = out_channels
-        self.grouped_conv = grouped_conv
-        self.combine = combine
-        self.groups = groups
-        self.bottleneck_channels = self.out_channels // 4
-
-        # define the type of ShuffleUnit
-        if self.combine == 'add':
-            # ShuffleUnit Figure 2b
-            self.depthwise_stride = 1
-            self._combine_func = self._add
-        elif self.combine == 'concat':
-            # ShuffleUnit Figure 2c
-            self.depthwise_stride = 2
-            self._combine_func = self._concat
-
-            # ensure output of concat has the same channels as
-            # original output channels.
-            self.out_channels -= self.in_channels
-        else:
-            raise ValueError(
-                "Cannot combine tensors with \"{}\" Only \"add\" and \"concat\" are supported".format(self.combine))
-
-        # Use a 1x1 grouped or non-grouped convolution to reduce input channels
-        # to bottleneck channels, as in a ResNet bottleneck module.
-        # NOTE: Do not use group convolution for the first conv1x1 in Stage 2.
-        self.first_1x1_groups = self.groups if grouped_conv else 1
-
-        self.g_conv_1x1_compress = self._make_grouped_conv1x1(
-            self.in_channels,
-            self.bottleneck_channels,
-            self.first_1x1_groups,
-            batch_norm=True,
-            relu=True
-        )
-
-        # 3x3 depthwise convolution followed by batch normalization
-        self.depthwise_conv3x3 = conv3x3(
-            self.bottleneck_channels, self.bottleneck_channels,
-            stride=self.depthwise_stride, groups=self.bottleneck_channels)
-        self.bn_after_depthwise = nn.BatchNorm2d(self.bottleneck_channels)
-
-        # Use 1x1 grouped convolution to expand from
-        # bottleneck_channels to out_channels
-        self.g_conv_1x1_expand = self._make_grouped_conv1x1(
-            self.bottleneck_channels,
-            self.out_channels,
-            self.groups,
-            batch_norm=True,
-            relu=False
-        )
-
-    @staticmethod
-    def _add(x, out):
-        # residual connection
-        return x + out
-
-    @staticmethod
-    def _concat(x, out):
-        # concatenate along channel axis
-        return torch.cat((x, out), 1)
-
-    @staticmethod
-    def _make_grouped_conv1x1(in_channels, out_channels, groups,
-                              batch_norm=True, relu=False):
-
-        modules = OrderedDict()
-
-        conv_ = conv1x1(in_channels, out_channels, groups=groups)
-        modules['conv1x1'] = conv_
-
-        if batch_norm:
-            modules['batch_norm'] = nn.BatchNorm2d(out_channels)
-        if relu:
-            modules['relu'] = nn.ReLU()
-        if len(modules) > 1:
-            return nn.Sequential(modules)
-        else:
-            return conv_
-
-    def forward(self, x):
-        # save for combining later with output
-        residual = x
-
-        if self.combine == 'concat':
-            residual = F.avg_pool2d(residual, kernel_size=3,
-                                    stride=2, padding=1)
-
-        out = self.g_conv_1x1_compress(x)
-        out = channel_shuffle(out, self.groups)
-        out = self.depthwise_conv3x3(out)
-        out = self.bn_after_depthwise(out)
-        out = self.g_conv_1x1_expand(out)
-
-        out = self._combine_func(residual, out)
-        return F.relu(out)
-
-
-class ShuffleNet(nn.Module):
-    """ShuffleNet implementation.
-    """
-
-    def __init__(self, groups=3, in_channels=3):
-        """ShuffleNet constructor.
-        Arguments:
-            groups (int, optional): number of groups to be used in grouped
-                1x1 convolutions in each ShuffleUnit. Default is 3 for best
-                performance according to original paper.
-            in_channels (int, optional): number of channels in the input tensor.
-                Default is 3 for RGB image inputs.
-        """
-        super(ShuffleNet, self).__init__()
-
-        self.groups = groups
-        self.stage_repeats = [3, 7, 3]
-        self.in_channels = in_channels
-
-        # index 0 is invalid and should never be called.
-        # only used for indexing convenience.
-        if groups == 1:
-            self.stage_out_channels = [-1, 24, 144, 288, 576]
-        elif groups == 2:
-            self.stage_out_channels = [-1, 24, 200, 400, 800]
-        elif groups == 3:
-            self.stage_out_channels = [-1, 24, 240, 480, 960]
-        elif groups == 4:
-            self.stage_out_channels = [-1, 24, 272, 544, 1088]
-        elif groups == 8:
-            self.stage_out_channels = [-1, 24, 384, 768, 1536]
-        else:
-            raise ValueError(
-                """{} groups is not supported for
-                   1x1 Grouped Convolutions""".format(groups))
-        # Same as MobileNetV2, to output correct dimensions, we change two of the stride settings below
-        # Stage 1 always has 24 output channels
-        self.conv1 = conv3x3(self.in_channels,
-                             self.stage_out_channels[1],  # stage 1
-                             stride=1)  # stride reduced from 2
-        self.maxpool = nn.MaxPool2d(kernel_size=3, stride=1, padding=1)  # stride reduced from 2
-
-        # Stage 2
-        self.stage2 = self._make_stage(2)
-        # Stage 3
-        self.stage3 = self._make_stage(3)
-        # Stage 4
-        self.stage4 = self._make_stage(4)
-
-        # Global pooling:
-        # Undefined as PyTorch's functional API can be used for on-the-fly
-        # shape inference if input size is not ImageNet's 224x224
-
-        self.init_params()
-
-    def init_params(self):
-        for m in self.modules():
-            if isinstance(m, nn.Conv2d):
-                nn.init.kaiming_normal_(m.weight, mode='fan_out')
-                if m.bias is not None:
-                    nn.init.constant_(m.bias, 0)
-            elif isinstance(m, nn.BatchNorm2d):
-                nn.init.constant_(m.weight, 1)
-                nn.init.constant_(m.bias, 0)
-            elif isinstance(m, nn.Linear):
-                nn.init.normal(m.weight, std=0.001)
-                if m.bias is not None:
-                    nn.init.constant_(m.bias, 0)
-
-    def _make_stage(self, stage):
-        modules = OrderedDict()
-        stage_name = "ShuffleUnit_Stage{}".format(stage)
-
-        # First ShuffleUnit in the stage
-        # 1. non-grouped 1x1 convolution (i.e. pointwise convolution)
-        #   is used in Stage 2. Group convolutions used everywhere else.
-        grouped_conv = stage > 2
-
-        # 2. concatenation unit is always used.
-        first_module = ShuffleUnit(
-            self.stage_out_channels[stage - 1],
-            self.stage_out_channels[stage],
-            groups=self.groups,
-            grouped_conv=grouped_conv,
-            combine='concat'
-        )
-        modules[stage_name + "_0"] = first_module
-
-        # add more ShuffleUnits depending on pre-defined number of repeats
-        for i in range(self.stage_repeats[stage - 2]):
-            name = stage_name + "_{}".format(i + 1)
-            module = ShuffleUnit(
-                self.stage_out_channels[stage],
-                self.stage_out_channels[stage],
-                groups=self.groups,
-                grouped_conv=True,
-                combine='add'
-            )
-            modules[name] = module
-
-        return nn.Sequential(modules)
-
-    def forward(self, x):
-        x = self.conv1(x)
-        x = self.maxpool(x)
-
-        x = self.stage2(x)
-        x = self.stage3(x)
-        x = self.stage4(x)
-
-        # Avg pooling is removed in favor of changing the stride of conv1 + maxpool
-        # With avg pooling, convergence is way too slow based on short tests, but we leave it here for reference
-        # between the original shufflenet and the modifications we made
-        # global average pooling layer
-        # x = F.avg_pool2d(x, x.data.size()[-2:])
-        return x
-
-
-class Cpm(nn.Module):
-    def __init__(self, in_channels, out_channels):
-        super().__init__()
-        self.align = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
-        self.trunk = nn.Sequential(
-            conv_dw_no_bn(out_channels, out_channels),
-            conv_dw_no_bn(out_channels, out_channels),
-            conv_dw_no_bn(out_channels, out_channels)
-        )
-        self.conv = conv(out_channels, out_channels, bn=False)
-
-    def forward(self, x):
-        x = self.align(x)
-        x = self.conv(x + self.trunk(x))
-        return x
-
-
-class InitialStage(nn.Module):
-    def __init__(self, num_channels, num_heatmaps, num_pafs):
-        super().__init__()
-        self.trunk = nn.Sequential(
-            conv(num_channels, num_channels, bn=False),
-            conv(num_channels, num_channels, bn=False),
-            conv(num_channels, num_channels, bn=False)
-        )
-        self.heatmaps = nn.Sequential(
-            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
-            conv(512, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-        self.pafs = nn.Sequential(
-            conv(num_channels, 512, kernel_size=1, padding=0, bn=False),
-            conv(512, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-
-    def forward(self, x):
-        trunk_features = self.trunk(x)
-        heatmaps = self.heatmaps(trunk_features)
-        pafs = self.pafs(trunk_features)
-        return [heatmaps, pafs]
-
-
-class RefinementStageBlock(nn.Module):
-    def __init__(self, in_channels, out_channels):
-        super().__init__()
-        self.initial = conv(in_channels, out_channels, kernel_size=1, padding=0, bn=False)
-        self.trunk = nn.Sequential(
-            conv(out_channels, out_channels),
-            conv(out_channels, out_channels, dilation=2, padding=2)
-        )
-
-    def forward(self, x):
-        initial_features = self.initial(x)
-        trunk_features = self.trunk(initial_features)
-        return initial_features + trunk_features
-
-
-class RefinementStage(nn.Module):
-    def __init__(self, in_channels, out_channels, num_heatmaps, num_pafs):
-        super().__init__()
-        self.trunk = nn.Sequential(
-            RefinementStageBlock(in_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels),
-            RefinementStageBlock(out_channels, out_channels)
-        )
-        self.heatmaps = nn.Sequential(
-            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
-            conv(out_channels, num_heatmaps, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-        self.pafs = nn.Sequential(
-            conv(out_channels, out_channels, kernel_size=1, padding=0, bn=False),
-            conv(out_channels, num_pafs, kernel_size=1, padding=0, bn=False, relu=False)
-        )
-
-    def forward(self, x):
-        trunk_features = self.trunk(x)
-        heatmaps = self.heatmaps(trunk_features)
-        pafs = self.pafs(trunk_features)
-        return [heatmaps, pafs]
-
-
-class PoseEstimationWithShuffleNet(nn.Module):
-    def __init__(self, num_refinement_stages=1, num_channels=128, num_heatmaps=19, num_pafs=38, groups=3):
-        super().__init__()
-
-        self.model = ShuffleNet(groups=groups, in_channels=3)
-        self.cpm = Cpm(self.model.stage_out_channels[-1], num_channels)
-
-        self.initial_stage = InitialStage(num_channels, num_heatmaps, num_pafs)
-        self.refinement_stages = nn.ModuleList()
-        for idx in range(num_refinement_stages):
-            self.refinement_stages.append(RefinementStage(num_channels + num_heatmaps + num_pafs, num_channels,
-                                                          num_heatmaps, num_pafs))
-
-    def forward(self, x):
-        backbone_features = self.model(x)
-        backbone_features = self.cpm(backbone_features)
-
-        stages_output = self.initial_stage(backbone_features)
-        for refinement_stage in self.refinement_stages:
-            stages_output.extend(
-                refinement_stage(torch.cat([backbone_features, stages_output[-2], stages_output[-1]], dim=1)))
-
-        return stages_output
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/__init__.py
deleted file mode 100644
index e69de29bb2..0000000000
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/conv.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/conv.py
deleted file mode 100644
index 259e4aa021..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/conv.py
+++ /dev/null
@@ -1,32 +0,0 @@
-from torch import nn
-
-
-def conv(in_channels, out_channels, kernel_size=3, padding=1, bn=True, dilation=1, stride=1, relu=True, bias=True):
-    modules = [nn.Conv2d(in_channels, out_channels, kernel_size, stride, padding, dilation, bias=bias)]
-    if bn:
-        modules.append(nn.BatchNorm2d(out_channels))
-    if relu:
-        modules.append(nn.ReLU(inplace=True))
-    return nn.Sequential(*modules)
-
-
-def conv_dw(in_channels, out_channels, kernel_size=3, padding=1, stride=1, dilation=1):
-    return nn.Sequential(
-        nn.Conv2d(in_channels, in_channels, kernel_size, stride, padding, dilation=dilation, groups=in_channels,
-                  bias=False),
-        nn.BatchNorm2d(in_channels),
-        nn.ReLU(inplace=True),
-        nn.Conv2d(in_channels, out_channels, 1, 1, 0, bias=False),
-        nn.BatchNorm2d(out_channels),
-        nn.ReLU(inplace=True),
-    )
-
-
-def conv_dw_no_bn(in_channels, out_channels, kernel_size=3, padding=1, stride=1, dilation=1):
-    return nn.Sequential(
-        nn.Conv2d(in_channels, in_channels, kernel_size, stride, padding, dilation=dilation, groups=in_channels,
-                  bias=False),
-        nn.ELU(inplace=True),
-        nn.Conv2d(in_channels, out_channels, 1, 1, 0, bias=False),
-        nn.ELU(inplace=True),
-    )
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/get_parameters.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/get_parameters.py
deleted file mode 100644
index bf5250b9de..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/get_parameters.py
+++ /dev/null
@@ -1,21 +0,0 @@
-from torch import nn
-
-
-def get_parameters(model, predicate):
-    for module in model.modules():
-        for param_name, param in module.named_parameters():
-            if predicate(module, param_name):
-                yield param
-
-
-def get_parameters_conv(model, name):
-    return get_parameters(model, lambda m, p: isinstance(m, nn.Conv2d) and m.groups == 1 and p == name)
-
-
-def get_parameters_conv_depthwise(model, name):
-    return get_parameters(model, lambda m, p: isinstance(m, nn.Conv2d) and m.groups == m.in_channels and
-                          m.in_channels == m.out_channels and p == name)
-
-
-def get_parameters_bn(model, name):
-    return get_parameters(model, lambda m, p: isinstance(m, nn.BatchNorm2d) and p == name)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/keypoints.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/keypoints.py
deleted file mode 100644
index 2a59ff7bda..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/keypoints.py
+++ /dev/null
@@ -1,159 +0,0 @@
-import math
-import numpy as np
-from operator import itemgetter
-
-BODY_PARTS_KPT_IDS = [[1, 2], [1, 5], [2, 3], [3, 4], [5, 6], [6, 7], [1, 8], [8, 9], [9, 10], [1, 11],
-                      [11, 12], [12, 13], [1, 0], [0, 14], [14, 16], [0, 15], [15, 17], [2, 16], [5, 17]]
-BODY_PARTS_PAF_IDS = ([12, 13], [20, 21], [14, 15], [16, 17], [22, 23], [24, 25], [0, 1], [2, 3], [4, 5],
-                      [6, 7], [8, 9], [10, 11], [28, 29], [30, 31], [34, 35], [32, 33], [36, 37], [18, 19], [26, 27])
-
-
-def extract_keypoints(heatmap, all_keypoints, total_keypoint_num):
-    heatmap[heatmap < 0.1] = 0
-    heatmap_with_borders = np.pad(heatmap, [(2, 2), (2, 2)], mode='constant')
-    heatmap_center = heatmap_with_borders[1:heatmap_with_borders.shape[0] - 1, 1:heatmap_with_borders.shape[1] - 1]
-    heatmap_left = heatmap_with_borders[1:heatmap_with_borders.shape[0] - 1, 2:heatmap_with_borders.shape[1]]
-    heatmap_right = heatmap_with_borders[1:heatmap_with_borders.shape[0] - 1, 0:heatmap_with_borders.shape[1] - 2]
-    heatmap_up = heatmap_with_borders[2:heatmap_with_borders.shape[0], 1:heatmap_with_borders.shape[1] - 1]
-    heatmap_down = heatmap_with_borders[0:heatmap_with_borders.shape[0] - 2, 1:heatmap_with_borders.shape[1] - 1]
-
-    heatmap_peaks = (heatmap_center > heatmap_left) & \
-                    (heatmap_center > heatmap_right) & \
-                    (heatmap_center > heatmap_up) & \
-                    (heatmap_center > heatmap_down)
-    heatmap_peaks = heatmap_peaks[1:heatmap_center.shape[0] - 1, 1:heatmap_center.shape[1] - 1]
-    keypoints = list(zip(np.nonzero(heatmap_peaks)[1], np.nonzero(heatmap_peaks)[0]))  # (w, h)
-    keypoints = sorted(keypoints, key=itemgetter(0))
-
-    suppressed = np.zeros(len(keypoints), np.uint8)
-    keypoints_with_score_and_id = []
-    keypoint_num = 0
-    for i in range(len(keypoints)):
-        if suppressed[i]:
-            continue
-        for j in range(i + 1, len(keypoints)):
-            if math.sqrt((keypoints[i][0] - keypoints[j][0]) ** 2 +
-                         (keypoints[i][1] - keypoints[j][1]) ** 2) < 6:
-                suppressed[j] = 1
-        keypoint_with_score_and_id = (keypoints[i][0], keypoints[i][1], heatmap[keypoints[i][1], keypoints[i][0]],
-                                      total_keypoint_num + keypoint_num)
-        keypoints_with_score_and_id.append(keypoint_with_score_and_id)
-        keypoint_num += 1
-    all_keypoints.append(keypoints_with_score_and_id)
-    return keypoint_num
-
-
-def connections_nms(a_idx, b_idx, affinity_scores):
-    # From all retrieved connections that share the same starting/ending keypoints leave only the top-scoring ones.
-    order = affinity_scores.argsort()[::-1]
-    affinity_scores = affinity_scores[order]
-    a_idx = a_idx[order]
-    b_idx = b_idx[order]
-    idx = []
-    has_kpt_a = set()
-    has_kpt_b = set()
-    for t, (i, j) in enumerate(zip(a_idx, b_idx)):
-        if i not in has_kpt_a and j not in has_kpt_b:
-            idx.append(t)
-            has_kpt_a.add(i)
-            has_kpt_b.add(j)
-    idx = np.asarray(idx, dtype=np.int32)
-    return a_idx[idx], b_idx[idx], affinity_scores[idx]
-
-
-def group_keypoints(all_keypoints_by_type, pafs, pose_entry_size=20, min_paf_score=0.05):
-    pose_entries = []
-    all_keypoints = np.array([item for sublist in all_keypoints_by_type for item in sublist])
-    points_per_limb = 10
-    grid = np.arange(points_per_limb, dtype=np.float32).reshape(1, -1, 1)
-    all_keypoints_by_type = [np.array(keypoints, np.float32) for keypoints in all_keypoints_by_type]
-    for part_id in range(len(BODY_PARTS_PAF_IDS)):
-        part_pafs = pafs[:, :, BODY_PARTS_PAF_IDS[part_id]]
-        kpts_a = all_keypoints_by_type[BODY_PARTS_KPT_IDS[part_id][0]]
-        kpts_b = all_keypoints_by_type[BODY_PARTS_KPT_IDS[part_id][1]]
-        n = len(kpts_a)
-        m = len(kpts_b)
-        if n == 0 or m == 0:
-            continue
-
-        # Get vectors between all pairs of keypoints, i.e. candidate limb vectors.
-        a = kpts_a[:, :2]
-        a = np.broadcast_to(a[None], (m, n, 2))
-        b = kpts_b[:, :2]
-        vec_raw = (b[:, None, :] - a).reshape(-1, 1, 2)
-
-        # Sample points along every candidate limb vector.
-        steps = (1 / (points_per_limb - 1) * vec_raw)
-        points = steps * grid + a.reshape(-1, 1, 2)
-        points = points.round().astype(dtype=np.int32)
-        x = points[..., 0].ravel()
-        y = points[..., 1].ravel()
-
-        # Compute affinity score between candidate limb vectors and part affinity field.
-        field = part_pafs[y, x].reshape(-1, points_per_limb, 2)
-        vec_norm = np.linalg.norm(vec_raw, ord=2, axis=-1, keepdims=True)
-        vec = vec_raw / (vec_norm + 1e-6)
-        affinity_scores = (field * vec).sum(-1).reshape(-1, points_per_limb)
-        valid_affinity_scores = affinity_scores > min_paf_score
-        valid_num = valid_affinity_scores.sum(1)
-        affinity_scores = (affinity_scores * valid_affinity_scores).sum(1) / (valid_num + 1e-6)
-        success_ratio = valid_num / points_per_limb
-
-        # Get a list of limbs according to the obtained affinity score.
-        valid_limbs = np.where(np.logical_and(affinity_scores > 0, success_ratio > 0.8))[0]
-        if len(valid_limbs) == 0:
-            continue
-        b_idx, a_idx = np.divmod(valid_limbs, n)
-        affinity_scores = affinity_scores[valid_limbs]
-
-        # Suppress incompatible connections.
-        a_idx, b_idx, affinity_scores = connections_nms(a_idx, b_idx, affinity_scores)
-        connections = list(zip(kpts_a[a_idx, 3].astype(np.int32),
-                               kpts_b[b_idx, 3].astype(np.int32),
-                               affinity_scores))
-        if len(connections) == 0:
-            continue
-
-        if part_id == 0:
-            pose_entries = [np.ones(pose_entry_size) * -1 for _ in range(len(connections))]
-            for i in range(len(connections)):
-                pose_entries[i][BODY_PARTS_KPT_IDS[0][0]] = connections[i][0]
-                pose_entries[i][BODY_PARTS_KPT_IDS[0][1]] = connections[i][1]
-                pose_entries[i][-1] = 2
-                pose_entries[i][-2] = np.sum(all_keypoints[connections[i][0:2], 2]) + connections[i][2]
-        elif part_id == 17 or part_id == 18:
-            kpt_a_id = BODY_PARTS_KPT_IDS[part_id][0]
-            kpt_b_id = BODY_PARTS_KPT_IDS[part_id][1]
-            for i in range(len(connections)):
-                for j in range(len(pose_entries)):
-                    if pose_entries[j][kpt_a_id] == connections[i][0] and pose_entries[j][kpt_b_id] == -1:
-                        pose_entries[j][kpt_b_id] = connections[i][1]
-                    elif pose_entries[j][kpt_b_id] == connections[i][1] and pose_entries[j][kpt_a_id] == -1:
-                        pose_entries[j][kpt_a_id] = connections[i][0]
-            continue
-        else:
-            kpt_a_id = BODY_PARTS_KPT_IDS[part_id][0]
-            kpt_b_id = BODY_PARTS_KPT_IDS[part_id][1]
-            for i in range(len(connections)):
-                num = 0
-                for j in range(len(pose_entries)):
-                    if pose_entries[j][kpt_a_id] == connections[i][0]:
-                        pose_entries[j][kpt_b_id] = connections[i][1]
-                        num += 1
-                        pose_entries[j][-1] += 1
-                        pose_entries[j][-2] += all_keypoints[connections[i][1], 2] + connections[i][2]
-                if num == 0:
-                    pose_entry = np.ones(pose_entry_size) * -1
-                    pose_entry[kpt_a_id] = connections[i][0]
-                    pose_entry[kpt_b_id] = connections[i][1]
-                    pose_entry[-1] = 2
-                    pose_entry[-2] = np.sum(all_keypoints[connections[i][0:2], 2]) + connections[i][2]
-                    pose_entries.append(pose_entry)
-
-    filtered_entries = []
-    for i in range(len(pose_entries)):
-        if pose_entries[i][-1] < 3 or (pose_entries[i][-2] / pose_entries[i][-1] < 0.2):
-            continue
-        filtered_entries.append(pose_entries[i])
-    pose_entries = np.asarray(filtered_entries)
-    return pose_entries, all_keypoints
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/load_state.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/load_state.py
deleted file mode 100644
index d23bc0d2fd..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/load_state.py
+++ /dev/null
@@ -1,35 +0,0 @@
-import collections
-
-
-def load_state(net, checkpoint):
-    try:
-        source_state = checkpoint['state_dict']
-    except KeyError:
-        source_state = checkpoint
-    target_state = net.state_dict()
-    new_target_state = collections.OrderedDict()
-    for target_key, target_value in target_state.items():
-        if target_key in source_state and source_state[target_key].size() == target_state[target_key].size():
-            new_target_state[target_key] = source_state[target_key]
-        else:
-            new_target_state[target_key] = target_state[target_key]
-            # print('[WARNING] Not found pre-trained parameters for {}'.format(target_key))
-
-    net.load_state_dict(new_target_state)
-
-
-def load_from_mobilenet(net, checkpoint):
-    source_state = checkpoint['state_dict']
-    target_state = net.state_dict()
-    new_target_state = collections.OrderedDict()
-    for target_key, target_value in target_state.items():
-        k = target_key
-        if k.find('model') != -1:
-            k = k.replace('model', 'module.model')
-        if k in source_state and source_state[k].size() == target_state[target_key].size():
-            new_target_state[target_key] = source_state[k]
-        else:
-            new_target_state[target_key] = target_state[target_key]
-            # print('[WARNING] Not found pre-trained parameters for {}'.format(target_key))
-
-    net.load_state_dict(new_target_state)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/loss.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/loss.py
deleted file mode 100644
index 88930181ce..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/loss.py
+++ /dev/null
@@ -1,5 +0,0 @@
-def l2_loss(input, target, mask, batch_size):
-    loss = (input - target) * mask
-    loss = (loss * loss) / 2 / batch_size
-
-    return loss.sum()
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/one_euro_filter.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/one_euro_filter.py
deleted file mode 100644
index 4ef6ffc3f0..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/modules/one_euro_filter.py
+++ /dev/null
@@ -1,51 +0,0 @@
-import math
-
-
-def get_alpha(rate=30, cutoff=1):
-    tau = 1 / (2 * math.pi * cutoff)
-    te = 1 / rate
-    return 1 / (1 + tau / te)
-
-
-class LowPassFilter:
-    def __init__(self):
-        self.x_previous = None
-
-    def __call__(self, x, alpha=0.5):
-        if self.x_previous is None:
-            self.x_previous = x
-            return x
-        x_filtered = alpha * x + (1 - alpha) * self.x_previous
-        self.x_previous = x_filtered
-        return x_filtered
-
-
-class OneEuroFilter:
-    def __init__(self, freq=15, mincutoff=1, beta=0.05, dcutoff=1):
-        self.freq = freq
-        self.mincutoff = mincutoff
-        self.beta = beta
-        self.dcutoff = dcutoff
-        self.filter_x = LowPassFilter()
-        self.filter_dx = LowPassFilter()
-        self.x_previous = None
-        self.dx = None
-
-    def __call__(self, x):
-        if self.dx is None:
-            self.dx = 0
-        else:
-            self.dx = (x - self.x_previous) * self.freq
-        dx_smoothed = self.filter_dx(self.dx, get_alpha(self.freq, self.dcutoff))
-        cutoff = self.mincutoff + self.beta * abs(dx_smoothed)
-        x_filtered = self.filter_x(x, get_alpha(self.freq, cutoff))
-        self.x_previous = x
-        return x_filtered
-
-
-if __name__ == '__main__':
-    filter = OneEuroFilter(freq=15, beta=0.1)
-    for val in range(10):
-        x = val + (-1) ** (val % 2)
-        x_filtered = filter(x)
-        print(x_filtered, x)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/__init__.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/__init__.py
deleted file mode 100644
index e69de29bb2..0000000000
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/make_val_subset.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/make_val_subset.py
deleted file mode 100644
index 7b02609268..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/make_val_subset.py
+++ /dev/null
@@ -1,43 +0,0 @@
-import json
-import random
-
-
-def make_val_subset(labels, output_path="val_subset.json", num_images=250):
-    """
-    :param labels: path to json with keypoints val labels
-    :param output_path: name of output file with subset of val labels, defaults to "val_subset.json"
-    :param num_images: number of images in subset, defaults to 250
-    """
-    with open(labels, 'r') as f:
-        data = json.load(f)
-
-    random.seed(0)
-    total_val_images = 5000
-    idxs = list(range(total_val_images))
-    random.shuffle(idxs)
-
-    images_by_id = {}
-    for idx in idxs[:num_images]:
-        images_by_id[data['images'][idx]['id']] = data['images'][idx]
-
-    annotations_by_image_id = {}
-    for annotation in data['annotations']:
-        if annotation['image_id'] in images_by_id:
-            if not annotation['image_id'] in annotations_by_image_id:
-                annotations_by_image_id[annotation['image_id']] = []
-            annotations_by_image_id[annotation['image_id']].append(annotation)
-
-    subset = {
-        'info': data['info'],
-        'licenses': data['licenses'],
-        'images': [],
-        'annotations': [],
-        'categories': data['categories']
-    }
-    for image_id, image in images_by_id.items():
-        subset['images'].append(image)
-        if image_id in annotations_by_image_id:  # image has at least 1 annotation
-            subset['annotations'].extend(annotations_by_image_id[image_id])
-
-    with open(output_path, 'w') as f:
-        json.dump(subset, f, indent=4)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/prepare_train_labels.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/prepare_train_labels.py
deleted file mode 100644
index 8fe1e36a4e..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/scripts/prepare_train_labels.py
+++ /dev/null
@@ -1,122 +0,0 @@
-import json
-import pickle
-
-
-def prepare_annotations(annotations_per_image, images_info, net_input_size):
-    """Prepare labels for training. For each annotated person calculates center
-    to perform crop around it during the training. Also converts data to the internal format.
-
-    :param annotations_per_image: all annotations for specified image id
-    :param images_info: auxiliary information about all images
-    :param net_input_size: network input size during training
-    :return: list of prepared annotations
-    """
-    prepared_annotations = []
-    for _, annotations in annotations_per_image.items():
-        previous_centers = []
-        for annotation in annotations[0]:
-            if annotation['num_keypoints'] < 5 or annotation['area'] < 32 * 32:
-                continue
-            person_center = [annotation['bbox'][0] + annotation['bbox'][2] / 2,
-                             annotation['bbox'][1] + annotation['bbox'][3] / 2]
-            is_close = False
-            for previous_center in previous_centers:
-                distance_to_previous = ((person_center[0] - previous_center[0]) ** 2 +
-                                        (person_center[1] - previous_center[1]) ** 2) ** 0.5
-                if distance_to_previous < previous_center[2] * 0.3:
-                    is_close = True
-                    break
-            if is_close:
-                continue
-
-            prepared_annotation = {
-                'img_paths': images_info[annotation['image_id']]['file_name'],
-                'img_width': images_info[annotation['image_id']]['width'],
-                'img_height': images_info[annotation['image_id']]['height'],
-                'objpos': person_center,
-                'image_id': annotation['image_id'],
-                'bbox': annotation['bbox'],
-                'segment_area': annotation['area'],
-                'scale_provided': annotation['bbox'][3] / net_input_size,
-                'num_keypoints': annotation['num_keypoints'],
-                'segmentations': annotations[1]
-            }
-
-            keypoints = []
-            for i in range(len(annotation['keypoints']) // 3):
-                keypoint = [annotation['keypoints'][i * 3], annotation['keypoints'][i * 3 + 1], 2]
-                if annotation['keypoints'][i * 3 + 2] == 1:
-                    keypoint[2] = 0
-                elif annotation['keypoints'][i * 3 + 2] == 2:
-                    keypoint[2] = 1
-                keypoints.append(keypoint)
-            prepared_annotation['keypoints'] = keypoints
-
-            prepared_other_annotations = []
-            for other_annotation in annotations[0]:
-                if other_annotation == annotation:
-                    continue
-
-                prepared_other_annotation = {
-                    'objpos': [other_annotation['bbox'][0] + other_annotation['bbox'][2] / 2,
-                               other_annotation['bbox'][1] + other_annotation['bbox'][3] / 2],
-                    'bbox': other_annotation['bbox'],
-                    'segment_area': other_annotation['area'],
-                    'scale_provided': other_annotation['bbox'][3] / net_input_size,
-                    'num_keypoints': other_annotation['num_keypoints']
-                }
-
-                keypoints = []
-                for i in range(len(other_annotation['keypoints']) // 3):
-                    keypoint = [other_annotation['keypoints'][i * 3], other_annotation['keypoints'][i * 3 + 1], 2]
-                    if other_annotation['keypoints'][i * 3 + 2] == 1:
-                        keypoint[2] = 0
-                    elif other_annotation['keypoints'][i * 3 + 2] == 2:
-                        keypoint[2] = 1
-                    keypoints.append(keypoint)
-                prepared_other_annotation['keypoints'] = keypoints
-                prepared_other_annotations.append(prepared_other_annotation)
-
-            prepared_annotation['processed_other_annotations'] = prepared_other_annotations
-            prepared_annotations.append(prepared_annotation)
-
-            previous_centers.append((person_center[0], person_center[1], annotation['bbox'][2], annotation['bbox'][3]))
-    return prepared_annotations
-
-
-def convert_annotations(labels, output_path="prepared_train_annotation.pkl", net_input_size=368):
-    """
-    :param labels: path to json with keypoints train labels
-    :param output_path: name of output file with prepared keypoints annotation, defaults to
-     "prepared_train_annotation.pkl"
-    :param net_input_size: network input size, defaults to 368
-    """
-    with open(labels, 'r') as f:
-        data = json.load(f)
-
-    annotations_per_image_mapping = {}
-    for annotation in data['annotations']:
-        if annotation['num_keypoints'] != 0 and not annotation['iscrowd']:
-            if annotation['image_id'] not in annotations_per_image_mapping:
-                annotations_per_image_mapping[annotation['image_id']] = [[], []]
-            annotations_per_image_mapping[annotation['image_id']][0].append(annotation)
-
-    crowd_segmentations_per_image_mapping = {}
-    for annotation in data['annotations']:
-        if annotation['iscrowd']:
-            if annotation['image_id'] not in crowd_segmentations_per_image_mapping:
-                crowd_segmentations_per_image_mapping[annotation['image_id']] = []
-            crowd_segmentations_per_image_mapping[annotation['image_id']].append(annotation['segmentation'])
-
-    for image_id, crowd_segmentations in crowd_segmentations_per_image_mapping.items():
-        if image_id in annotations_per_image_mapping:
-            annotations_per_image_mapping[image_id][1] = crowd_segmentations
-
-    images_info = {}
-    for image_info in data['images']:
-        images_info[image_info['id']] = image_info
-
-    prepared_annotations = prepare_annotations(annotations_per_image_mapping, images_info, net_input_size)
-
-    with open(output_path, 'wb') as f:
-        pickle.dump(prepared_annotations, f)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/val.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/val.py
deleted file mode 100644
index 0958170791..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm/val.py
+++ /dev/null
@@ -1,161 +0,0 @@
-import cv2
-import json
-import math
-import numpy as np
-from pycocotools.coco import COCO
-from pycocotools.cocoeval import COCOeval
-
-import torch
-
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.datasets.coco import CocoValDataset
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.keypoints import \
-    extract_keypoints, group_keypoints
-
-
-def run_coco_eval(gt_file_path, dt_file_path, verbose=False):
-    annotation_type = 'keypoints'
-    if verbose:
-        print('Running test for {} results.'.format(annotation_type))
-
-    coco_gt = COCO(gt_file_path)
-    coco_dt = coco_gt.loadRes(dt_file_path)
-
-    result = COCOeval(coco_gt, coco_dt, annotation_type)
-    result.evaluate()
-    result.accumulate()
-    result.summarize()
-    return result
-
-
-def normalize(img, img_mean, img_scale):
-    img = np.array(img, dtype=np.float32)
-    img = (img - img_mean) * img_scale
-    return img
-
-
-def pad_width(img, stride, pad_value, min_dims):
-    h, w, _ = img.shape
-    h = min(min_dims[0], h)
-    min_dims[0] = math.ceil(min_dims[0] / float(stride)) * stride
-    min_dims[1] = max(min_dims[1], w)
-    min_dims[1] = math.ceil(min_dims[1] / float(stride)) * stride
-    pad = []
-    pad.append(int(math.floor((min_dims[0] - h) / 2.0)))
-    pad.append(int(math.floor((min_dims[1] - w) / 2.0)))
-    pad.append(int(min_dims[0] - h - pad[0]))
-    pad.append(int(min_dims[1] - w - pad[1]))
-    padded_img = cv2.copyMakeBorder(img, pad[0], pad[2], pad[1], pad[3],
-                                    cv2.BORDER_CONSTANT, value=pad_value)
-    return padded_img, pad
-
-
-def convert_to_coco_format(pose_entries, all_keypoints):
-    coco_keypoints = []
-    scores = []
-    for n in range(len(pose_entries)):
-        if len(pose_entries[n]) == 0:
-            continue
-        keypoints = [0] * 17 * 3
-        to_coco_map = [0, -1, 6, 8, 10, 5, 7, 9, 12, 14, 16, 11, 13, 15, 2, 1, 4, 3]
-        person_score = pose_entries[n][-2]
-        position_id = -1
-        for keypoint_id in pose_entries[n][:-2]:
-            position_id += 1
-            if position_id == 1:  # no 'neck' in COCO
-                continue
-
-            cx, cy, score, visibility = 0, 0, 0, 0  # keypoint not found
-            if keypoint_id != -1:
-                cx, cy, score = all_keypoints[int(keypoint_id), 0:3]
-                cx = cx + 0.5
-                cy = cy + 0.5
-                visibility = 1
-            keypoints[to_coco_map[position_id] * 3 + 0] = cx
-            keypoints[to_coco_map[position_id] * 3 + 1] = cy
-            keypoints[to_coco_map[position_id] * 3 + 2] = visibility
-        coco_keypoints.append(keypoints)
-        scores.append(person_score * max(0, (pose_entries[n][-1] - 1)))  # -1 for 'neck'
-    return coco_keypoints, scores
-
-
-def infer(net, img, scales, base_height, stride, pad_value=(0, 0, 0), img_mean=(128, 128, 128), img_scale=1 / 256):
-    normed_img = normalize(img, img_mean, img_scale)
-    height, width, _ = normed_img.shape
-    scales_ratios = [scale * base_height / float(height) for scale in scales]
-    avg_heatmaps = np.zeros((height, width, 19), dtype=np.float32)
-    avg_pafs = np.zeros((height, width, 38), dtype=np.float32)
-
-    for ratio in scales_ratios:
-        scaled_img = cv2.resize(normed_img, (0, 0), fx=ratio, fy=ratio, interpolation=cv2.INTER_CUBIC)
-        min_dims = [base_height, max(scaled_img.shape[1], base_height)]
-        padded_img, pad = pad_width(scaled_img, stride, pad_value, min_dims)
-
-        tensor_img = torch.from_numpy(padded_img).permute(2, 0, 1).unsqueeze(0).float().cuda()
-        stages_output = net(tensor_img)
-
-        stage2_heatmaps = stages_output[-2]
-        heatmaps = np.transpose(stage2_heatmaps.squeeze().cpu().data.numpy(), (1, 2, 0))
-        heatmaps = cv2.resize(heatmaps, (0, 0), fx=stride, fy=stride, interpolation=cv2.INTER_CUBIC)
-        heatmaps = heatmaps[pad[0]:heatmaps.shape[0] - pad[2], pad[1]:heatmaps.shape[1] - pad[3]:, :]
-        heatmaps = cv2.resize(heatmaps, (width, height), interpolation=cv2.INTER_CUBIC)
-        avg_heatmaps = avg_heatmaps + heatmaps / len(scales_ratios)
-
-        stage2_pafs = stages_output[-1]
-        pafs = np.transpose(stage2_pafs.squeeze().cpu().data.numpy(), (1, 2, 0))
-        pafs = cv2.resize(pafs, (0, 0), fx=stride, fy=stride, interpolation=cv2.INTER_CUBIC)
-        pafs = pafs[pad[0]:pafs.shape[0] - pad[2], pad[1]:pafs.shape[1] - pad[3], :]
-        pafs = cv2.resize(pafs, (width, height), interpolation=cv2.INTER_CUBIC)
-        avg_pafs = avg_pafs + pafs / len(scales_ratios)
-
-    return avg_heatmaps, avg_pafs
-
-
-def evaluate(labels, output_name, images_folder, net, multiscale=False, visualize=False):
-    net = net.cuda().eval()
-    base_height = 368
-    scales = [1]
-    if multiscale:
-        scales = [0.5, 1.0, 1.5, 2.0]
-    stride = 8
-
-    dataset = CocoValDataset(labels, images_folder)
-    coco_result = []
-    for sample in dataset:
-        file_name = sample['file_name']
-        img = sample['img']
-
-        avg_heatmaps, avg_pafs = infer(net, img, scales, base_height, stride)
-
-        total_keypoints_num = 0
-        all_keypoints_by_type = []
-        for kpt_idx in range(18):  # 19th for bg
-            total_keypoints_num += extract_keypoints(avg_heatmaps[:, :, kpt_idx], all_keypoints_by_type,
-                                                     total_keypoints_num)
-
-        pose_entries, all_keypoints = group_keypoints(all_keypoints_by_type, avg_pafs)
-        coco_keypoints, scores = convert_to_coco_format(pose_entries, all_keypoints)
-
-        image_id = int(file_name[0:file_name.rfind('.')])
-        for idx in range(len(coco_keypoints)):
-            coco_result.append({
-                'image_id': image_id,
-                'category_id': 1,  # person
-                'keypoints': coco_keypoints[idx],
-                'score': scores[idx]
-            })
-
-        if visualize:
-            for keypoints in coco_keypoints:
-                for idx in range(len(keypoints) // 3):
-                    cv2.circle(img, (int(keypoints[idx * 3]), int(keypoints[idx * 3 + 1])),
-                               3, (255, 0, 255), -1)
-            print(coco_keypoints)
-            cv2.imshow('keypoints', img)
-            key = cv2.waitKey()
-            if key == 27:  # esc
-                return
-
-    with open(output_name, 'w') as f:
-        json.dump(coco_result, f, indent=4)
-
-    run_coco_eval(labels, output_name)
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/filtered_pose.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/filtered_pose.py
deleted file mode 100644
index 680acb428a..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/filtered_pose.py
+++ /dev/null
@@ -1,22 +0,0 @@
-# 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.engine.target import Pose
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.one_euro_filter import OneEuroFilter
-
-
-class FilteredPose(Pose):
-    def __init__(self, keypoints, confidence):
-        super().__init__(keypoints, confidence)
-        self.filters = [[OneEuroFilter(), OneEuroFilter()] for _ in range(self.num_kpts)]
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
similarity index 77%
rename from src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
rename to src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index 08cc1928dd..b9135d27a0 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -17,7 +17,6 @@
 import onnxruntime as ort
 import os
 import ntpath
-import shutil
 import cv2
 import torch
 import json
@@ -34,26 +33,20 @@
 from opendr.engine.constants import OPENDR_SERVER_URL
 
 # OpenDR lightweight_open_pose imports
-
-from opendr.perception.pose_estimation.hr_pose_estimation.filtered_pose import FilteredPose
-from opendr.perception.pose_estimation.hr_pose_estimation.utilities import track_poses
-from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.models.with_mobilenet import \
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.models.with_mobilenet import \
     PoseEstimationWithMobileNet
-from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.models.with_mobilenet_v2 import \
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.models.with_mobilenet_v2 import \
     PoseEstimationWithMobileNetV2
-from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.models.with_shufflenet import \
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.models.with_shufflenet import \
     PoseEstimationWithShuffleNet
-
-from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.modules.load_state import \
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.load_state import \
     load_state
-from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.modules.keypoints import \
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.keypoints import \
     extract_keypoints, group_keypoints
-from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.datasets.coco import CocoValDataset
-
-from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.val import \
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.datasets.coco import CocoValDataset
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.val import \
     convert_to_coco_format, run_coco_eval, normalize, pad_width
-from opendr.perception.pose_estimation.hr_pose_estimation.algorithm.scripts import \
-    make_val_subset
+from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.scripts import make_val_subset
 
 
 class HighResolutionPoseEstimationLearner(Learner):
@@ -61,7 +54,7 @@ class HighResolutionPoseEstimationLearner(Learner):
     def __init__(self, device='cuda', backbone='mobilenet',
                  temp_path='temp', mobilenet_use_stride=True, mobilenetv2_width=1.0, shufflenet_groups=3,
                  num_refinement_stages=2, batches_per_iter=1, base_height=256,
-                 first_pass_height=360, second_pass_height=540,
+                 first_pass_height=360, second_pass_height=540, img_resolution=1080,
                  experiment_name='default', num_workers=8, weights_only=True, output_name='detections.json',
                  multiscale=False, scales=None, visualize=False,
                  img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256), pad_value=(0, 0, 0),
@@ -71,7 +64,7 @@ def __init__(self, device='cuda', backbone='mobilenet',
 
         self.first_pass_height = first_pass_height
         self.second_pass_height = second_pass_height
-        self.img_resol = 1080  # default value for sample image in OpenDr server
+        self.img_resol = img_resolution  # default value for sample image in OpenDr server
 
         self.parent_dir = temp_path  # Parent dir should be filled by the user according to README
 
@@ -122,7 +115,7 @@ def __init__(self, device='cuda', backbone='mobilenet',
         self.ort_session = None  # ONNX runtime inference session
         self.model_train_state = True
 
-    def first_pass(self, net, img):
+    def __first_pass(self, net, img):
 
         if 'cuda' in self.device:
             tensor_img = torch.from_numpy(img).permute(2, 0, 1).unsqueeze(0).float().cuda()
@@ -132,24 +125,15 @@ def first_pass(self, net, img):
         else:
             tensor_img = torch.from_numpy(img).permute(2, 0, 1).unsqueeze(0).float().cpu()
 
-        start = torch.cuda.Event(enable_timing=True)
-        end = torch.cuda.Event(enable_timing=True)
-        start.record()
-
         stages_output = net(tensor_img)
 
-        end.record()
-        torch.cuda.synchronize()
-
         stage2_pafs = stages_output[-1]
         pafs = np.transpose(stage2_pafs.squeeze().cpu().data.numpy(), (1, 2, 0))
+        return pafs
 
-        avg_pafs = pafs
-        return avg_pafs
-
-    def second_pass_infer(self, net, img, net_input_height_size, max_width, stride, upsample_ratio,
-                          pad_value=(0, 0, 0),
-                          img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256)):
+    def __second_pass(self, net, img, net_input_height_size, max_width, stride, upsample_ratio,
+                      pad_value=(0, 0, 0),
+                      img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256)):
         height, width, _ = img.shape
         scale = net_input_height_size / height
         img_ratio = width / height
@@ -169,15 +153,8 @@ def second_pass_infer(self, net, img, net_input_height_size, max_width, stride,
         else:
             tensor_img = torch.from_numpy(padded_img).permute(2, 0, 1).unsqueeze(0).float().cpu()
 
-        start = torch.cuda.Event(enable_timing=True)
-        end = torch.cuda.Event(enable_timing=True)
-        start.record()
-
         stages_output = net(tensor_img)
 
-        end.record()
-        torch.cuda.synchronize()
-
         stage2_heatmaps = stages_output[-2]
         heatmaps = np.transpose(stage2_heatmaps.squeeze().cpu().data.numpy(), (1, 2, 0))
         heatmaps = heatmaps.astype(np.float32)
@@ -190,82 +167,82 @@ def second_pass_infer(self, net, img, net_input_height_size, max_width, stride,
 
         return heatmaps, pafs, scale, pad
 
-    def Pooling(self, img, kernel):  # Pooling on input image for dim reduction
-        pooling = torch.nn.AvgPool2d(kernel)
+    def __pooling(self, img, kernel):  # Pooling on input image for dim reduction
+        pool = torch.nn.AvgPool2d(kernel)
         pool_img = torchvision.transforms.ToTensor()(img)
         pool_img = pool_img.unsqueeze(0)
-        pool_img = pooling(pool_img)
+        pool_img = pool(pool_img)
         pool_img = pool_img.squeeze(0).permute(1, 2, 0).cpu().float().numpy()
         return pool_img
 
-    def fit(self, val_dataset=None, logging_path='', logging_flush_secs=30,
-            silent=False, verbose=True, use_val_subset=True, val_subset_size=250,
-            val_images_folder_name="val2017", val_annotations_filename="person_keypoints_val2017.json"):
+    def fit(self, dataset, val_dataset=None, logging_path='', silent=True, verbose=True):
         raise NotImplementedError
 
-    def optimize(self, do_constant_folding=False):
+    def optimize(self, target_device):
         raise NotImplementedError
 
     def reset(self):
         """This method is not used in this implementation."""
         return NotImplementedError
 
-    def save(self, path, verbose=False):
-        """
-        This method is used to save a trained model.
-        Provided with the path, absolute or relative, including a *folder* name, it creates a directory with the name
-        of the *folder* provided and saves the model inside with a proper format and a .json file with metadata.
-
-        If self.optimize was ran previously, it saves the optimized ONNX model in a similar fashion, by copying it
-        from the self.temp_path it was saved previously during conversion.
-
-        :param path: for the model to be saved, including the folder name
-        :type path: str
-        :param verbose: whether to print success message or not, defaults to 'False'
-        :type verbose: bool, optional
-        """
-        if self.model is None and self.ort_session is None:
-            raise UserWarning("No model is loaded, cannot save.")
-
-        folder_name, _, tail = self.__extract_trailing(path)  # Extract trailing folder name from path
-        # Also extract folder name without any extension if extension is erroneously provided
-        folder_name_no_ext = folder_name.split(sep='.')[0]
-
-        # Extract path without folder name, by removing folder name from original path
-        path_no_folder_name = path.replace(folder_name, '')
-        # If tail is '', then path was a/b/c/, which leaves a trailing double '/'
-        if tail == '':
-            path_no_folder_name = path_no_folder_name[0:-1]  # Remove one '/'
-
-        # Create model directory
-        full_path_to_model_folder = path_no_folder_name + folder_name_no_ext
-        os.makedirs(full_path_to_model_folder, exist_ok=True)
-
-        model_metadata = {"model_paths": [], "framework": "pytorch", "format": "", "has_data": False,
-                          "inference_params": {}, "optimized": None, "optimizer_info": {}, "backbone": self.backbone}
-
-        if self.ort_session is None:
-            model_metadata["model_paths"] = [folder_name_no_ext + ".pth"]
-            model_metadata["optimized"] = False
-            model_metadata["format"] = "pth"
-
-            custom_dict = {'state_dict': self.model.state_dict()}
-            torch.save(custom_dict, os.path.join(full_path_to_model_folder, model_metadata["model_paths"][0]))
-            if verbose:
-                print("Saved Pytorch model.")
-        else:
-            model_metadata["model_paths"] = [os.path.join(folder_name_no_ext + ".onnx")]
-            model_metadata["optimized"] = True
-            model_metadata["format"] = "onnx"
-            # Copy already optimized model from temp path
-            shutil.copy2(os.path.join(self.temp_path, "onnx_model_temp.onnx"),
-                         os.path.join(full_path_to_model_folder, model_metadata["model_paths"][0]))
-            model_metadata["optimized"] = True
-            if verbose:
-                print("Saved ONNX model.")
-
-        with open(os.path.join(full_path_to_model_folder, folder_name_no_ext + ".json"), 'w') as outfile:
-            json.dump(model_metadata, outfile)
+    def save(self, path):
+        """This method is not used in this implementation."""
+        return NotImplementedError
+    #     """
+    #     This method is used to save a trained model.
+    #     Provided with the path, absolute or relative, including a *folder* name, it creates a directory with the name
+    #     of the *folder* provided and saves the model inside with a proper format and a .json file with metadata.
+    #
+    #     If self.optimize was ran previously, it saves the optimized ONNX model in a similar fashion, by copying it
+    #     from the self.temp_path it was saved previously during conversion.
+    #
+    #     :param path: for the model to be saved, including the folder name
+    #     :type path: str
+    #     :param verbose: whether to print success message or not, defaults to 'False'
+    #     :type verbose: bool, optional
+    #     """
+    #     if self.model is None and self.ort_session is None:
+    #         raise UserWarning("No model is loaded, cannot save.")
+    #
+    #     folder_name, _, tail = self.__extract_trailing(path)  # Extract trailing folder name from path
+    #     # Also extract folder name without any extension if extension is erroneously provided
+    #     folder_name_no_ext = folder_name.split(sep='.')[0]
+    #
+    #     # Extract path without folder name, by removing folder name from original path
+    #     path_no_folder_name = path.replace(folder_name, '')
+    #     # If tail is '', then path was a/b/c/, which leaves a trailing double '/'
+    #     if tail == '':
+    #         path_no_folder_name = path_no_folder_name[0:-1]  # Remove one '/'
+    #
+    #     # Create model directory
+    #     full_path_to_model_folder = path_no_folder_name + folder_name_no_ext
+    #     os.makedirs(full_path_to_model_folder, exist_ok=True)
+    #
+    #     model_metadata = {"model_paths": [], "framework": "pytorch", "format": "", "has_data": False,
+    #                       "inference_params": {}, "optimized": None, "optimizer_info": {}, "backbone": self.backbone}
+    #
+    #     if self.ort_session is None:
+    #         model_metadata["model_paths"] = [folder_name_no_ext + ".pth"]
+    #         model_metadata["optimized"] = False
+    #         model_metadata["format"] = "pth"
+    #
+    #         custom_dict = {'state_dict': self.model.state_dict()}
+    #         torch.save(custom_dict, os.path.join(full_path_to_model_folder, model_metadata["model_paths"][0]))
+    #         if verbose:
+    #             print("Saved Pytorch model.")
+    #     else:
+    #         model_metadata["model_paths"] = [os.path.join(folder_name_no_ext + ".onnx")]
+    #         model_metadata["optimized"] = True
+    #         model_metadata["format"] = "onnx"
+    #         # Copy already optimized model from temp path
+    #         shutil.copy2(os.path.join(self.temp_path, "onnx_model_temp.onnx"),
+    #                      os.path.join(full_path_to_model_folder, model_metadata["model_paths"][0]))
+    #         model_metadata["optimized"] = True
+    #         if verbose:
+    #             print("Saved ONNX model.")
+    #
+    #     with open(os.path.join(full_path_to_model_folder, folder_name_no_ext + ".json"), 'w') as outfile:
+    #         json.dump(model_metadata, outfile)
 
     def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
              subset_size=250,
@@ -339,7 +316,7 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
             max_width = w
             kernel = int(h / self.first_pass_height)
             if kernel > 0:
-                pool_img = HighResolutionPoseEstimationLearner.Pooling(self, img, kernel)
+                pool_img = HighResolutionPoseEstimationLearner.__pooling(self, img, kernel)
 
             else:
                 pool_img = img
@@ -349,7 +326,7 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
             thresshold = 0.1  # thresshold for heatmap
 
             # ------- Heatmap Generation -------
-            avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.model, pool_img)
+            avg_pafs = HighResolutionPoseEstimationLearner.__first_pass(self, self.model, pool_img)
             avg_pafs = avg_pafs.astype(np.float32)
 
             pafs_map = cv2.blur(avg_pafs, (5, 5))
@@ -402,10 +379,10 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
 
                 # ------- Second pass of the image, inference for pose estimation -------
                 avg_heatmaps, avg_pafs, scale, pad = \
-                    HighResolutionPoseEstimationLearner.second_pass_infer(self,
-                                                                          self.model, crop_img,
-                                                                          self.second_pass_height, max_width,
-                                                                          self.stride, self.upsample_ratio)
+                    HighResolutionPoseEstimationLearner.__second_pass(self,
+                                                                      self.model, crop_img,
+                                                                      self.second_pass_height, max_width,
+                                                                      self.stride, self.upsample_ratio)
                 total_keypoints_num = 0
                 all_keypoints_by_type = []
                 for kpt_idx in range(18):
@@ -497,7 +474,7 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
         kernel = int(h / self.first_pass_height)
         if kernel > 0:
-            pool_img = HighResolutionPoseEstimationLearner.Pooling(self, img, kernel)
+            pool_img = HighResolutionPoseEstimationLearner.__pooling(self, img, kernel)
         else:
             pool_img = img
 
@@ -506,7 +483,7 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
         thresshold = 0.1  # threshold for heatmap
 
         # ------- Heatmap Generation -------
-        avg_pafs = HighResolutionPoseEstimationLearner.first_pass(self, self.model, pool_img)
+        avg_pafs = HighResolutionPoseEstimationLearner.__first_pass(self, self.model, pool_img)
         avg_pafs = avg_pafs.astype(np.float32)
         pafs_map = cv2.blur(avg_pafs, (5, 5))
 
@@ -558,9 +535,9 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
             # ------- Second pass of the image, inference for pose estimation -------
             avg_heatmaps, avg_pafs, scale, pad = \
-                HighResolutionPoseEstimationLearner.second_pass_infer(self, self.model, crop_img,
-                                                                      self.second_pass_height,
-                                                                      max_width, stride, upsample_ratio)
+                HighResolutionPoseEstimationLearner.__second_pass(self, self.model, crop_img,
+                                                                  self.second_pass_height,
+                                                                  max_width, stride, upsample_ratio)
 
             total_keypoints_num = 0
             all_keypoints_by_type = []
@@ -595,98 +572,6 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
         return current_poses
 
-    def infer_light_odr(self, img, upsample_ratio=4, track=True, smooth=True):  # LwOP from OpenDR implementation
-        """
-        This method is used to perform pose estimation on an image.
-
-        :param img: image to run inference on
-        :rtype img: engine.data.Image class object
-        :param upsample_ratio: Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing,
-            defaults to 4
-        :type upsample_ratio: int, optional
-        :param track: If True, infer propagates poses ids from previous frame results to track poses, defaults to 'True'
-        :type track: bool, optional
-        :param smooth: If True, smoothing is performed on pose keypoints between frames, defaults to 'True'
-        :type smooth: bool, optional
-        :return: Returns a list of engine.target.Pose objects, where each holds a pose, or returns an empty list if no
-            detections were made.
-        :rtype: list of engine.target.Pose objects
-        """
-        if not isinstance(img, Image):
-            img = Image(img)
-
-        # Bring image into the appropriate format for the implementation
-        img = img.convert(format='channels_last', channel_order='bgr')
-
-        height, width, _ = img.shape
-        scale = self.base_height / height
-
-        scaled_img = cv2.resize(img, (0, 0), fx=scale, fy=scale, interpolation=cv2.INTER_LINEAR)
-        scaled_img = normalize(scaled_img, self.img_mean, self.img_scale)
-        min_dims = [self.base_height, max(scaled_img.shape[1], self.base_height)]
-        padded_img, pad = pad_width(scaled_img, self.stride, self.pad_value, min_dims)
-
-        tensor_img = torch.from_numpy(padded_img).permute(2, 0, 1).unsqueeze(0).float()
-        if "cuda" in self.device:
-            tensor_img = tensor_img.to(self.device)
-            if self.half:
-                tensor_img = tensor_img.half()
-
-        if self.ort_session is not None:
-            stages_output = self.ort_session.run(None, {'data': np.array(tensor_img.cpu())})
-            stage2_heatmaps = torch.tensor(stages_output[-2])
-            stage2_pafs = torch.tensor(stages_output[-1])
-        else:
-            if self.model is None:
-                raise UserWarning("No model is loaded, cannot run inference. Load a model first using load().")
-            if self.model_train_state:
-                self.model.eval()
-                self.model_train_state = False
-            stages_output = self.model(tensor_img)
-            stage2_heatmaps = stages_output[-2]
-            stage2_pafs = stages_output[-1]
-
-        heatmaps = np.transpose(stage2_heatmaps.squeeze().cpu().data.numpy(), (1, 2, 0))
-        if self.half:
-            heatmaps = np.float32(heatmaps)
-        heatmaps = cv2.resize(heatmaps, (0, 0), fx=upsample_ratio, fy=upsample_ratio, interpolation=cv2.INTER_CUBIC)
-
-        pafs = np.transpose(stage2_pafs.squeeze().cpu().data.numpy(), (1, 2, 0))
-        if self.half:
-            pafs = np.float32(pafs)
-        pafs = cv2.resize(pafs, (0, 0), fx=upsample_ratio, fy=upsample_ratio, interpolation=cv2.INTER_CUBIC)
-
-        total_keypoints_num = 0
-        all_keypoints_by_type = []
-        num_keypoints = 18
-        for kpt_idx in range(num_keypoints):  # 19th for bg
-            total_keypoints_num += extract_keypoints(heatmaps[:, :, kpt_idx], all_keypoints_by_type,
-                                                     total_keypoints_num)
-
-        pose_entries, all_keypoints = group_keypoints(all_keypoints_by_type, pafs)
-        for kpt_id in range(all_keypoints.shape[0]):
-            all_keypoints[kpt_id, 0] = (all_keypoints[kpt_id, 0] * self.stride / upsample_ratio - pad[1]) / scale
-            all_keypoints[kpt_id, 1] = (all_keypoints[kpt_id, 1] * self.stride / upsample_ratio - pad[0]) / scale
-        current_poses = []
-        for n in range(len(pose_entries)):
-            if len(pose_entries[n]) == 0:
-                continue
-            pose_keypoints = np.ones((num_keypoints, 2), dtype=np.int32) * -1
-            for kpt_id in range(num_keypoints):
-                if pose_entries[n][kpt_id] != -1.0:  # keypoint was found
-                    pose_keypoints[kpt_id, 0] = int(all_keypoints[int(pose_entries[n][kpt_id]), 0])
-                    pose_keypoints[kpt_id, 1] = int(all_keypoints[int(pose_entries[n][kpt_id]), 1])
-            if smooth:
-                pose = FilteredPose(pose_keypoints, pose_entries[n][18])
-            else:
-                pose = Pose(pose_keypoints, pose_entries[n][18])
-            current_poses.append(pose)
-
-        if track:
-            track_poses(self.previous_poses, current_poses, smooth=smooth)
-            self.previous_poses = current_poses
-        return current_poses
-
     def init_model(self):
         if self.model is None:
             # No model loaded, initializing new
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/utilities.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/utilities.py
deleted file mode 100644
index d26dc49a0e..0000000000
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/utilities.py
+++ /dev/null
@@ -1,153 +0,0 @@
-# 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 numpy as np
-import cv2
-from opendr.engine.target import Pose
-
-# More information on body-part id naming on target.py - Pose class.
-# For in-depth explanation of BODY_PARTS_KPT_IDS and BODY_PARTS_PAF_IDS see
-#  https://github.com/Daniil-Osokin/lightweight-human-pose-estimation.pytorch/blob/master/TRAIN-ON-CUSTOM-DATASET.md
-BODY_PARTS_KPT_IDS = [[1, 2], [1, 5], [2, 3], [3, 4], [5, 6], [6, 7], [1, 8], [8, 9], [9, 10], [1, 11],
-                      [11, 12], [12, 13], [1, 0], [0, 14], [14, 16], [0, 15], [15, 17], [2, 16], [5, 17]]
-BODY_PARTS_PAF_IDS = ([12, 13], [20, 21], [14, 15], [16, 17], [22, 23], [24, 25], [0, 1], [2, 3], [4, 5],
-                      [6, 7], [8, 9], [10, 11], [28, 29], [30, 31], [34, 35], [32, 33], [36, 37], [18, 19],
-                      [26, 27])
-sigmas = np.array([.26, .79, .79, .72, .62, .79, .72, .62, 1.07, .87, .89, 1.07, .87, .89, .25, .25, .35, .35],
-                  dtype=np.float32) / 10.0
-vars_ = (sigmas * 2) ** 2
-last_id = -1
-color = [0, 224, 255]
-
-
-def get_bbox(pose):
-    """
-    Return a cv2 bounding box based on the keypoints of the pose provided.
-
-    :param pose: Pose class object
-    :return: bounding box as cv2.boundingRect object
-    """
-    found_keypoints = np.zeros((np.count_nonzero(pose.data[:, 0] != -1), 2), dtype=np.int32)
-    found_kpt_id = 0
-    for kpt_id in range(Pose.num_kpts):
-        if pose.data[kpt_id, 0] == -1:
-            continue
-        found_keypoints[found_kpt_id] = pose.data[kpt_id]
-        found_kpt_id += 1
-    bbox = cv2.boundingRect(found_keypoints)
-    return bbox
-
-
-def update_id(pose, id_=None):
-    """
-    Increments or updates the id of the provided pose.
-
-    :param pose: Pose class object
-    :param id_: id to set, leave None to increment pose.id by one
-    """
-    pose.id = id_
-    if pose.id is None:
-        pose.id = Pose.last_id + 1
-        Pose.last_id += 1
-
-
-def draw(img, pose):
-    """
-    Draws the provided pose on the provided image.
-
-    :param img: the image to draw the pose on
-    :param pose: the pose to draw on the image
-    """
-    assert pose.data.shape == (Pose.num_kpts, 2)
-
-    for part_id in range(len(BODY_PARTS_PAF_IDS) - 2):
-        kpt_a_id = BODY_PARTS_KPT_IDS[part_id][0]
-        global_kpt_a_id = pose.data[kpt_a_id, 0]
-        x_a, y_a, x_b, y_b = 0, 0, 0, 0
-        if global_kpt_a_id != -1:
-            x_a, y_a = pose.data[kpt_a_id]
-            cv2.circle(img, (int(x_a), int(y_a)), 3, color, -1)
-        kpt_b_id = BODY_PARTS_KPT_IDS[part_id][1]
-        global_kpt_b_id = pose.data[kpt_b_id, 0]
-        if global_kpt_b_id != -1:
-            x_b, y_b = pose.data[kpt_b_id]
-            cv2.circle(img, (int(x_b), int(y_b)), 3, color, -1)
-        if global_kpt_a_id != -1 and global_kpt_b_id != -1:
-            cv2.line(img, (int(x_a), int(y_a)), (int(x_b), int(y_b)), color, 2)
-
-
-def get_similarity(a, b, threshold=0.5):
-    """
-    Calculates the Keypoint Similarity, explained in detail on the official COCO dataset site
-    https://cocodataset.org/#keypoints-eval
-
-    :param a: first pose
-    :param b: second pose
-    :param threshold: the similarity threshold to consider the keypoints similar
-    :return: number of similar keypoints
-    :rtype: int
-    """
-    bbox_a = get_bbox(a)
-    bbox_b = get_bbox(b)
-    num_similar_kpt = 0
-    for kpt_id in range(Pose.num_kpts):
-        if a.data[kpt_id, 0] != -1 and b.data[kpt_id, 0] != -1:
-            distance = np.sum((a.data[kpt_id] - b.data[kpt_id]) ** 2)
-            area = max(bbox_a[2] * bbox_a[3], bbox_b[2] * bbox_b[3])
-            similarity = np.exp(-distance / (2 * (area + np.spacing(1)) * vars_[kpt_id]))
-            if similarity > threshold:
-                num_similar_kpt += 1
-    return num_similar_kpt
-
-
-def track_poses(previous_poses, current_poses, threshold=3, smooth=False):
-    """
-    Propagate poses ids from previous frame results. Id is propagated,
-    if there are at least `threshold` similar keypoints between pose from previous frame and current.
-    If correspondence between pose on previous and current frame was established, pose keypoints are smoothed.
-
-    :param previous_poses: poses from previous frame with ids
-    :param current_poses: poses from current frame to assign ids
-    :param threshold: minimal number of similar keypoints between poses
-    :param smooth: smooth pose keypoints between frames
-    """
-    current_poses = sorted(current_poses, key=lambda pose: pose.confidence, reverse=True)  # match confident poses first
-    mask = np.ones(len(previous_poses), dtype=np.int32)
-    for current_pose in current_poses:
-        best_matched_id = None
-        best_matched_pose_id = None
-        best_matched_iou = 0
-        for id_, previous_pose in enumerate(previous_poses):
-            if not mask[id_]:
-                continue
-            iou = get_similarity(current_pose, previous_pose)
-            if iou > best_matched_iou:
-                best_matched_iou = iou
-                best_matched_pose_id = previous_pose.id
-                best_matched_id = id_
-        if best_matched_iou >= threshold:
-            mask[best_matched_id] = 0
-        else:  # pose not similar to any previous
-            best_matched_pose_id = None
-        update_id(current_pose, best_matched_pose_id)
-
-        if smooth:
-            for kpt_id in range(Pose.num_kpts):
-                if current_pose.data[kpt_id, 0] == -1:
-                    continue
-                # reuse filter if previous pose has valid filter
-                if best_matched_pose_id is not None and previous_poses[best_matched_id].data[kpt_id, 0] != -1:
-                    current_pose.filters[kpt_id] = previous_poses[best_matched_id].filters[kpt_id]
-                current_pose.data[kpt_id, 0] = current_pose.filters[kpt_id][0](current_pose.data[kpt_id, 0])
-                current_pose.data[kpt_id, 1] = current_pose.filters[kpt_id][1](current_pose.data[kpt_id, 1])
diff --git a/tests/test_license.py b/tests/test_license.py
index 1f1a0eb6b6..6452095449 100755
--- a/tests/test_license.py
+++ b/tests/test_license.py
@@ -86,7 +86,6 @@ def setUp(self):
         ]
 
         skippedDirectoryPaths = [
-            'src/opendr/perception/pose_estimation/hr_pose_estimation/algorithm',
             'src/opendr/perception/pose_estimation/lightweight_open_pose/algorithm',
             'src/opendr/perception/object_detection_3d/voxel_object_detection_3d/second_detector',
             'src/opendr/perception/face_recognition/algorithm',

From fcadc1441c963d58b96137078e97e91bc97fadc8 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Tue, 13 Dec 2022 12:15:19 +0200
Subject: [PATCH 13/27] suggestions from review (edit functions, code
 duplication,typos,etc)

---
 .../high_resolution_pose_estimation.md        | 113 ++++++------------
 docs/reference/index.md                       |   2 +-
 .../high_resolution_pose_estimation/README.md |   0
 .../demos/benchmarking_demo.py                |   4 +-
 .../demos/eval_demo.py                        |   4 +-
 .../demos/inference_demo.py                   |   4 +-
 .../lightweight_open_pose/README.md           |   0
 .../demos/benchmarking_demo.py                |   4 +-
 .../lightweight_open_pose/demos/eval_demo.py  |   4 +-
 .../demos/inference_demo.py                   |   4 +-
 .../demos/inference_tutorial.ipynb            |   0
 .../demos/webcam_demo.py                      |   2 +-
 .../lightweight_open_pose/jetbot/README.md    |   0
 .../lightweight_open_pose/jetbot/evaluate.sh  |   0
 .../jetbot/fall_controller.py                 |   2 +-
 .../lightweight_open_pose/jetbot/flask.png    | Bin
 .../lightweight_open_pose/jetbot/jetbot.sh    |   0
 .../jetbot/jetbot_kill.sh                     |   0
 .../jetbot/requirements.txt                   |   0
 .../jetbot/results/.keep                      |   0
 .../simulation_pose/protos/human_010_sit.wbo  |   0
 .../protos/human_010_standing.wbo             |   0
 .../simulation_pose/worlds/pose_demo.wbt      |   0
 .../worlds/textures/brown_eye.png             | Bin
 .../worlds/textures/eyebrow005.png            | Bin
 .../worlds/textures/eyebrow009.png            | Bin
 .../worlds/textures/eyelashes01.png           | Bin
 .../worlds/textures/eyelashes04.png           | Bin
 .../textures/female_elegantsuit01_diffuse.png | Bin
 .../textures/female_elegantsuit01_normal.png  | Bin
 .../worlds/textures/keylthnormals.png         | Bin
 .../worlds/textures/keylthtex1.png            | Bin
 .../textures/male_casualsuit02_diffuse.png    | Bin
 .../textures/male_casualsuit02_normal.png     | Bin
 .../middleage_lightskinned_male_diffuse2.png  | Bin
 .../worlds/textures/short01_diffuse.png       | Bin
 .../jetbot/static/eu.png                      | Bin
 .../jetbot/static/opendr.png                  | Bin
 .../jetbot/static/opendr_logo.png             | Bin
 .../jetbot/templates/index.html               |   0
 .../jetbot/utils/__init__.py                  |   0
 .../jetbot/utils/active.py                    |   0
 .../lightweight_open_pose/jetbot/utils/pid.py |   0
 .../jetbot/utils/pose_controller.py           |   0
 .../jetbot/utils/pose_utils.py                |   0
 .../jetbot/utils/robot_interface.py           |   0
 .../jetbot/utils/visualization.py             |   0
 .../jetbot/utils/webots.py                    |   0
 .../high_resolution_learner.py                |  73 +----------
 49 files changed, 56 insertions(+), 160 deletions(-)
 rename projects/python/perception/{ => pose_estimation}/high_resolution_pose_estimation/README.md (100%)
 rename projects/python/perception/{ => pose_estimation}/high_resolution_pose_estimation/demos/benchmarking_demo.py (96%)
 rename projects/python/perception/{ => pose_estimation}/high_resolution_pose_estimation/demos/eval_demo.py (96%)
 rename projects/python/perception/{ => pose_estimation}/high_resolution_pose_estimation/demos/inference_demo.py (95%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/README.md (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/demos/benchmarking_demo.py (96%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/demos/eval_demo.py (95%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/demos/inference_demo.py (95%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/demos/inference_tutorial.ipynb (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/demos/webcam_demo.py (98%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/README.md (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/evaluate.sh (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/fall_controller.py (98%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/flask.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/jetbot.sh (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/jetbot_kill.sh (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/requirements.txt (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/results/.keep (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_sit.wbo (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_standing.wbo (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/pose_demo.wbt (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/brown_eye.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow005.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow009.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes01.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes04.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_diffuse.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_normal.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthnormals.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthtex1.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_diffuse.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_normal.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/middleage_lightskinned_male_diffuse2.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/short01_diffuse.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/static/eu.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/static/opendr.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/static/opendr_logo.png (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/templates/index.html (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/utils/__init__.py (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/utils/active.py (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/utils/pid.py (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/utils/pose_controller.py (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/utils/pose_utils.py (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/utils/robot_interface.py (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/utils/visualization.py (100%)
 rename projects/python/perception/{ => pose_estimation}/lightweight_open_pose/jetbot/utils/webots.py (100%)

diff --git a/docs/reference/high_resolution_pose_estimation.md b/docs/reference/high_resolution_pose_estimation.md
index dd9d675347..53aa8761b5 100644
--- a/docs/reference/high_resolution_pose_estimation.md
+++ b/docs/reference/high_resolution_pose_estimation.md
@@ -8,7 +8,8 @@ Bases: `engine.learners.Learner`
 The *HighResolutionLightweightOpenPose* class is an implementation for pose estimation in high resolution images.
 This method creates a heatmap of a resized version of the input image.
 Using this heatmap, the input image is cropped keeping the area of interest and then it is used for pose estimation.
-The pose estimation is based on the Lightweight OpenPose algorithm.
+Since the high resolution pose estimation method is based on Lightweight OpenPose algorithm,the models that could be used have to be trained with Lightweight OpenPose tool.
+
 In this method there are two important variables which are responsible for the increase in speed and accuracy in high resolution images.
 These variables are the *first_pass_height* and the *second_pass_height* that the image is resized in this procedure.
 
@@ -113,15 +114,20 @@ Parameters:
   Object of type engine.data.Image.
 - **upsample_ratio**: *int, default=4*\
   Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing.
+- **stride**: *int, default=8*\
+  Defines the stride value for creating a padded image.
 - **track**: *bool, default=True*\
   If True, infer propagates poses ids from previous frame results to track poses.
 - **smooth**: *bool, default=True*\
   If True, smoothing is performed on pose keypoints between frames.
+- **multiscale**: *bool, default=False*\
+  Specifies whether evaluation will run in the predefined multiple scales setup or not.
+
 
 
-#### `HighResolutionPoseEstimationLearner.first_pass`
+#### `HighResolutionPoseEstimationLearner.__first_pass`
 ```python
-HighResolutionPoseEstimationLearner.first_pass(self, net, img)
+HighResolutionPoseEstimationLearner.__first_pass(self, net, img)
 ```
 
 This method is used for extracting from the input image a heatmap about human locations in the picture.
@@ -133,9 +139,9 @@ Parameters:
 - **net**: *object*\
   The model that is used for creating the heatmap.
 
-#### `HighResolutionPoseEstimationLearner.second_pass`
+#### `HighResolutionPoseEstimationLearner.__second_pass`
 ```python
-HighResolutionPoseEstimationLearner.second_pass_infer(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, pad_value, img_mean, img_scale)
+HighResolutionPoseEstimationLearner.__second_pass(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, pad_value, img_mean, img_scale)
 ```
 
 On this method it is carried out the second inference step which estimates the human poses on the image that is inserted.
@@ -162,66 +168,6 @@ Parameters:
 - **img_scale**: *float, default=1/256*\
   Specifies the scale based on which the images are normalized.
 
-#### `HighResolutionPoseEstimation.pooling`
-```python
-HighResolutionPoseEstimation.Pooling(self, img, kernel)
-```
-
-Parameters:
-
-- **img**: *object***\
-  Object of type engine.data.Image.
-- **kernel**: *int*\
-  The size of kernel in Average Pooling procedure before heatmap generation in order to resize the input image.
-
-#### `HighResolutionPoseEstimation.infer_light_odr()`
-```python
-HighResolutionPoseEstimation.infer_light_odr(self, img, upsample_ratio, track, smooth)
-```
-
-This method is an inference function of OpenDR LightWeight OpenPose pose estiamtion.
-
-Parameters:
-
-- **img**: *object***\
-  Object of type engine.data.Image.
-- **upsample_ratio**: *int, default=4*\
-  Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing.
-- **track**: *bool, default=True*\
-  If True, infer propagates poses ids from previous frame results to track poses.
-- **smooth**: *bool, default=True*\
-  If True, smoothing is performed on pose keypoints between frames.
-
-#### `HighResolutionPoseEstimation.save`
-```python
-HighResolutionPoseEstimation.save(self, path, verbose)
-```
-
-This method is used to save a trained model.
-Provided with the path "/my/path/name" (absolute or relative), it creates the "name" directory, if it does not already exist.
-Inside this folder, the model is saved as "name.pth" and the metadata file as "name.json". If the directory already exists, the "name.pth" and "name.json" files are overwritten.
-
-Parameters:
-
-- **path**: *str*\
-  Path to save the model, including the filename.
-- **verbose**: *bool, default=False*\
-  If set to True, prints a message on success.
-
-#### `HighResolutionPoseEstimation.load`
-```python
-HighResolutionPoseEstimation.load(self, path, verbose)
-```
-
-This method is used to load a previously saved model from its saved folder.
-Loads the model from inside the directory of the path provided, using the metadata .json file included.
-
-Parameters:
-
-- **path**: *str*\
-  Path of the model to be loaded.
-- **verbose**: *bool, default=False*\
-  If set to True, prints a message on success.
 
 #### `HighResolutionPoseEstimation.download`
 ```python
@@ -260,7 +206,7 @@ Parameters:
                                                        mobilenet_use_stride=False, half_precision=False,
                                                        first_pass_height=360,
                                                        second_pass_height=540,
-                                                       img_resol=1080)
+                                                       img_resolution=1080)
   pose_estimator.download()  # Download the default pretrained mobilenet model in the temp_path
 
   pose_estimator.load("./parent_dir/openpose_default")
@@ -324,21 +270,32 @@ was used as input to the models.
 The average precision and average recall on the COCO evaluation split is also reported in the Table below:
 
 
-#### Lightweight OpenPose
-| Method            | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) | Evaluation time (sec) |
-|-------------------|------------------------------|---------------------------|-----------------------|
-| OpenDR - Baseline | 0.0                          | 0.0                       | 6558                  |
+#### Lightweight OpenPose with resizing
+| Method            | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) |
+|-------------------|------------------------------|---------------------------|
+| OpenDR - Baseline | 0.101                        | 0.267                     |
+ | OpenDR - Full     | 0.031                        | 0.044                     |
+
+
+
+
+#### Lightweight OpenPose without resizing
+| Method            | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) |
+|-------------------|------------------------------|---------------------------|
+| OpenDR - Baseline | 0.695                        | 0.749                     |
+| OpenDR - Full     | 0.389                        | 0.441                     |
+
 
 
 #### High Resolution Pose Estimation
-| Method                 | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) | Evaluation Time (sec) |
-|------------------------|------------------------------|---------------------------|-----------------------|
-| HRPoseEstim - Baseline | 0.615                        | 0.637                     | 288                   |
-| HRPoseEstim - Half     | 0.604                        | 0.621                     | 269                   |
-| HRPoseEstim - Stride   | 0.262                        | 0.274                     | 160                   |
-| HRPoseEstim - Stages   | 0.539                        | 0.562                     | 238                   |
-| HRPoseEstim - H+S      | 0.254                        | 0.267                     | 165                   |
-| HRPoseEstim - Full     | 0.259                        | 0.272                     | 145                   |
+| Method                 | Average Precision (IoU=0.50) | Average Recall (IoU=0.50) |
+|------------------------|------------------------------|---------------------------|
+| HRPoseEstim - Baseline | 0.615                        | 0.637                     |
+| HRPoseEstim - Half     | 0.604                        | 0.621                     |
+| HRPoseEstim - Stride   | 0.262                        | 0.274                     | 
+| HRPoseEstim - Stages   | 0.539                        | 0.562                     |
+| HRPoseEstim - H+S      | 0.254                        | 0.267                     |
+| HRPoseEstim - Full     | 0.259                        | 0.272                     |
 
 The average precision and the average recall have been calculated on a 1080p version of COCO2017 validation dataset and the results are reported in the table below:
 
diff --git a/docs/reference/index.md b/docs/reference/index.md
index 6e0be38158..960833158e 100644
--- a/docs/reference/index.md
+++ b/docs/reference/index.md
@@ -109,7 +109,7 @@ 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)
         - 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)
diff --git a/projects/python/perception/high_resolution_pose_estimation/README.md b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/README.md
similarity index 100%
rename from projects/python/perception/high_resolution_pose_estimation/README.md
rename to projects/python/perception/pose_estimation/high_resolution_pose_estimation/README.md
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
similarity index 96%
rename from projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
rename to projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
index 7fc66de1f0..88b894ad79 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/benchmarking_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
@@ -53,11 +53,11 @@
                                                          mobilenet_use_stride=stride, half_precision=half_precision,
                                                          first_pass_height=base_height1,
                                                          second_pass_height=base_height2)
-    pose_estimator.download(path=".", verbose=True)
+    pose_estimator.download(path="", verbose=True)
     pose_estimator.load("openpose_default")
 
     # Download one sample image
-    pose_estimator.download(path=".", mode="test_data")
+    pose_estimator.download(path="", mode="test_data")
     image_path = join("temp", "dataset", "image", "000000000785_1080.jpg")
     img = cv2.imread(image_path)
 
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
similarity index 96%
rename from projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
rename to projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
index 5c1c9100ff..50938a5b15 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/eval_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
@@ -47,14 +47,14 @@
                                                          half_precision=half_precision,
                                                          first_pass_height=base_height1,
                                                          second_pass_height=base_height2)
-    pose_estimator.download(path=".", verbose=True)
+    pose_estimator.download(path="", verbose=True)
     pose_estimator.load("openpose_default")
 
     if onnx:
         pose_estimator.optimize()
 
     # Download a sample dataset
-    pose_estimator.download(path=".", mode="test_data")
+    pose_estimator.download(path="", mode="test_data")
 
     eval_dataset = ExternalDataset(path=join("temp", "dataset"), dataset_type="COCO")
 
diff --git a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
similarity index 95%
rename from projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
rename to projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
index df6d62df6f..d8c58f61fc 100644
--- a/projects/python/perception/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
@@ -47,11 +47,11 @@
                                                          mobilenet_use_stride=stride, half_precision=half_precision,
                                                          first_pass_height=base_height1,
                                                          second_pass_height=base_height2)
-    pose_estimator.download(path=".", verbose=True)
+    pose_estimator.download(path="", verbose=True)
     pose_estimator.load("openpose_default")
 
     # Download one sample image
-    pose_estimator.download(path=".", mode="test_data")
+    pose_estimator.download(path="", mode="test_data")
 
     image_path = join("temp", "dataset", "image", "000000000785_1080.jpg")
 
diff --git a/projects/python/perception/lightweight_open_pose/README.md b/projects/python/perception/pose_estimation/lightweight_open_pose/README.md
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/README.md
rename to projects/python/perception/pose_estimation/lightweight_open_pose/README.md
diff --git a/projects/python/perception/lightweight_open_pose/demos/benchmarking_demo.py b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/benchmarking_demo.py
similarity index 96%
rename from projects/python/perception/lightweight_open_pose/demos/benchmarking_demo.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/demos/benchmarking_demo.py
index cc80487d70..24ebefe688 100644
--- a/projects/python/perception/lightweight_open_pose/demos/benchmarking_demo.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/benchmarking_demo.py
@@ -40,11 +40,11 @@
 
     pose_estimator = LightweightOpenPoseLearner(device=device, num_refinement_stages=stages,
                                                 mobilenet_use_stride=stride, half_precision=half_precision)
-    pose_estimator.download(path=".", verbose=True)
+    pose_estimator.download(path="", verbose=True)
     pose_estimator.load("openpose_default")
 
     # Download one sample image
-    pose_estimator.download(path=".", mode="test_data")
+    pose_estimator.download(path="", mode="test_data")
     image_path = join("temp", "dataset", "image", "000000000785.jpg")
     img = cv2.imread(image_path)
 
diff --git a/projects/python/perception/lightweight_open_pose/demos/eval_demo.py b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/eval_demo.py
similarity index 95%
rename from projects/python/perception/lightweight_open_pose/demos/eval_demo.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/demos/eval_demo.py
index 3ecd6c6884..5055415dc1 100644
--- a/projects/python/perception/lightweight_open_pose/demos/eval_demo.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/eval_demo.py
@@ -39,14 +39,14 @@
     pose_estimator = LightweightOpenPoseLearner(device=device, num_refinement_stages=stages,
                                                 mobilenet_use_stride=stride,
                                                 half_precision=half_precision)
-    pose_estimator.download(path=".", verbose=True)
+    pose_estimator.download(path="", verbose=True)
     pose_estimator.load("openpose_default")
 
     if onnx:
         pose_estimator.optimize()
 
     # Download a sample dataset
-    pose_estimator.download(path=".", mode="test_data")
+    pose_estimator.download(path="", mode="test_data")
 
     eval_dataset = ExternalDataset(path=join("temp", "dataset"), dataset_type="COCO")
 
diff --git a/projects/python/perception/lightweight_open_pose/demos/inference_demo.py b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/inference_demo.py
similarity index 95%
rename from projects/python/perception/lightweight_open_pose/demos/inference_demo.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/demos/inference_demo.py
index 1b494919fa..549493d87f 100644
--- a/projects/python/perception/lightweight_open_pose/demos/inference_demo.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/inference_demo.py
@@ -39,11 +39,11 @@
 
     pose_estimator = LightweightOpenPoseLearner(device=device, num_refinement_stages=stages,
                                                 mobilenet_use_stride=stride, half_precision=half_precision)
-    pose_estimator.download(path=".", verbose=True)
+    pose_estimator.download(path="", verbose=True)
     pose_estimator.load("openpose_default")
 
     # Download one sample image
-    pose_estimator.download(path=".", mode="test_data")
+    pose_estimator.download(path="", mode="test_data")
     image_path = join("temp", "dataset", "image", "000000000785.jpg")
     img = Image.open(image_path)
 
diff --git a/projects/python/perception/lightweight_open_pose/demos/inference_tutorial.ipynb b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/inference_tutorial.ipynb
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/demos/inference_tutorial.ipynb
rename to projects/python/perception/pose_estimation/lightweight_open_pose/demos/inference_tutorial.ipynb
diff --git a/projects/python/perception/lightweight_open_pose/demos/webcam_demo.py b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/webcam_demo.py
similarity index 98%
rename from projects/python/perception/lightweight_open_pose/demos/webcam_demo.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/demos/webcam_demo.py
index 149783d1e1..7eb7993004 100644
--- a/projects/python/perception/lightweight_open_pose/demos/webcam_demo.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/webcam_demo.py
@@ -63,7 +63,7 @@ def __next__(self):
 
     pose_estimator = LightweightOpenPoseLearner(device=device, num_refinement_stages=stages,
                                                 mobilenet_use_stride=stride, half_precision=half_precision)
-    pose_estimator.download(path=".", verbose=True)
+    pose_estimator.download(path="", verbose=True)
     pose_estimator.load("openpose_default")
 
     if onnx:
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/README.md b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/README.md
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/README.md
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/README.md
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/evaluate.sh b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/evaluate.sh
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/evaluate.sh
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/evaluate.sh
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/fall_controller.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/fall_controller.py
similarity index 98%
rename from projects/python/perception/lightweight_open_pose/jetbot/fall_controller.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/fall_controller.py
index cc9ecb32a9..baaf0db90b 100644
--- a/projects/python/perception/lightweight_open_pose/jetbot/fall_controller.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/fall_controller.py
@@ -82,7 +82,7 @@
                                                     mobilenet_use_stride=False, half_precision=False)
         infer_delay = 0.43  # delay calculated based on FPS on jetbot
 
-    pose_estimator.download(path=".", verbose=True)
+    pose_estimator.download(path="", verbose=True)
     pose_estimator.load("./openpose_default")
 
     def fall_handler_fn_file(imgs):
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/flask.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/flask.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/flask.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/flask.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/jetbot.sh b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/jetbot.sh
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/jetbot.sh
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/jetbot.sh
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/jetbot_kill.sh b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/jetbot_kill.sh
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/jetbot_kill.sh
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/jetbot_kill.sh
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/requirements.txt b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/requirements.txt
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/requirements.txt
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/requirements.txt
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/results/.keep b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/results/.keep
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/results/.keep
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/results/.keep
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_sit.wbo b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_sit.wbo
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_sit.wbo
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_sit.wbo
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_standing.wbo b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_standing.wbo
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_standing.wbo
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/protos/human_010_standing.wbo
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/pose_demo.wbt b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/pose_demo.wbt
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/pose_demo.wbt
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/pose_demo.wbt
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/brown_eye.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/brown_eye.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/brown_eye.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/brown_eye.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow005.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow005.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow005.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow005.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow009.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow009.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow009.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyebrow009.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes01.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes01.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes01.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes01.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes04.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes04.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes04.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/eyelashes04.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_diffuse.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_diffuse.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_diffuse.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_diffuse.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_normal.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_normal.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_normal.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/female_elegantsuit01_normal.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthnormals.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthnormals.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthnormals.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthnormals.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthtex1.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthtex1.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthtex1.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/keylthtex1.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_diffuse.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_diffuse.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_diffuse.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_diffuse.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_normal.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_normal.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_normal.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/male_casualsuit02_normal.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/middleage_lightskinned_male_diffuse2.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/middleage_lightskinned_male_diffuse2.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/middleage_lightskinned_male_diffuse2.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/middleage_lightskinned_male_diffuse2.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/short01_diffuse.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/short01_diffuse.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/short01_diffuse.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/simulation_pose/worlds/textures/short01_diffuse.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/static/eu.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/static/eu.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/static/eu.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/static/eu.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/static/opendr.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/static/opendr.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/static/opendr.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/static/opendr.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/static/opendr_logo.png b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/static/opendr_logo.png
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/static/opendr_logo.png
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/static/opendr_logo.png
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/templates/index.html b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/templates/index.html
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/templates/index.html
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/templates/index.html
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/utils/__init__.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/__init__.py
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/utils/__init__.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/__init__.py
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/utils/active.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/active.py
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/utils/active.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/active.py
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/utils/pid.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/pid.py
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/utils/pid.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/pid.py
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/utils/pose_controller.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/pose_controller.py
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/utils/pose_controller.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/pose_controller.py
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/utils/pose_utils.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/pose_utils.py
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/utils/pose_utils.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/pose_utils.py
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/utils/robot_interface.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/robot_interface.py
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/utils/robot_interface.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/robot_interface.py
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/utils/visualization.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/visualization.py
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/utils/visualization.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/visualization.py
diff --git a/projects/python/perception/lightweight_open_pose/jetbot/utils/webots.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/webots.py
similarity index 100%
rename from projects/python/perception/lightweight_open_pose/jetbot/utils/webots.py
rename to projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/webots.py
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index 05a0fba6bf..a3a15616bb 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -87,10 +87,6 @@ def __init__(self, device='cuda', backbone='mobilenet',
             self.mobilenetv2_width = mobilenetv2_width
         if self.backbone == "shufflenet":
             self.shufflenet_groups = shufflenet_groups
-        # if self.backbone == "mobilenet":
-        #     self.from_mobilenet = True # TODO from_mobilenet = True, bugs out the loading
-        # else:
-        #     self.from_mobilenet = False
 
         self.weights_only = weights_only  # If True, it won't load optimizer, scheduler, num_iter, current_epoch
 
@@ -176,9 +172,13 @@ def __pooling(self, img, kernel):  # Pooling on input image for dim reduction
         return pool_img
 
     def fit(self, dataset, val_dataset=None, logging_path='', silent=True, verbose=True):
+        """This method is not used in this implementation."""
+
         raise NotImplementedError
 
     def optimize(self, target_device):
+        """This method is not used in this implementation."""
+
         raise NotImplementedError
 
     def reset(self):
@@ -188,61 +188,7 @@ def reset(self):
     def save(self, path):
         """This method is not used in this implementation."""
         return NotImplementedError
-    #     """
-    #     This method is used to save a trained model.
-    #     Provided with the path, absolute or relative, including a *folder* name, it creates a directory with the name
-    #     of the *folder* provided and saves the model inside with a proper format and a .json file with metadata.
-    #
-    #     If self.optimize was ran previously, it saves the optimized ONNX model in a similar fashion, by copying it
-    #     from the self.temp_path it was saved previously during conversion.
-    #
-    #     :param path: for the model to be saved, including the folder name
-    #     :type path: str
-    #     :param verbose: whether to print success message or not, defaults to 'False'
-    #     :type verbose: bool, optional
-    #     """
-    #     if self.model is None and self.ort_session is None:
-    #         raise UserWarning("No model is loaded, cannot save.")
-    #
-    #     folder_name, _, tail = self.__extract_trailing(path)  # Extract trailing folder name from path
-    #     # Also extract folder name without any extension if extension is erroneously provided
-    #     folder_name_no_ext = folder_name.split(sep='.')[0]
-    #
-    #     # Extract path without folder name, by removing folder name from original path
-    #     path_no_folder_name = path.replace(folder_name, '')
-    #     # If tail is '', then path was a/b/c/, which leaves a trailing double '/'
-    #     if tail == '':
-    #         path_no_folder_name = path_no_folder_name[0:-1]  # Remove one '/'
-    #
-    #     # Create model directory
-    #     full_path_to_model_folder = path_no_folder_name + folder_name_no_ext
-    #     os.makedirs(full_path_to_model_folder, exist_ok=True)
-    #
-    #     model_metadata = {"model_paths": [], "framework": "pytorch", "format": "", "has_data": False,
-    #                       "inference_params": {}, "optimized": None, "optimizer_info": {}, "backbone": self.backbone}
-    #
-    #     if self.ort_session is None:
-    #         model_metadata["model_paths"] = [folder_name_no_ext + ".pth"]
-    #         model_metadata["optimized"] = False
-    #         model_metadata["format"] = "pth"
-    #
-    #         custom_dict = {'state_dict': self.model.state_dict()}
-    #         torch.save(custom_dict, os.path.join(full_path_to_model_folder, model_metadata["model_paths"][0]))
-    #         if verbose:
-    #             print("Saved Pytorch model.")
-    #     else:
-    #         model_metadata["model_paths"] = [os.path.join(folder_name_no_ext + ".onnx")]
-    #         model_metadata["optimized"] = True
-    #         model_metadata["format"] = "onnx"
-    #         # Copy already optimized model from temp path
-    #         shutil.copy2(os.path.join(self.temp_path, "onnx_model_temp.onnx"),
-    #                      os.path.join(full_path_to_model_folder, model_metadata["model_paths"][0]))
-    #         model_metadata["optimized"] = True
-    #         if verbose:
-    #             print("Saved ONNX model.")
-    #
-    #     with open(os.path.join(full_path_to_model_folder, folder_name_no_ext + ".json"), 'w') as outfile:
-    #         json.dump(model_metadata, outfile)
+
 
     def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
              subset_size=250,
@@ -274,10 +220,6 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
             if not silent and verbose:
                 print("Loading checkpoint:", full_path)
 
-            # Loads weights in self.model from checkpoint
-            # if self.from_mobilenet:  # TODO see todo on ctor
-            #     load_from_mobilenet(self.model, checkpoint)
-            # else:
             load_state(self.model, checkpoint)
         elif self.model is None:
             raise AttributeError("self.model is None. Please load a model or set checkpoint_load_iter.")
@@ -456,7 +398,7 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
             return {"average_precision": [0.0 for _ in range(5)], "average_recall": [0.0 for _ in range(5)]}
 
     def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
-              multiscale=False, visualize=False):
+              multiscale=False):
         current_poses = []
 
         offset = 0
@@ -619,9 +561,6 @@ def __load_from_pth(self, path):
         """
         self.init_model()
         checkpoint = torch.load(path, map_location=torch.device(self.device))
-        # if self.from_mobilenet:  # TODO see todo on ctor
-        #     load_from_mobilenet(self.model, checkpoint)
-        # else:
         load_state(self.model, checkpoint)
         if "cuda" in self.device:
             self.model.to(self.device)

From d3340f5ef23e845a9b6a3f2b3dcee7aadad8bb1e Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Tue, 13 Dec 2022 12:19:42 +0200
Subject: [PATCH 14/27] edit some paths

---
 .../demos/benchmarking_demo.py                                | 4 ++--
 .../high_resolution_pose_estimation/demos/eval_demo.py        | 4 ++--
 .../high_resolution_pose_estimation/demos/inference_demo.py   | 4 ++--
 .../lightweight_open_pose/demos/benchmarking_demo.py          | 4 ++--
 .../pose_estimation/lightweight_open_pose/demos/eval_demo.py  | 4 ++--
 .../lightweight_open_pose/demos/inference_demo.py             | 4 ++--
 6 files changed, 12 insertions(+), 12 deletions(-)

diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
index 88b894ad79..7fc66de1f0 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
@@ -53,11 +53,11 @@
                                                          mobilenet_use_stride=stride, half_precision=half_precision,
                                                          first_pass_height=base_height1,
                                                          second_pass_height=base_height2)
-    pose_estimator.download(path="", verbose=True)
+    pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
     # Download one sample image
-    pose_estimator.download(path="", mode="test_data")
+    pose_estimator.download(path=".", mode="test_data")
     image_path = join("temp", "dataset", "image", "000000000785_1080.jpg")
     img = cv2.imread(image_path)
 
diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
index 50938a5b15..5c1c9100ff 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
@@ -47,14 +47,14 @@
                                                          half_precision=half_precision,
                                                          first_pass_height=base_height1,
                                                          second_pass_height=base_height2)
-    pose_estimator.download(path="", verbose=True)
+    pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
     if onnx:
         pose_estimator.optimize()
 
     # Download a sample dataset
-    pose_estimator.download(path="", mode="test_data")
+    pose_estimator.download(path=".", mode="test_data")
 
     eval_dataset = ExternalDataset(path=join("temp", "dataset"), dataset_type="COCO")
 
diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
index d8c58f61fc..df6d62df6f 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
@@ -47,11 +47,11 @@
                                                          mobilenet_use_stride=stride, half_precision=half_precision,
                                                          first_pass_height=base_height1,
                                                          second_pass_height=base_height2)
-    pose_estimator.download(path="", verbose=True)
+    pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
     # Download one sample image
-    pose_estimator.download(path="", mode="test_data")
+    pose_estimator.download(path=".", mode="test_data")
 
     image_path = join("temp", "dataset", "image", "000000000785_1080.jpg")
 
diff --git a/projects/python/perception/pose_estimation/lightweight_open_pose/demos/benchmarking_demo.py b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/benchmarking_demo.py
index 24ebefe688..cc80487d70 100644
--- a/projects/python/perception/pose_estimation/lightweight_open_pose/demos/benchmarking_demo.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/benchmarking_demo.py
@@ -40,11 +40,11 @@
 
     pose_estimator = LightweightOpenPoseLearner(device=device, num_refinement_stages=stages,
                                                 mobilenet_use_stride=stride, half_precision=half_precision)
-    pose_estimator.download(path="", verbose=True)
+    pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
     # Download one sample image
-    pose_estimator.download(path="", mode="test_data")
+    pose_estimator.download(path=".", mode="test_data")
     image_path = join("temp", "dataset", "image", "000000000785.jpg")
     img = cv2.imread(image_path)
 
diff --git a/projects/python/perception/pose_estimation/lightweight_open_pose/demos/eval_demo.py b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/eval_demo.py
index 5055415dc1..3ecd6c6884 100644
--- a/projects/python/perception/pose_estimation/lightweight_open_pose/demos/eval_demo.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/eval_demo.py
@@ -39,14 +39,14 @@
     pose_estimator = LightweightOpenPoseLearner(device=device, num_refinement_stages=stages,
                                                 mobilenet_use_stride=stride,
                                                 half_precision=half_precision)
-    pose_estimator.download(path="", verbose=True)
+    pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
     if onnx:
         pose_estimator.optimize()
 
     # Download a sample dataset
-    pose_estimator.download(path="", mode="test_data")
+    pose_estimator.download(path=".", mode="test_data")
 
     eval_dataset = ExternalDataset(path=join("temp", "dataset"), dataset_type="COCO")
 
diff --git a/projects/python/perception/pose_estimation/lightweight_open_pose/demos/inference_demo.py b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/inference_demo.py
index 549493d87f..1b494919fa 100644
--- a/projects/python/perception/pose_estimation/lightweight_open_pose/demos/inference_demo.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/inference_demo.py
@@ -39,11 +39,11 @@
 
     pose_estimator = LightweightOpenPoseLearner(device=device, num_refinement_stages=stages,
                                                 mobilenet_use_stride=stride, half_precision=half_precision)
-    pose_estimator.download(path="", verbose=True)
+    pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
     # Download one sample image
-    pose_estimator.download(path="", mode="test_data")
+    pose_estimator.download(path=".", mode="test_data")
     image_path = join("temp", "dataset", "image", "000000000785.jpg")
     img = Image.open(image_path)
 

From d6ba595273facd1ba558c10f48a279160d90e071 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Tue, 13 Dec 2022 13:05:47 +0200
Subject: [PATCH 15/27] changes for test errors

---
 .../hr_pose_estimation/high_resolution_learner.py     |  1 -
 .../test_high_resolution_pose_estimation.py           | 11 -----------
 tests/test_license.py                                 |  2 +-
 3 files changed, 1 insertion(+), 13 deletions(-)

diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index a3a15616bb..2ddb18aa47 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -189,7 +189,6 @@ def save(self, path):
         """This method is not used in this implementation."""
         return NotImplementedError
 
-
     def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
              subset_size=250,
              images_folder_name="val2017", annotations_filename="person_keypoints_val2017.json"):
diff --git a/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py b/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py
index b8a1096b84..aa0a27005d 100644
--- a/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py
+++ b/tests/sources/tools/perception/pose_estimation/high_resolution_pose_estimation/test_high_resolution_pose_estimation.py
@@ -90,17 +90,6 @@ def test_infer(self):
         self.assertGreater(len(self.pose_estimator.infer(img)[0].data), 0,
                            msg="Returned pose must have non-zero number of keypoints.")
 
-    def test_save_load(self):
-        self.pose_estimator.model = None
-        self.pose_estimator.ort_session = None
-        self.pose_estimator.init_model()
-        self.pose_estimator.save(os.path.join(self.temp_dir, "test_model"))
-        self.pose_estimator.model = None
-        self.pose_estimator.load(os.path.join(self.temp_dir, "test_model"))
-        self.assertIsNotNone(self.pose_estimator.model, "model is None after loading pth model.")
-        # Cleanup
-        rmdir(os.path.join(self.temp_dir, "test_model"))
-
 
 if __name__ == "__main__":
     unittest.main()
diff --git a/tests/test_license.py b/tests/test_license.py
index 6452095449..d12d1bfa04 100755
--- a/tests/test_license.py
+++ b/tests/test_license.py
@@ -111,7 +111,7 @@ def setUp(self):
 
         skippedFilePaths = [
             'src/opendr/perception/activity_recognition/datasets/utils/decoder.py',
-            'projects/python/perception/lightweight_open_pose/jetbot/utils/pid.py',
+            'projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/utils/pid.py',
             'src/opendr/perception/compressive_learning/multilinear_compressive_learning/algorithm/trainers.py',
             'src/opendr/perception/object_detection_2d/retinaface/Makefile',
             'src/opendr/perception/multimodal_human_centric/audiovisual_emotion_learner/algorithm/efficientface_modulator.py',

From e9dabd1056b6bed0e2700b151410148f5b6eb5b1 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Mon, 19 Dec 2022 16:01:50 +0200
Subject: [PATCH 16/27] apply suggestions from review

---
 docs/reference/high_resolution_pose_estimation.md    | 12 ++++++++++++
 .../scripts/hr_pose_estimation_node.py               |  2 +-
 .../lightweight_open_pose/demos/webcam_demo.py       |  2 +-
 .../lightweight_open_pose/jetbot/fall_controller.py  |  2 +-
 .../hr_pose_estimation/high_resolution_learner.py    |  3 +--
 5 files changed, 16 insertions(+), 5 deletions(-)

diff --git a/docs/reference/high_resolution_pose_estimation.md b/docs/reference/high_resolution_pose_estimation.md
index 53aa8761b5..4d8193fcea 100644
--- a/docs/reference/high_resolution_pose_estimation.md
+++ b/docs/reference/high_resolution_pose_estimation.md
@@ -192,6 +192,18 @@ Parameters:
 - **url**: *str, default=OpenDR FTP URL*\
   URL of the FTP server.
 
+#### `HighResolutionPoseEstimation.load`
+```python
+HighResolutionPoseEstimation.load(self, path, verbose)
+```
+This method is used to load a pretrained model that has trained with Lightweight OpenPose. The model is loaded from  inside the directory of the path provided, using the metadata .json file included.
+
+Parameters: 
+- **path**: *str*\
+  Path of the model to be loaded.
+- **verbose**: *bool, default=False*\
+  If set to True, prints a message on success.
+
 
 #### Examples
 
diff --git a/projects/opendr_ws/src/opendr_perception/scripts/hr_pose_estimation_node.py b/projects/opendr_ws/src/opendr_perception/scripts/hr_pose_estimation_node.py
index a820c91b1c..0a471b224e 100755
--- a/projects/opendr_ws/src/opendr_perception/scripts/hr_pose_estimation_node.py
+++ b/projects/opendr_ws/src/opendr_perception/scripts/hr_pose_estimation_node.py
@@ -79,7 +79,7 @@ def listen(self):
         """
         Start the node and begin processing input data.
         """
-        rospy.init_node('opendr_pose_estimation_node', anonymous=True)
+        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()
diff --git a/projects/python/perception/pose_estimation/lightweight_open_pose/demos/webcam_demo.py b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/webcam_demo.py
index 7eb7993004..149783d1e1 100644
--- a/projects/python/perception/pose_estimation/lightweight_open_pose/demos/webcam_demo.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/demos/webcam_demo.py
@@ -63,7 +63,7 @@ def __next__(self):
 
     pose_estimator = LightweightOpenPoseLearner(device=device, num_refinement_stages=stages,
                                                 mobilenet_use_stride=stride, half_precision=half_precision)
-    pose_estimator.download(path="", verbose=True)
+    pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
     if onnx:
diff --git a/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/fall_controller.py b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/fall_controller.py
index baaf0db90b..cc9ecb32a9 100644
--- a/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/fall_controller.py
+++ b/projects/python/perception/pose_estimation/lightweight_open_pose/jetbot/fall_controller.py
@@ -82,7 +82,7 @@
                                                     mobilenet_use_stride=False, half_precision=False)
         infer_delay = 0.43  # delay calculated based on FPS on jetbot
 
-    pose_estimator.download(path="", verbose=True)
+    pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("./openpose_default")
 
     def fall_handler_fn_file(imgs):
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index 2ddb18aa47..45fcb752fc 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -164,10 +164,9 @@ def __second_pass(self, net, img, net_input_height_size, max_width, stride, upsa
         return heatmaps, pafs, scale, pad
 
     def __pooling(self, img, kernel):  # Pooling on input image for dim reduction
-        pool = torch.nn.AvgPool2d(kernel)
         pool_img = torchvision.transforms.ToTensor()(img)
         pool_img = pool_img.unsqueeze(0)
-        pool_img = pool(pool_img)
+        pool_img = torch.nn.functional.avg_pool2d(pool_img, kernel)
         pool_img = pool_img.squeeze(0).permute(1, 2, 0).cpu().float().numpy()
         return pool_img
 

From 2d42b0b943f58c5ac19d2e7f6a8e129f442d7ace Mon Sep 17 00:00:00 2001
From: mthodoris <45919203+mthodoris@users.noreply.github.com>
Date: Tue, 20 Dec 2022 11:36:31 +0200
Subject: [PATCH 17/27] Apply suggestions from code review

type casting issue on height variables
str() to int()

Co-authored-by: Nikolaos Passalis <passalis@users.noreply.github.com>
---
 .../demos/benchmarking_demo.py                                | 4 ++--
 .../high_resolution_pose_estimation/demos/eval_demo.py        | 4 ++--
 .../high_resolution_pose_estimation/demos/inference_demo.py   | 4 ++--
 3 files changed, 6 insertions(+), 6 deletions(-)

diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
index 7fc66de1f0..e819b99566 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
@@ -51,8 +51,8 @@
 
     pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
                                                          mobilenet_use_stride=stride, half_precision=half_precision,
-                                                         first_pass_height=base_height1,
-                                                         second_pass_height=base_height2)
+                                                         first_pass_height=int(base_height1),
+                                                         second_pass_height=int(base_height2))
     pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
index 5c1c9100ff..bdc088fb03 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
@@ -45,8 +45,8 @@
     pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
                                                          mobilenet_use_stride=stride,
                                                          half_precision=half_precision,
-                                                         first_pass_height=base_height1,
-                                                         second_pass_height=base_height2)
+                                                         first_pass_height=int(base_height1),
+                                                         second_pass_height=int(base_height2))
     pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
index df6d62df6f..76b8c5e881 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
@@ -45,8 +45,8 @@
 
     pose_estimator = HighResolutionPoseEstimationLearner(device=device, num_refinement_stages=stages,
                                                          mobilenet_use_stride=stride, half_precision=half_precision,
-                                                         first_pass_height=base_height1,
-                                                         second_pass_height=base_height2)
+                                                         first_pass_height=int(base_height1),
+                                                         second_pass_height=int(base_height2))
     pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 

From 15608ee5154af7506dd8df25fd4934863ae60bf9 Mon Sep 17 00:00:00 2001
From: ad-daniel <daniel.dias@epfl.ch>
Date: Tue, 20 Dec 2022 12:28:15 +0100
Subject: [PATCH 18/27] Missing stuff

---
 CHANGELOG.md                                                 | 5 ++---
 ...pose_estimation.md => high-resolution-pose-estimation.md} | 0
 docs/reference/index.md                                      | 2 ++
 3 files changed, 4 insertions(+), 3 deletions(-)
 rename docs/reference/{high_resolution_pose_estimation.md => high-resolution-pose-estimation.md} (100%)

diff --git a/CHANGELOG.md b/CHANGELOG.md
index b6a6ab2f37..6625a92fa1 100644
--- a/CHANGELOG.md
+++ b/CHANGELOG.md
@@ -7,12 +7,11 @@ Released on December, XX, 2022.
     - Added YOLOv5 as an inference-only tool ([#360](https://github.com/opendr-eu/opendr/pull/360)).
     - Added Continual Transformer Encoders ([#317](https://github.com/opendr-eu/opendr/pull/317)).
     - 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)).
     - Fixed undefined `image_id` and `segmentation` for COCO `BoundingBoxList` ([#365](https://github.com/opendr-eu/opendr/pull/365)).
-
-  - Bug Fixes:
     - Fixed Continual X3D ONNX support ([#372](https://github.com/opendr-eu/opendr/pull/372)).
 
 ## Version 1.1.1
diff --git a/docs/reference/high_resolution_pose_estimation.md b/docs/reference/high-resolution-pose-estimation.md
similarity index 100%
rename from docs/reference/high_resolution_pose_estimation.md
rename to docs/reference/high-resolution-pose-estimation.md
diff --git a/docs/reference/index.md b/docs/reference/index.md
index 856233e3e3..ff428cd642 100644
--- a/docs/reference/index.md
+++ b/docs/reference/index.md
@@ -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)
             - [x3d Module](activity-recognition.md#class-x3dlearner)
@@ -111,6 +112,7 @@ Neither the copyright holder nor any applicable licensor will be liable for any
             - [heart anomaly detection Demo](/projects/python/perception/heart_anomaly_detection)
         - pose estimation:
             - [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)

From 9e4bea8f54cd540bae60122b676e0b1e8e9a2156 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Tue, 20 Dec 2022 15:34:00 +0200
Subject: [PATCH 19/27] add a CHANGELOG entry, reference the demo and
 documentation in index.md

---
 CHANGELOG.md            | 5 ++---
 docs/reference/index.md | 2 ++
 2 files changed, 4 insertions(+), 3 deletions(-)

diff --git a/CHANGELOG.md b/CHANGELOG.md
index b6a6ab2f37..6625a92fa1 100644
--- a/CHANGELOG.md
+++ b/CHANGELOG.md
@@ -7,12 +7,11 @@ Released on December, XX, 2022.
     - Added YOLOv5 as an inference-only tool ([#360](https://github.com/opendr-eu/opendr/pull/360)).
     - Added Continual Transformer Encoders ([#317](https://github.com/opendr-eu/opendr/pull/317)).
     - 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)).
     - Fixed undefined `image_id` and `segmentation` for COCO `BoundingBoxList` ([#365](https://github.com/opendr-eu/opendr/pull/365)).
-
-  - Bug Fixes:
     - Fixed Continual X3D ONNX support ([#372](https://github.com/opendr-eu/opendr/pull/372)).
 
 ## Version 1.1.1
diff --git a/docs/reference/index.md b/docs/reference/index.md
index 856233e3e3..ff428cd642 100644
--- a/docs/reference/index.md
+++ b/docs/reference/index.md
@@ -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)
             - [x3d Module](activity-recognition.md#class-x3dlearner)
@@ -111,6 +112,7 @@ Neither the copyright holder nor any applicable licensor will be liable for any
             - [heart anomaly detection Demo](/projects/python/perception/heart_anomaly_detection)
         - pose estimation:
             - [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)

From 0dd322a9972d3e61c7bca77f0093872f9724530c Mon Sep 17 00:00:00 2001
From: Nikolaos <passalis@csd.auth.gr>
Date: Wed, 21 Dec 2022 10:47:16 +0200
Subject: [PATCH 20/27] Simplified HR pose estimation

---
 .../high_resolution_learner.py                | 323 ++----------------
 1 file changed, 23 insertions(+), 300 deletions(-)

diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index 45fcb752fc..6567d0f142 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -33,6 +33,8 @@
 from opendr.engine.constants import OPENDR_SERVER_URL
 
 # OpenDR lightweight_open_pose imports
+from opendr.perception.pose_estimation.lightweight_open_pose.lightweight_open_pose_learner import \
+    LightweightOpenPoseLearner
 from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.models.with_mobilenet import \
     PoseEstimationWithMobileNet
 from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.models.with_mobilenet_v2 import \
@@ -49,7 +51,7 @@
 from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.scripts import make_val_subset
 
 
-class HighResolutionPoseEstimationLearner(Learner):
+class HighResolutionPoseEstimationLearner(LightweightOpenPoseLearner):
 
     def __init__(self, device='cuda', backbone='mobilenet',
                  temp_path='temp', mobilenet_use_stride=True, mobilenetv2_width=1.0, shufflenet_groups=3,
@@ -60,56 +62,20 @@ def __init__(self, device='cuda', backbone='mobilenet',
                  img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256), pad_value=(0, 0, 0),
                  half_precision=False):
 
-        super(HighResolutionPoseEstimationLearner, self).__init__(temp_path=temp_path, device=device, backbone=backbone)
+        super(HighResolutionPoseEstimationLearner, self).__init__(device=device, backbone=backbone,
+                 temp_path=temp_path, mobilenet_use_stride=mobilenet_use_stride, 
+                 mobilenetv2_width=mobilenetv2_width, shufflenet_groups=shufflenet_groups,
+                 num_refinement_stages=num_refinement_stages, batches_per_iter=batches_per_iter, 
+                 base_height=base_height, experiment_name=experiment_name, num_workers=num_workers,
+                 weights_only=weights_only, output_name=output_name, multiscale=multiscale, scales=scales,
+                 visualize=visualize, img_mean=img_mean, img_scale=img_scale, pad_value=pad_value,
+                 half_precision=half_precision)
 
         self.first_pass_height = first_pass_height
         self.second_pass_height = second_pass_height
-        self.img_resol = img_resolution  # default value for sample image in OpenDr server
-
-        self.parent_dir = temp_path  # Parent dir should be filled by the user according to README
-
-        self.num_refinement_stages = num_refinement_stages  # How many extra refinement stages to add
-        self.batches_per_iter = batches_per_iter
-
-        self.experiment_name = experiment_name
-        self.num_workers = num_workers
-        self.backbone = backbone.lower()
-        self.half = half_precision
-
-        supportedBackbones = ["mobilenet", "mobilenetv2", "shufflenet"]
-        if self.backbone not in supportedBackbones:
-            raise ValueError(self.backbone + " not a valid backbone. Supported backbones:" + str(supportedBackbones))
-        if self.backbone == "mobilenet":
-            self.use_stride = mobilenet_use_stride
-        else:
-            self.use_stride = None
-        if self.backbone == "mobilenetv2":
-            self.mobilenetv2_width = mobilenetv2_width
-        if self.backbone == "shufflenet":
-            self.shufflenet_groups = shufflenet_groups
-
-        self.weights_only = weights_only  # If True, it won't load optimizer, scheduler, num_iter, current_epoch
-
-        self.output_name = os.path.join(self.parent_dir, output_name)  # Path to json file containing detections
-        self.visualize = visualize
-        self.base_height = base_height
-        if scales is None:
-            scales = [1]
-        self.multiscale = multiscale  # If set to true, overwrites self.scales to [0.5, 1.0, 1.5, 2.0]
-        self.scales = scales
-        if self.use_stride:
-            self.stride = 8 * 2
-        else:
-            self.stride = 8
+        self.img_resol = img_resolution  # default value for sample image in OpenDR server
         self.upsample_ratio = 4
 
-        self.img_mean = img_mean
-        self.img_scale = img_scale
-        self.pad_value = pad_value
-        self.previous_poses = []
-
-        self.ort_session = None  # ONNX runtime inference session
-        self.model_train_state = True
 
     def __first_pass(self, net, img):
 
@@ -192,7 +158,8 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
              subset_size=250,
              images_folder_name="val2017", annotations_filename="person_keypoints_val2017.json"):
 
-        data = self.__prepare_val_dataset(dataset, use_subset=use_subset,
+        data = super(HighResolutionPoseEstimationLearner, self)._LightweightOpenPoseLearner__prepare_val_dataset(
+                                          dataset, use_subset=use_subset,
                                           subset_name="val_subset.json",
                                           subset_size=subset_size,
                                           images_folder_default_name=images_folder_name,
@@ -512,97 +479,10 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
         return current_poses
 
-    def init_model(self):
-        if self.model is None:
-            # No model loaded, initializing new
-            if self.backbone == "mobilenet":
-                self.model = PoseEstimationWithMobileNet(self.num_refinement_stages, use_stride=self.use_stride)
-            elif self.backbone == "mobilenetv2":
-                self.model = PoseEstimationWithMobileNetV2(self.num_refinement_stages,
-                                                           width_mult=self.mobilenetv2_width)
-            elif self.backbone == "shufflenet":
-                self.model = PoseEstimationWithShuffleNet(self.num_refinement_stages,
-                                                          groups=self.shufflenet_groups)
-        else:
-            raise UserWarning("Tried to initialize model while model is already initialized.")
-        self.model.to(self.device)
-
-    def load(self, path, verbose=False):
-        """
-        Loads the model from inside the path provided, based on the metadata .json file included.
-        :param path: path of the directory the model was saved
-        :type path: str
-        :param verbose: whether to print success message or not, defaults to 'False'
-        :type verbose: bool, optional
-        """
-        model_name, _, _ = self.__extract_trailing(path)  # Trailing folder name from the path provided
-
-        with open(os.path.join(path, model_name + ".json")) as metadata_file:
-            metadata = json.load(metadata_file)
-
-        self.backbone = metadata["backbone"]
-        if not metadata["optimized"]:
-            self.__load_from_pth(os.path.join(path, metadata['model_paths'][0]))
-            if verbose:
-                print("Loaded Pytorch model.")
-        else:
-            self.__load_from_onnx(os.path.join(path, metadata['model_paths'][0]))
-            if verbose:
-                print("Loaded ONNX model.")
-
-    def __load_from_pth(self, path):
-        """
-        This method loads a regular Pytorch model from the path provided into self.model.
-
-        :param path: path to .pth model
-        :type path: str
-        """
-        self.init_model()
-        checkpoint = torch.load(path, map_location=torch.device(self.device))
-        load_state(self.model, checkpoint)
-        if "cuda" in self.device:
-            self.model.to(self.device)
-            if self.half:
-                self.model.half()
-        self.model.train(False)
-
-    def __load_from_onnx(self, path):
-        """
-        This method loads an ONNX model from the path provided into an onnxruntime inference session.
-
-        :param path: path to ONNX model
-        :type path: str
-        """
-        self.ort_session = ort.InferenceSession(path)
-
-        # The comments below are the alternative way to use the onnx model, it might be useful in the future
-        # depending on how ONNX saving/loading will be implemented across the toolkit.
-        # # Load the ONNX model
-        # self.model = onnx.load(path)
-        #
-        # # Check that the IR is well formed
-        # onnx.checker.check_model(self.model)
-        #
-        # # Print a human-readable representation of the graph
-        # onnx.helper.printable_graph(self.model.graph)
-
-    @staticmethod
-    def __extract_trailing(path):
-        """
-        Extracts the trailing folder name or filename from a path provided in an OS-generic way, also handling
-        cases where the last trailing character is a separator. Returns the folder name and the split head and tail.
-
-        :param path: the path to extract the trailing filename or folder name from
-        :type path: str
-        :return: the folder name, the head and tail of the path
-        :rtype: tuple of three strings
-        """
-        head, tail = ntpath.split(path)
-        folder_name = tail or ntpath.basename(head)  # handle both a/b/c and a/b/c/
-        return folder_name, head, tail
 
     def download(self, path=None, mode="pretrained", verbose=False,
-                 url=OPENDR_SERVER_URL + "perception/pose_estimation/lightweight_open_pose/"):
+                 url=OPENDR_SERVER_URL + "perception/pose_estimation/lightweight_open_pose/",
+                 image_resolution=1080):
         """
         Download utility for various Lightweight Open Pose components. Downloads files depending on mode and
         saves them in the path provided. It supports downloading:
@@ -617,6 +497,8 @@ def download(self, path=None, mode="pretrained", verbose=False,
         :type verbose: bool, optional
         :param url: URL of the FTP server, defaults to OpenDR FTP URL
         :type url: str, optional
+        :param image_resolution: Resolution of the test images to download
+        :type image_resolution: int, optional
         """
         valid_modes = ["weights", "pretrained", "test_data"]
         if mode not in valid_modes:
@@ -628,70 +510,8 @@ def download(self, path=None, mode="pretrained", verbose=False,
         if not os.path.exists(path):
             os.makedirs(path)
 
-        if mode == "pretrained":
-            # Create model's folder
-            path = os.path.join(path, "openpose_default")
-            if not os.path.exists(path):
-                os.makedirs(path)
-
-            if verbose:
-                print("Downloading pretrained model...")
-
-            # Download the model's files
-            if self.backbone == "mobilenet":
-                if not os.path.exists(os.path.join(path, "openpose_default.json")):
-                    file_url = os.path.join(url, "openpose_default/openpose_default.json")
-                    urlretrieve(file_url, os.path.join(path, "openpose_default.json"))
-                    if verbose:
-                        print("Downloaded metadata json.")
-                else:
-                    if verbose:
-                        print("Metadata json file already exists.")
-                if not os.path.exists(os.path.join(path, "openpose_default.pth")):
-                    file_url = os.path.join(url, "openpose_default/openpose_default.pth")
-                    urlretrieve(file_url, os.path.join(path, "openpose_default.pth"))
-                else:
-                    if verbose:
-                        print("Trained model .pth file already exists.")
-            elif self.backbone == "mobilenetv2":
-                raise UserWarning("mobilenetv2 does not support pretrained model.")
-            elif self.backbone == "shufflenet":
-                raise UserWarning("shufflenet does not support pretrained model.")
-            if verbose:
-                print("Pretrained model download complete.")
-
-        elif mode == "weights":
-            if verbose:
-                print("Downloading weights file...")
-            if self.backbone == "mobilenet":
-                if not os.path.exists(os.path.join(self.temp_path, "mobilenet_sgd_68.848.pth.tar")):
-                    file_url = os.path.join(url, "mobilenet_sgd_68.848.pth.tar")
-                    urlretrieve(file_url, os.path.join(self.temp_path, "mobilenet_sgd_68.848.pth.tar"))
-                    if verbose:
-                        print("Downloaded mobilenet weights.")
-                else:
-                    if verbose:
-                        print("Weights file already exists.")
-            elif self.backbone == "mobilenetv2":
-                if not os.path.exists(os.path.join(self.temp_path, "mobilenetv2_1.0-f2a8633.pth.tar")):
-                    file_url = os.path.join(url, "mobilenetv2_1.0-f2a8633.pth.tar")
-                    urlretrieve(file_url, os.path.join(self.temp_path, "mobilenetv2_1.0-f2a8633.pth.tar"))
-                    if verbose:
-                        print("Downloaded mobilenetv2 weights.")
-                else:
-                    if verbose:
-                        print("Weights file already exists.")
-            elif self.backbone == "shufflenet":
-                if not os.path.exists(os.path.join(self.temp_path, "shufflenet.pth.tar")):
-                    file_url = os.path.join(url, "shufflenet.pth.tar")
-                    urlretrieve(file_url, os.path.join(self.temp_path, "shufflenet.pth.tar"))
-                    if verbose:
-                        print("Downloaded shufflenet weights.")
-                else:
-                    if verbose:
-                        print("Weights file already exists.")
-            if verbose:
-                print("Weights file download complete.")
+        if mode in ("pretrained", "weights"):
+             super(HighResolutionPoseEstimationLearner, self).download(path=path, mode=mode, verbose=verbose, url=url)
 
         elif mode == "test_data":
             if verbose:
@@ -706,109 +526,12 @@ def download(self, path=None, mode="pretrained", verbose=False,
             file_url = os.path.join(url, "dataset", "annotation.json")
             urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "annotation.json"))
             # Download test image
-            if self.img_resol == 1080:
-                file_url = os.path.join(url, "dataset", "image", "000000000785_1080.jpg")
+            if image_resolution in(1080, 1440):
+                file_url = os.path.join(url, "dataset", "image", "000000000785_" + str(image_resolution) + ".jpg")
                 urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "image", "000000000785_1080.jpg"))
-            elif self.img_resol == 1440:
-                file_url = os.path.join(url, "dataset", "image", "000000000785_1440.jpg")
-                urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "image", "000000000785_1440.jpg"))
             else:
-                raise UserWarning("There are no data for this image resolution")
+                raise UserWarning("There are no data for this image resolution (only 1080 and 1440 are supported).")
 
             if verbose:
                 print("Test data download complete.")
 
-    @staticmethod
-    def __prepare_val_dataset(dataset, use_subset=False, subset_name="val_subset.json",
-                              subset_size=250,
-                              images_folder_default_name="val2017",
-                              annotations_filename="person_keypoints_val2017.json",
-                              verbose=True):
-        """
-        This internal method prepares the validation dataset depending on what type of dataset is provided.
-
-        If an ExternalDataset object type is provided, the method tried to prepare the dataset based on the original
-        implementation, supposing that the dataset is in the COCO format. The path provided is searched for the
-        images folder and the annotations file, converts the annotations file into the internal format used if needed
-        and finally the CocoValDataset object is returned.
-
-        If the dataset is of the DatasetIterator format, then it's a custom implementation of a dataset and all
-        required operations should be handled by the user, so the dataset object is just returned.
-
-        :param dataset: the dataset
-        :type dataset: ExternalDataset class object or DatasetIterator class object
-        :param use_subset: whether to return a subset of the validation dataset, defaults to 'False'
-        :type use_subset: bool, optional
-        :param subset_name: the .json file where the validation dataset subset is saved, defaults to "val_subset.json"
-        :type subset_name: str, optional
-        :param subset_size: the size of the subset, defaults to 250
-        :type subset_size: int
-        :param images_folder_default_name: the name of the folder that contains the image files, defaults to "val2017"
-        :type images_folder_default_name: str, optional
-        :param annotations_filename: the .json file that contains the original annotations, defaults
-            to "person_keypoints_val2017.json"
-        :type annotations_filename: str, optional
-        :param verbose: whether to print additional information, defaults to 'True'
-        :type verbose: bool, optional
-
-        :raises UserWarning: UserWarnings with appropriate messages are raised for wrong type of dataset, or wrong paths
-            and filenames
-
-        :return: returns CocoValDataset object or custom DatasetIterator implemented by user
-        :rtype: CocoValDataset class object or DatasetIterator instance
-        """
-        if isinstance(dataset, ExternalDataset):
-            if dataset.dataset_type.lower() != "coco":
-                raise UserWarning("dataset_type must be \"COCO\"")
-
-            # Get files and subdirectories of dataset.path directory
-            f = []
-            dirs = []
-            for (dirpath, dirnames, filenames) in os.walk(dataset.path):
-                f = filenames
-                dirs = dirnames
-                break
-
-            # Get images folder
-            if images_folder_default_name not in dirs:
-                raise UserWarning("Didn't find \"" + images_folder_default_name +
-                                  "\" folder in the dataset path provided.")
-            images_folder = os.path.join(dataset.path, images_folder_default_name)
-
-            # Get annotations file
-            if annotations_filename not in f:
-                raise UserWarning("Didn't find \"" + annotations_filename +
-                                  "\" file in the dataset path provided.")
-            val_labels_file = os.path.join(dataset.path, annotations_filename)
-
-            if use_subset:
-                val_sub_labels_file = os.path.join(dataset.path, subset_name)
-                if subset_name not in f:
-                    if verbose:
-                        print("Didn't find " + subset_name + " in dataset.path, creating new...")
-                    make_val_subset.make_val_subset(val_labels_file,
-                                                    output_path=val_sub_labels_file,
-                                                    num_images=subset_size)
-                    if verbose:
-                        print("Created new validation subset file.")
-                    data = CocoValDataset(val_sub_labels_file, images_folder)
-                else:
-                    if verbose:
-                        print("Val subset already exists.")
-                    data = CocoValDataset(val_sub_labels_file, images_folder)
-                    if len(data) != subset_size:
-                        if verbose:
-                            print("Val subset is wrong size, creating new.")
-                        # os.remove(val_sub_labels_file)
-                        make_val_subset.make_val_subset(val_labels_file,
-                                                        output_path=val_sub_labels_file,
-                                                        num_images=subset_size)
-                        if verbose:
-                            print("Created new validation subset file.")
-                        data = CocoValDataset(val_sub_labels_file, images_folder)
-            else:
-                data = CocoValDataset(val_labels_file, images_folder)
-            return data
-
-        elif isinstance(dataset, DatasetIterator):
-            return dataset

From 191c3f6db65550be7ddbe89c5c0611d262f945f5 Mon Sep 17 00:00:00 2001
From: Nikolaos <passalis@csd.auth.gr>
Date: Wed, 21 Dec 2022 11:08:14 +0200
Subject: [PATCH 21/27] pep8 fixes

---
 .../high_resolution_learner.py                | 67 +++++++------------
 1 file changed, 25 insertions(+), 42 deletions(-)

diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index 6567d0f142..9e4ea05c59 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -14,9 +14,7 @@
 
 # General imports
 import torchvision.transforms
-import onnxruntime as ort
 import os
-import ntpath
 import cv2
 import torch
 import json
@@ -26,8 +24,6 @@
 from urllib.request import urlretrieve
 
 # OpenDR engine imports
-from opendr.engine.learners import Learner
-from opendr.engine.datasets import ExternalDataset, DatasetIterator
 from opendr.engine.data import Image
 from opendr.engine.target import Pose
 from opendr.engine.constants import OPENDR_SERVER_URL
@@ -35,20 +31,12 @@
 # OpenDR lightweight_open_pose imports
 from opendr.perception.pose_estimation.lightweight_open_pose.lightweight_open_pose_learner import \
     LightweightOpenPoseLearner
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.models.with_mobilenet import \
-    PoseEstimationWithMobileNet
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.models.with_mobilenet_v2 import \
-    PoseEstimationWithMobileNetV2
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.models.with_shufflenet import \
-    PoseEstimationWithShuffleNet
 from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.load_state import \
     load_state
 from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.modules.keypoints import \
     extract_keypoints, group_keypoints
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.datasets.coco import CocoValDataset
 from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.val import \
     convert_to_coco_format, run_coco_eval, normalize, pad_width
-from opendr.perception.pose_estimation.lightweight_open_pose.algorithm.scripts import make_val_subset
 
 
 class HighResolutionPoseEstimationLearner(LightweightOpenPoseLearner):
@@ -62,20 +50,22 @@ def __init__(self, device='cuda', backbone='mobilenet',
                  img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256), pad_value=(0, 0, 0),
                  half_precision=False):
 
-        super(HighResolutionPoseEstimationLearner, self).__init__(device=device, backbone=backbone,
-                 temp_path=temp_path, mobilenet_use_stride=mobilenet_use_stride, 
-                 mobilenetv2_width=mobilenetv2_width, shufflenet_groups=shufflenet_groups,
-                 num_refinement_stages=num_refinement_stages, batches_per_iter=batches_per_iter, 
-                 base_height=base_height, experiment_name=experiment_name, num_workers=num_workers,
-                 weights_only=weights_only, output_name=output_name, multiscale=multiscale, scales=scales,
-                 visualize=visualize, img_mean=img_mean, img_scale=img_scale, pad_value=pad_value,
-                 half_precision=half_precision)
+        super(HighResolutionPoseEstimationLearner, self).__init__(device=device, backbone=backbone, temp_path=temp_path,
+                                                                  mobilenet_use_stride=mobilenet_use_stride,
+                                                                  mobilenetv2_width=mobilenetv2_width,
+                                                                  shufflenet_groups=shufflenet_groups,
+                                                                  num_refinement_stages=num_refinement_stages,
+                                                                  batches_per_iter=batches_per_iter,
+                                                                  base_height=base_height, experiment_name=experiment_name,
+                                                                  num_workers=num_workers, weights_only=weights_only,
+                                                                  output_name=output_name, multiscale=multiscale,
+                                                                  scales=scales, visualize=visualize, img_mean=img_mean,
+                                                                  img_scale=img_scale, pad_value=pad_value,
+                                                                  half_precision=half_precision)
 
         self.first_pass_height = first_pass_height
         self.second_pass_height = second_pass_height
         self.img_resol = img_resolution  # default value for sample image in OpenDR server
-        self.upsample_ratio = 4
-
 
     def __first_pass(self, net, img):
 
@@ -154,17 +144,16 @@ def save(self, path):
         """This method is not used in this implementation."""
         return NotImplementedError
 
-    def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
-             subset_size=250,
+    def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_size=250, upsample_ratio=4,
              images_folder_name="val2017", annotations_filename="person_keypoints_val2017.json"):
 
-        data = super(HighResolutionPoseEstimationLearner, self)._LightweightOpenPoseLearner__prepare_val_dataset(
-                                          dataset, use_subset=use_subset,
-                                          subset_name="val_subset.json",
-                                          subset_size=subset_size,
-                                          images_folder_default_name=images_folder_name,
-                                          annotations_filename=annotations_filename,
-                                          verbose=verbose and not silent)
+        data = super(HighResolutionPoseEstimationLearner,
+                     self)._LightweightOpenPoseLearner__prepare_val_dataset(dataset, use_subset=use_subset,
+                                                                            subset_name="val_subset.json",
+                                                                            subset_size=subset_size,
+                                                                            images_folder_default_name=images_folder_name,
+                                                                            annotations_filename=annotations_filename,
+                                                                            verbose=verbose and not silent)
         # Model initialization if needed
         if self.model is None and self.checkpoint_load_iter != 0:
             # No model loaded, initializing new
@@ -209,7 +198,7 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
 
         img_height = data[0]['img'].shape[0]
 
-        if img_height == 1080 or img_height == 1440:
+        if img_height in (1080, 1440):
             offset = 200
         elif img_height == 720:
             offset = 50
@@ -229,7 +218,6 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
                 pool_img = img
 
             perc = 0.3  # percentage around cropping
-
             threshold = 0.1  # threshold for heatmap
 
             # ------- Heatmap Generation -------
@@ -289,7 +277,7 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
                     HighResolutionPoseEstimationLearner.__second_pass(self,
                                                                       self.model, crop_img,
                                                                       self.second_pass_height, max_width,
-                                                                      self.stride, self.upsample_ratio)
+                                                                      self.stride, upsample_ratio)
                 total_keypoints_num = 0
                 all_keypoints_by_type = []
                 for kpt_idx in range(18):
@@ -299,10 +287,8 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True,
                 pose_entries, all_keypoints = group_keypoints(all_keypoints_by_type, avg_pafs)
 
                 for kpt_id in range(all_keypoints.shape[0]):
-                    all_keypoints[kpt_id, 0] = (all_keypoints[kpt_id, 0] * self.stride / self.upsample_ratio - pad[
-                        1]) / scale
-                    all_keypoints[kpt_id, 1] = (all_keypoints[kpt_id, 1] * self.stride / self.upsample_ratio - pad[
-                        0]) / scale
+                    all_keypoints[kpt_id, 0] = (all_keypoints[kpt_id, 0] * self.stride / upsample_ratio - pad[1]) / scale
+                    all_keypoints[kpt_id, 1] = (all_keypoints[kpt_id, 1] * self.stride / upsample_ratio - pad[0]) / scale
 
                 for i in range(all_keypoints.shape[0]):
                     for j in range(all_keypoints.shape[1]):
@@ -479,7 +465,6 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
         return current_poses
 
-
     def download(self, path=None, mode="pretrained", verbose=False,
                  url=OPENDR_SERVER_URL + "perception/pose_estimation/lightweight_open_pose/",
                  image_resolution=1080):
@@ -511,8 +496,7 @@ def download(self, path=None, mode="pretrained", verbose=False,
             os.makedirs(path)
 
         if mode in ("pretrained", "weights"):
-             super(HighResolutionPoseEstimationLearner, self).download(path=path, mode=mode, verbose=verbose, url=url)
-
+            super(HighResolutionPoseEstimationLearner, self).download(path=path, mode=mode, verbose=verbose, url=url)
         elif mode == "test_data":
             if verbose:
                 print("Downloading test data...")
@@ -534,4 +518,3 @@ def download(self, path=None, mode="pretrained", verbose=False,
 
             if verbose:
                 print("Test data download complete.")
-

From 4a6c7d2e7a89a1dacd5fa4c1bfec0c2b41a23782 Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Wed, 21 Dec 2022 13:27:38 +0200
Subject: [PATCH 22/27] apply review suggestions edited hardcoded values,
 removed unnecessary values from learner, added docstrings in functions edited
 the readme file after the changes

---
 .../high-resolution-pose-estimation.md        |   9 +-
 .../high_resolution_learner.py                | 126 +++++++++++++++---
 2 files changed, 114 insertions(+), 21 deletions(-)

diff --git a/docs/reference/high-resolution-pose-estimation.md b/docs/reference/high-resolution-pose-estimation.md
index 4d8193fcea..1ff45aa426 100644
--- a/docs/reference/high-resolution-pose-estimation.md
+++ b/docs/reference/high-resolution-pose-estimation.md
@@ -17,7 +17,7 @@ The [HighResolutionPoseEstimationLearner](/src/opendr/perception/pose_estimation
 
 #### `HighResolutionPoseEstimationLearner` constructor
 ```python
-HighResolutionPoseEstimationLearner(self, device, backbone, temp_path, mobilenet_use_stride, mobilenetv2_width, shufflenet_groups, num_refinement_stages, batches_per_iter, base_height, first_pass_height, second_pass_height, img_resol, experiment_name, num_workers, weights_only, output_name, multiscale, scales, visualize,  img_mean, img_scale, pad_value, half_precision)
+HighResolutionPoseEstimationLearner(self, device, backbone, temp_path, mobilenet_use_stride, mobilenetv2_width, shufflenet_groups, num_refinement_stages, batches_per_iter, base_height, first_pass_height, second_pass_height, percentage_arround_crop, heatmap_threshold, experiment_name, num_workers, weights_only, output_name, multiscale, scales, visualize,  img_mean, img_scale, pad_value, half_precision)
 ```
 
 Constructor parameters:
@@ -45,6 +45,10 @@ Constructor parameters:
   Specifies the height that the input image will be resized during the heatmap generation procedure.
 - **second_pass_height**: *int, default=540*\
   Specifies the height of the image on the second inference for pose estimation procedure.
+- **percentage_arround_crop**: *float, default=0.3*\
+  Specifies the percentage of an extra pad arround the cropped image
+- **heatmap_threshold**: *float, default=0.1*\
+  Specifies a threshlod value that the heatmap elements should have
 - **experiment_name**: *str, default='default'*\
   String name to attach to checkpoints.
 - **num_workers**: *int, default=8*\
@@ -217,8 +221,7 @@ Parameters:
   pose_estimator = HighResolutionPoseEstimationLearner(device='cuda', num_refinement_stages=2,
                                                        mobilenet_use_stride=False, half_precision=False,
                                                        first_pass_height=360,
-                                                       second_pass_height=540,
-                                                       img_resolution=1080)
+                                                       second_pass_height=540)
   pose_estimator.download()  # Download the default pretrained mobilenet model in the temp_path
 
   pose_estimator.load("./parent_dir/openpose_default")
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index 9e4ea05c59..49ea5e3b2b 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -44,7 +44,7 @@ class HighResolutionPoseEstimationLearner(LightweightOpenPoseLearner):
     def __init__(self, device='cuda', backbone='mobilenet',
                  temp_path='temp', mobilenet_use_stride=True, mobilenetv2_width=1.0, shufflenet_groups=3,
                  num_refinement_stages=2, batches_per_iter=1, base_height=256,
-                 first_pass_height=360, second_pass_height=540, img_resolution=1080,
+                 first_pass_height=360, second_pass_height=540, percentage_arround_crop=0.3, heatmap_threshold=0.1,
                  experiment_name='default', num_workers=8, weights_only=True, output_name='detections.json',
                  multiscale=False, scales=None, visualize=False,
                  img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256), pad_value=(0, 0, 0),
@@ -56,7 +56,8 @@ def __init__(self, device='cuda', backbone='mobilenet',
                                                                   shufflenet_groups=shufflenet_groups,
                                                                   num_refinement_stages=num_refinement_stages,
                                                                   batches_per_iter=batches_per_iter,
-                                                                  base_height=base_height, experiment_name=experiment_name,
+                                                                  base_height=base_height,
+                                                                  experiment_name=experiment_name,
                                                                   num_workers=num_workers, weights_only=weights_only,
                                                                   output_name=output_name, multiscale=multiscale,
                                                                   scales=scales, visualize=visualize, img_mean=img_mean,
@@ -65,9 +66,23 @@ def __init__(self, device='cuda', backbone='mobilenet',
 
         self.first_pass_height = first_pass_height
         self.second_pass_height = second_pass_height
-        self.img_resol = img_resolution  # default value for sample image in OpenDR server
+        self.perc = percentage_arround_crop
+        self.threshold = heatmap_threshold
 
     def __first_pass(self, net, img):
+        """
+        This method is generating a rough heatmap of the input image in order to specify the approximate location
+        of humans in the picture.
+
+        :param net: the pose estimation model that has been loaded
+        :type net: opendr.perception.pose_estimation.lightweight_open_pose.\
+            algorithm.models.with_mobilenet.PoseEstimationWithMobileNet class object
+        :param img: input image for heatmap generation
+        :type img: numpy.ndarray
+
+        :return: returns the Part Affinity Fields (PAFs) of the humans inside the image
+        :rtype: numpy.ndarray
+        """
 
         if 'cuda' in self.device:
             tensor_img = torch.from_numpy(img).permute(2, 0, 1).unsqueeze(0).float().cuda()
@@ -86,6 +101,31 @@ def __first_pass(self, net, img):
     def __second_pass(self, net, img, net_input_height_size, max_width, stride, upsample_ratio,
                       pad_value=(0, 0, 0),
                       img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256)):
+        """
+        This method detects the keypoints and estimates the pose of humans using the cropped image from the
+        previous step (__first_pass_).
+
+        param net: the pose estimation model that has been loaded
+        :type net: opendr.perception.pose_estimation.lightweight_open_pose.\
+            algorithm.models.with_mobilenet.PoseEstimationWithMobileNet class object
+        :param img: input image for heatmap generation
+        :type img: numpy.ndarray
+        :param net_input_height_size: the height that the input image will be resized  for inference
+        :type net_input_height_size: int
+        :param max_width: this parameter is the maximum width that the resized image should have. It is introduced to
+            avoid cropping images with abnormal ratios e.g (30, 800)
+        :type max_width: int
+        :param upsample_ratio: Defines the amount of upsampling to be performed on the heatmaps and PAFs when resizing,
+            defaults to 4
+        :type upsample_ratio: int, optional
+
+         :returns: the heatmap of human figures, the part affinity filed (pafs), the scale of the resized image compred
+            to the initial and the pad arround the image
+         :rtype: heatmap, pafs -> numpy.ndarray
+                 scale -> float
+                 pad = -> list
+        """
+
         height, width, _ = img.shape
         scale = net_input_height_size / height
         img_ratio = width / height
@@ -119,7 +159,14 @@ def __second_pass(self, net, img, net_input_height_size, max_width, stride, upsa
 
         return heatmaps, pafs, scale, pad
 
-    def __pooling(self, img, kernel):  # Pooling on input image for dim reduction
+    def __pooling(self, img, kernel):  # Pooling on input image for dimension reduction
+        """This method applies a pooling filter on an input image in order to resize it in a fixed shape
+
+         :param img: input image for resizing
+         :rtype img: engine.data.Image class object
+         :param kernel: the kernel size of the pooling filter
+         :type kernel: int
+         """
         pool_img = torchvision.transforms.ToTensor()(img)
         pool_img = pool_img.unsqueeze(0)
         pool_img = torch.nn.functional.avg_pool2d(pool_img, kernel)
@@ -146,6 +193,34 @@ def save(self, path):
 
     def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_size=250, upsample_ratio=4,
              images_folder_name="val2017", annotations_filename="person_keypoints_val2017.json"):
+        """
+                This method is used to evaluate a trained model on an evaluation dataset.
+
+                :param dataset: object that holds the evaluation dataset.
+                :type dataset: ExternalDataset class object or DatasetIterator class object
+                :param silent: if set to True, disables all printing of evalutaion progress reports and other
+                    information to STDOUT, defaults to 'False'
+                :type silent: bool, optional
+                :param verbose: if set to True, enables the maximum verbosity, defaults to 'True'
+                :type verbose: bool, optional
+                :param use_subset: If set to True, a subset of the validation dataset is created and used in
+                    evaluation, defaults to 'True'
+                :type use_subset: bool, optional
+                :param subset_size: Controls the size of the validation subset, defaults to '250'
+                :type subset_size: int, optional
+                param upsample_ratio: Defines the amount of upsampling to be performed on the heatmaps and PAFs
+                    when resizing,defaults to 4
+                :type upsample_ratio: int, optional
+                :param images_folder_name: Folder name that contains the dataset images. This folder should be contained
+                in the dataset path provided. Note that this is a folder name, not a path, defaults to 'val2017'
+                :type images_folder_name: str, optional
+                :param annotations_filename: Filename of the annotations json file. This file should be contained in the
+                    dataset path provided, defaults to 'pesron_keypoints_val2017.json'
+                :type annotations_filename: str, optional
+
+                :returns: returns stats regarding evaluation
+                :rtype: dict
+                """
 
         data = super(HighResolutionPoseEstimationLearner,
                      self)._LightweightOpenPoseLearner__prepare_val_dataset(dataset, use_subset=use_subset,
@@ -217,15 +292,12 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_siz
             else:
                 pool_img = img
 
-            perc = 0.3  # percentage around cropping
-            threshold = 0.1  # threshold for heatmap
-
             # ------- Heatmap Generation -------
             avg_pafs = HighResolutionPoseEstimationLearner.__first_pass(self, self.model, pool_img)
             avg_pafs = avg_pafs.astype(np.float32)
 
             pafs_map = cv2.blur(avg_pafs, (5, 5))
-            pafs_map[pafs_map < threshold] = 0
+            pafs_map[pafs_map < self.threshold] = 0
 
             heatmap = pafs_map.sum(axis=2)
             heatmap = heatmap * 100
@@ -253,8 +325,8 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_siz
                 ymin = int(np.floor(min(ydim))) * int((h / heatmap.shape[0])) * kernel
                 ymax = int(np.floor(max(ydim))) * int((h / heatmap.shape[0])) * kernel
 
-                extra_pad_x = int(perc * (xmax - xmin))  # Adding an extra pad around cropped image
-                extra_pad_y = int(perc * (ymax - ymin))
+                extra_pad_x = int(self.perc * (xmax - xmin))  # Adding an extra pad around cropped image
+                extra_pad_y = int(self.perc * (ymax - ymin))
 
                 if xmin - extra_pad_x > 0:
                     xmin = xmin - extra_pad_x
@@ -350,6 +422,28 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_siz
 
     def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
               multiscale=False):
+        """
+                This method is used to perform pose estimation on an image.
+
+                :param img: image to run inference on
+                :rtype img: engine.data.Image class object
+                :param upsample_ratio: Defines the amount of upsampling to be performed on the heatmaps and PAFs
+                    when resizing,defaults to 4
+                :type upsample_ratio: int, optional
+                :param stride: Defines the stride value for creating a padded image
+                :type stride: int,optional
+                :param track: If True, infer propagates poses ids from previous frame results to track poses,
+                    defaults to 'True'
+                :type track: bool, optional
+                :param smooth: If True, smoothing is performed on pose keypoints between frames, defaults to 'True'
+                :type smooth: bool, optional
+                :param multiscale: Specifies whether evaluation will run in the predefined multiple scales setup or not.
+                :type multiscale: bool,optional
+
+                :return: Returns a list of engine.target.Pose objects, where each holds a pose, or returns an empty list
+                    if no detections were made.
+                :rtype: list of engine.target.Pose objects
+                """
         current_poses = []
 
         offset = 0
@@ -371,16 +465,12 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
         else:
             pool_img = img
 
-        perc = 0.3  # percentage around cropping
-
-        threshold = 0.1  # threshold for heatmap
-
         # ------- Heatmap Generation -------
         avg_pafs = HighResolutionPoseEstimationLearner.__first_pass(self, self.model, pool_img)
         avg_pafs = avg_pafs.astype(np.float32)
         pafs_map = cv2.blur(avg_pafs, (5, 5))
 
-        pafs_map[pafs_map < threshold] = 0
+        pafs_map[pafs_map < self.threshold] = 0
 
         heatmap = pafs_map.sum(axis=2)
         heatmap = heatmap * 100
@@ -407,8 +497,8 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
             ymin = int(np.floor(min(ydim))) * int((h / heatmap.shape[0])) * kernel
             ymax = int(np.floor(max(ydim))) * int((h / heatmap.shape[0])) * kernel
 
-            extra_pad_x = int(perc * (xmax - xmin))  # Adding an extra pad around cropped image
-            extra_pad_y = int(perc * (ymax - ymin))
+            extra_pad_x = int(self.perc * (xmax - xmin))  # Adding an extra pad around cropped image
+            extra_pad_y = int(self.perc * (ymax - ymin))
 
             if xmin - extra_pad_x > 0:
                 xmin = xmin - extra_pad_x
@@ -510,7 +600,7 @@ def download(self, path=None, mode="pretrained", verbose=False,
             file_url = os.path.join(url, "dataset", "annotation.json")
             urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "annotation.json"))
             # Download test image
-            if image_resolution in(1080, 1440):
+            if image_resolution in (1080, 1440):
                 file_url = os.path.join(url, "dataset", "image", "000000000785_" + str(image_resolution) + ".jpg")
                 urlretrieve(file_url, os.path.join(self.temp_path, "dataset", "image", "000000000785_1080.jpg"))
             else:

From 664d0bbe13c6809146dc827d10541a4b89cadcf5 Mon Sep 17 00:00:00 2001
From: mthodoris <45919203+mthodoris@users.noreply.github.com>
Date: Wed, 21 Dec 2022 14:14:22 +0200
Subject: [PATCH 23/27] Update
 docs/reference/high-resolution-pose-estimation.md

Co-authored-by: Nikolaos Passalis <passalis@users.noreply.github.com>
---
 docs/reference/high-resolution-pose-estimation.md | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/docs/reference/high-resolution-pose-estimation.md b/docs/reference/high-resolution-pose-estimation.md
index 1ff45aa426..c77e90e0ef 100644
--- a/docs/reference/high-resolution-pose-estimation.md
+++ b/docs/reference/high-resolution-pose-estimation.md
@@ -48,7 +48,7 @@ Constructor parameters:
 - **percentage_arround_crop**: *float, default=0.3*\
   Specifies the percentage of an extra pad arround the cropped image
 - **heatmap_threshold**: *float, default=0.1*\
-  Specifies a threshlod value that the heatmap elements should have
+  Specifies the threshold value that the heatmap elements should have during the first pass in order to trigger the second pass
 - **experiment_name**: *str, default='default'*\
   String name to attach to checkpoints.
 - **num_workers**: *int, default=8*\

From 82313ba8cf72065fc3566782944c178482d79a61 Mon Sep 17 00:00:00 2001
From: mthodoris <45919203+mthodoris@users.noreply.github.com>
Date: Wed, 21 Dec 2022 15:58:04 +0200
Subject: [PATCH 24/27] Apply suggestions from code review

Co-authored-by: Kostas Tsampazis <27914645+tsampazk@users.noreply.github.com>
---
 .../high-resolution-pose-estimation.md        | 18 ++++----
 .../high_resolution_pose_estimation/README.md |  2 +-
 .../demos/benchmarking_demo.py                |  7 +---
 .../demos/eval_demo.py                        |  6 +--
 .../demos/inference_demo.py                   |  6 +--
 .../high_resolution_learner.py                | 41 ++++++++++---------
 6 files changed, 34 insertions(+), 46 deletions(-)

diff --git a/docs/reference/high-resolution-pose-estimation.md b/docs/reference/high-resolution-pose-estimation.md
index c77e90e0ef..791ae06e02 100644
--- a/docs/reference/high-resolution-pose-estimation.md
+++ b/docs/reference/high-resolution-pose-estimation.md
@@ -8,12 +8,12 @@ Bases: `engine.learners.Learner`
 The *HighResolutionLightweightOpenPose* class is an implementation for pose estimation in high resolution images.
 This method creates a heatmap of a resized version of the input image.
 Using this heatmap, the input image is cropped keeping the area of interest and then it is used for pose estimation.
-Since the high resolution pose estimation method is based on Lightweight OpenPose algorithm,the models that could be used have to be trained with Lightweight OpenPose tool.
+Since the high resolution pose estimation method is based on the Lightweight OpenPose algorithm, the models that can be used have to be trained with the Lightweight OpenPose tool.
 
 In this method there are two important variables which are responsible for the increase in speed and accuracy in high resolution images.
-These variables are the *first_pass_height* and the *second_pass_height* that the image is resized in this procedure.
+These variables are *first_pass_height* and *second_pass_height* which define how the image is resized in this procedure.
 
-The [HighResolutionPoseEstimationLearner](/src/opendr/perception/pose_estimation/hr_pose_estimation/HighResolutionLearner.py) class has the following public methods:
+The [HighResolutionPoseEstimationLearner](/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py) class has the following public methods:
 
 #### `HighResolutionPoseEstimationLearner` constructor
 ```python
@@ -134,7 +134,7 @@ Parameters:
 HighResolutionPoseEstimationLearner.__first_pass(self, net, img)
 ```
 
-This method is used for extracting from the input image a heatmap about human locations in the picture.
+This method is used for extracting a heatmap from the input image about human locations in the picture.
 
 Parameters:
 
@@ -148,8 +148,8 @@ Parameters:
 HighResolutionPoseEstimationLearner.__second_pass(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, pad_value, img_mean, img_scale)
 ```
 
-On this method it is carried out the second inference step which estimates the human poses on the image that is inserted.
-Following the steps of the proposed method this image should be the cropped part of the initial high resolution image that came out from taking into account the area of interest of heatmap generation.
+On this method the second inference step is carried out, which estimates the human poses on the image that is provided.
+Following the steps of the proposed method this image should be the cropped part of the initial high resolution image that came out from taking into account the area of interest of the heatmap generated.
 
 Parameters:
 
@@ -253,7 +253,7 @@ The experiments are conducted on a 1080p image.
 |                  OpenDR - Full                   | 2.9                   | 83.1              | 11.2                 | 13.5                |
 
 
-#### Lightweght OpenPoseWithout resizing
+#### Lightweight OpenPoseWithout resizing
 | Method            | CPU i7-9700K (FPS) | RTX 2070  (FPS) | Jetson TX2 (FPS) | Xavier NX (FPS) |
 |-------------------|--------------------|-----------------|------------------|-----------------|
 | OpenDR - Baseline | 0.05               | 2.6             | 0.3              | 0.5             |
@@ -270,7 +270,7 @@ The experiments are conducted on a 1080p image.
 | HRPoseEstim - H+S      | 8.2                | 25.9           | 3.6              | 5.5             |
 | HRPoseEstim - Full     | 10.9               | 31.7           | 4.8              | 6.9             |
 
-As it is shown in the previous Table, OpenDR Lightweight OpenPose achieves higher FPS when it is resing the input image into 256 pixels.
+As it is shown in the previous tables, OpenDR Lightweight OpenPose achieves higher FPS when it is resizing the input image into 256 pixels.
 It is easier to process that image, but as it is shown in the next tables the method falls apart when it comes to accuracy and there are no detections.
 
 We have evaluated the effect of using different inference settings, namely:
@@ -282,7 +282,7 @@ We have evaluated the effect of using different inference settings, namely:
 - *HRPoseEstim - Full*, which refers to combining all three available optimization.
 was used as input to the models.
 
-The average precision and average recall on the COCO evaluation split is also reported in the Table below:
+The average precision and average recall on the COCO evaluation split is also reported in the tables below:
 
 
 #### Lightweight OpenPose with resizing
diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/README.md b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/README.md
index 75e19ef104..da48ec4088 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/README.md
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/README.md
@@ -6,6 +6,6 @@ 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.py: A simple benchmarking tool for measuring the performance of High Resolution Pose Estimation in various platforms.
+3. demos/benchmarking_demo.py: A simple benchmarking tool for measuring the performance of High Resolution Pose Estimation in various platforms.
 
 
diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
index e819b99566..33142e7c99 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/benchmarking_demo.py
@@ -23,7 +23,6 @@
 
 if __name__ == '__main__':
     parser = argparse.ArgumentParser()
-    parser.add_argument("--onnx", help="Use ONNX", default=False, action="store_true")
     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")
@@ -32,7 +31,7 @@
 
     args = parser.parse_args()
 
-    onnx, device, accelerate, base_height1, base_height2 = args.onnx, args.device, args.accelerate,\
+    device, accelerate, base_height1, base_height2 = args.device, args.accelerate,\
         args.height1, args.height2
 
     if device == 'cpu':
@@ -61,15 +60,11 @@
     image_path = join("temp", "dataset", "image", "000000000785_1080.jpg")
     img = cv2.imread(image_path)
 
-    if onnx:
-        pose_estimator.optimize()
-
     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()
diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
index bdc088fb03..9f71e0bd5c 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/eval_demo.py
@@ -21,7 +21,6 @@
 
 if __name__ == '__main__':
     parser = argparse.ArgumentParser()
-    parser.add_argument("--onnx", help="Use ONNX", default=False, action="store_true")
     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")
@@ -30,7 +29,7 @@
 
     args = parser.parse_args()
 
-    onnx, device, accelerate, base_height1, base_height2 = args.onnx, args.device, args.accelerate,\
+    device, accelerate, base_height1, base_height2 = args.device, args.accelerate,\
         args.height1, args.height2
 
     if accelerate:
@@ -50,9 +49,6 @@
     pose_estimator.download(path=".", verbose=True)
     pose_estimator.load("openpose_default")
 
-    if onnx:
-        pose_estimator.optimize()
-
     # Download a sample dataset
     pose_estimator.download(path=".", mode="test_data")
 
diff --git a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
index 76b8c5e881..f1b588d943 100644
--- a/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
+++ b/projects/python/perception/pose_estimation/high_resolution_pose_estimation/demos/inference_demo.py
@@ -22,7 +22,6 @@
 
 if __name__ == '__main__':
     parser = argparse.ArgumentParser()
-    parser.add_argument("--onnx", help="Use ONNX", default=False, action="store_true")
     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")
@@ -31,7 +30,7 @@
 
     args = parser.parse_args()
 
-    onnx, device, accelerate, base_height1, base_height2 = args.onnx, args.device, args.accelerate,\
+    device, accelerate, base_height1, base_height2 = args.device, args.accelerate,\
         args.height1, args.height2
 
     if accelerate:
@@ -57,9 +56,6 @@
 
     img = Image.open(image_path)
 
-    if onnx:
-        pose_estimator.optimize()
-
     poses = pose_estimator.infer(img)
 
     img_cv = img.opencv()
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index 49ea5e3b2b..c94e6b0ee0 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -159,7 +159,8 @@ def __second_pass(self, net, img, net_input_height_size, max_width, stride, upsa
 
         return heatmaps, pafs, scale, pad
 
-    def __pooling(self, img, kernel):  # Pooling on input image for dimension reduction
+    @staticmethod
+    def __pooling(img, kernel):  # Pooling on input image for dimension reduction
         """This method applies a pooling filter on an input image in order to resize it in a fixed shape
 
          :param img: input image for resizing
@@ -173,12 +174,15 @@ def __pooling(self, img, kernel):  # Pooling on input image for dimension reduct
         pool_img = pool_img.squeeze(0).permute(1, 2, 0).cpu().float().numpy()
         return pool_img
 
-    def fit(self, dataset, val_dataset=None, logging_path='', silent=True, verbose=True):
+    def fit(self, dataset, val_dataset=None, logging_path='', logging_flush_secs=30,
+            silent=False, verbose=True, epochs=None, use_val_subset=True, val_subset_size=250,
+            images_folder_name="train2017", annotations_filename="person_keypoints_train2017.json",
+            val_images_folder_name="val2017", val_annotations_filename="person_keypoints_val2017.json"):
         """This method is not used in this implementation."""
 
         raise NotImplementedError
 
-    def optimize(self, target_device):
+    def optimize(self, do_constant_folding=False):
         """This method is not used in this implementation."""
 
         raise NotImplementedError
@@ -187,11 +191,11 @@ def reset(self):
         """This method is not used in this implementation."""
         return NotImplementedError
 
-    def save(self, path):
+    def save(self, path, verbose=False):
         """This method is not used in this implementation."""
         return NotImplementedError
 
-    def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_size=250, upsample_ratio=4,
+    def eval(self, dataset, silent=False, verbose=True, use_subset=True, subset_size=250, upsample_ratio=4,
              images_folder_name="val2017", annotations_filename="person_keypoints_val2017.json"):
         """
                 This method is used to evaluate a trained model on an evaluation dataset.
@@ -222,7 +226,7 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_siz
                 :rtype: dict
                 """
 
-        data = super(HighResolutionPoseEstimationLearner,
+        data = super(HighResolutionPoseEstimationLearner,  # NOQA
                      self)._LightweightOpenPoseLearner__prepare_val_dataset(dataset, use_subset=use_subset,
                                                                             subset_name="val_subset.json",
                                                                             subset_size=subset_size,
@@ -287,13 +291,13 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_siz
             max_width = w
             kernel = int(h / self.first_pass_height)
             if kernel > 0:
-                pool_img = HighResolutionPoseEstimationLearner.__pooling(self, img, kernel)
+                pool_img = self.__pooling(img, kernel)
 
             else:
                 pool_img = img
 
             # ------- Heatmap Generation -------
-            avg_pafs = HighResolutionPoseEstimationLearner.__first_pass(self, self.model, pool_img)
+            avg_pafs = self.__first_pass(self.model, pool_img)
             avg_pafs = avg_pafs.astype(np.float32)
 
             pafs_map = cv2.blur(avg_pafs, (5, 5))
@@ -345,11 +349,9 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_siz
                 h, w, _ = crop_img.shape
 
                 # ------- Second pass of the image, inference for pose estimation -------
-                avg_heatmaps, avg_pafs, scale, pad = \
-                    HighResolutionPoseEstimationLearner.__second_pass(self,
-                                                                      self.model, crop_img,
-                                                                      self.second_pass_height, max_width,
-                                                                      self.stride, upsample_ratio)
+                avg_heatmaps, avg_pafs, scale, pad = self.__second_pass(self.model, crop_img,
+                                                                        self.second_pass_height, max_width,
+                                                                        self.stride, upsample_ratio)
                 total_keypoints_num = 0
                 all_keypoints_by_type = []
                 for kpt_idx in range(18):
@@ -396,7 +398,7 @@ def eval(self, dataset,  silent=False, verbose=True, use_subset=True, subset_siz
             if self.visualize:
                 for keypoints in coco_keypoints:
                     for idx in range(len(keypoints) // 3):
-                        cv2.circle(img, (int(keypoints[idx * 3]+offset), int(keypoints[idx * 3 + 1])+offset),
+                        cv2.circle(img, (int(keypoints[idx * 3] + offset), int(keypoints[idx * 3 + 1]) + offset),
                                    3, (255, 0, 255), -1)
                 cv2.imshow('keypoints', img)
                 key = cv2.waitKey()
@@ -461,12 +463,12 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
 
         kernel = int(h / self.first_pass_height)
         if kernel > 0:
-            pool_img = HighResolutionPoseEstimationLearner.__pooling(self, img, kernel)
+            pool_img = self.__pooling(img, kernel)
         else:
             pool_img = img
 
         # ------- Heatmap Generation -------
-        avg_pafs = HighResolutionPoseEstimationLearner.__first_pass(self, self.model, pool_img)
+        avg_pafs = self.__first_pass(self.model, pool_img)
         avg_pafs = avg_pafs.astype(np.float32)
         pafs_map = cv2.blur(avg_pafs, (5, 5))
 
@@ -517,10 +519,9 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
             h, w, _ = crop_img.shape
 
             # ------- Second pass of the image, inference for pose estimation -------
-            avg_heatmaps, avg_pafs, scale, pad = \
-                HighResolutionPoseEstimationLearner.__second_pass(self, self.model, crop_img,
-                                                                  self.second_pass_height,
-                                                                  max_width, stride, upsample_ratio)
+            avg_heatmaps, avg_pafs, scale, pad = self.__second_pass(self.model, crop_img,
+                                                                    self.second_pass_height,
+                                                                    max_width, stride, upsample_ratio)
 
             total_keypoints_num = 0
             all_keypoints_by_type = []

From bcf222b20ac19098daa15dc0d41a46b77beb114c Mon Sep 17 00:00:00 2001
From: mthodoris <45919203+mthodoris@users.noreply.github.com>
Date: Wed, 21 Dec 2022 16:01:11 +0200
Subject: [PATCH 25/27] Apply suggestions from code review

Co-authored-by: Kostas Tsampazis <27914645+tsampazk@users.noreply.github.com>
---
 .../hr_pose_estimation/high_resolution_learner.py             | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index c94e6b0ee0..72e09c2599 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -202,7 +202,7 @@ def eval(self, dataset, silent=False, verbose=True, use_subset=True, subset_size
 
                 :param dataset: object that holds the evaluation dataset.
                 :type dataset: ExternalDataset class object or DatasetIterator class object
-                :param silent: if set to True, disables all printing of evalutaion progress reports and other
+                :param silent: if set to True, disables all printing of evaluation progress reports and other
                     information to STDOUT, defaults to 'False'
                 :type silent: bool, optional
                 :param verbose: if set to True, enables the maximum verbosity, defaults to 'True'
@@ -219,7 +219,7 @@ def eval(self, dataset, silent=False, verbose=True, use_subset=True, subset_size
                 in the dataset path provided. Note that this is a folder name, not a path, defaults to 'val2017'
                 :type images_folder_name: str, optional
                 :param annotations_filename: Filename of the annotations json file. This file should be contained in the
-                    dataset path provided, defaults to 'pesron_keypoints_val2017.json'
+                    dataset path provided, defaults to 'person_keypoints_val2017.json'
                 :type annotations_filename: str, optional
 
                 :returns: returns stats regarding evaluation

From d6853ad6199cbc2b1544ea971d27fd6632b2cbfc Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Wed, 21 Dec 2022 16:19:17 +0200
Subject: [PATCH 26/27] review fixes

---
 .../high-resolution-pose-estimation.md        |  9 +++----
 .../high_resolution_learner.py                | 24 +++++++------------
 2 files changed, 11 insertions(+), 22 deletions(-)

diff --git a/docs/reference/high-resolution-pose-estimation.md b/docs/reference/high-resolution-pose-estimation.md
index 791ae06e02..b0128397ee 100644
--- a/docs/reference/high-resolution-pose-estimation.md
+++ b/docs/reference/high-resolution-pose-estimation.md
@@ -131,7 +131,7 @@ Parameters:
 
 #### `HighResolutionPoseEstimationLearner.__first_pass`
 ```python
-HighResolutionPoseEstimationLearner.__first_pass(self, net, img)
+HighResolutionPoseEstimationLearner.__first_pass(self, img)
 ```
 
 This method is used for extracting a heatmap from the input image about human locations in the picture.
@@ -140,12 +140,11 @@ Parameters:
 
 - **img**: *object***\
   Object of type engine.data.Image.
-- **net**: *object*\
-  The model that is used for creating the heatmap.
+
 
 #### `HighResolutionPoseEstimationLearner.__second_pass`
 ```python
-HighResolutionPoseEstimationLearner.__second_pass(self, net, img, net_input_height_size, max_width, stride, upsample_ratio, pad_value, img_mean, img_scale)
+HighResolutionPoseEstimationLearner.__second_pass(self, img, net_input_height_size, max_width, stride, upsample_ratio, pad_value, img_mean, img_scale)
 ```
 
 On this method the second inference step is carried out, which estimates the human poses on the image that is provided.
@@ -153,8 +152,6 @@ Following the steps of the proposed method this image should be the cropped part
 
 Parameters:
 
-- **net**: *object*\
-  The model that is used for creating the heatmap.
 - **img**: *object***\
   Object of type engine.data.Image.
 - **net_input_height_size**: *int*\
diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index 72e09c2599..83d62fa036 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -69,14 +69,11 @@ def __init__(self, device='cuda', backbone='mobilenet',
         self.perc = percentage_arround_crop
         self.threshold = heatmap_threshold
 
-    def __first_pass(self, net, img):
+    def __first_pass(self, img):
         """
         This method is generating a rough heatmap of the input image in order to specify the approximate location
         of humans in the picture.
 
-        :param net: the pose estimation model that has been loaded
-        :type net: opendr.perception.pose_estimation.lightweight_open_pose.\
-            algorithm.models.with_mobilenet.PoseEstimationWithMobileNet class object
         :param img: input image for heatmap generation
         :type img: numpy.ndarray
 
@@ -92,22 +89,19 @@ def __first_pass(self, net, img):
         else:
             tensor_img = torch.from_numpy(img).permute(2, 0, 1).unsqueeze(0).float().cpu()
 
-        stages_output = net(tensor_img)
+        stages_output = self.model(tensor_img)
 
         stage2_pafs = stages_output[-1]
         pafs = np.transpose(stage2_pafs.squeeze().cpu().data.numpy(), (1, 2, 0))
         return pafs
 
-    def __second_pass(self, net, img, net_input_height_size, max_width, stride, upsample_ratio,
+    def __second_pass(self, img, net_input_height_size, max_width, stride, upsample_ratio,
                       pad_value=(0, 0, 0),
                       img_mean=np.array([128, 128, 128], np.float32), img_scale=np.float32(1 / 256)):
         """
         This method detects the keypoints and estimates the pose of humans using the cropped image from the
         previous step (__first_pass_).
 
-        param net: the pose estimation model that has been loaded
-        :type net: opendr.perception.pose_estimation.lightweight_open_pose.\
-            algorithm.models.with_mobilenet.PoseEstimationWithMobileNet class object
         :param img: input image for heatmap generation
         :type img: numpy.ndarray
         :param net_input_height_size: the height that the input image will be resized  for inference
@@ -145,7 +139,7 @@ def __second_pass(self, net, img, net_input_height_size, max_width, stride, upsa
         else:
             tensor_img = torch.from_numpy(padded_img).permute(2, 0, 1).unsqueeze(0).float().cpu()
 
-        stages_output = net(tensor_img)
+        stages_output = self.model(tensor_img)
 
         stage2_heatmaps = stages_output[-2]
         heatmaps = np.transpose(stage2_heatmaps.squeeze().cpu().data.numpy(), (1, 2, 0))
@@ -297,7 +291,7 @@ def eval(self, dataset, silent=False, verbose=True, use_subset=True, subset_size
                 pool_img = img
 
             # ------- Heatmap Generation -------
-            avg_pafs = self.__first_pass(self.model, pool_img)
+            avg_pafs = self.__first_pass(pool_img)
             avg_pafs = avg_pafs.astype(np.float32)
 
             pafs_map = cv2.blur(avg_pafs, (5, 5))
@@ -349,8 +343,7 @@ def eval(self, dataset, silent=False, verbose=True, use_subset=True, subset_size
                 h, w, _ = crop_img.shape
 
                 # ------- Second pass of the image, inference for pose estimation -------
-                avg_heatmaps, avg_pafs, scale, pad = self.__second_pass(self.model, crop_img,
-                                                                        self.second_pass_height, max_width,
+                avg_heatmaps, avg_pafs, scale, pad = self.__second_pass(crop_img, self.second_pass_height, max_width,
                                                                         self.stride, upsample_ratio)
                 total_keypoints_num = 0
                 all_keypoints_by_type = []
@@ -468,7 +461,7 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
             pool_img = img
 
         # ------- Heatmap Generation -------
-        avg_pafs = self.__first_pass(self.model, pool_img)
+        avg_pafs = self.__first_pass(pool_img)
         avg_pafs = avg_pafs.astype(np.float32)
         pafs_map = cv2.blur(avg_pafs, (5, 5))
 
@@ -519,8 +512,7 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
             h, w, _ = crop_img.shape
 
             # ------- Second pass of the image, inference for pose estimation -------
-            avg_heatmaps, avg_pafs, scale, pad = self.__second_pass(self.model, crop_img,
-                                                                    self.second_pass_height,
+            avg_heatmaps, avg_pafs, scale, pad = self.__second_pass(crop_img,self.second_pass_height,
                                                                     max_width, stride, upsample_ratio)
 
             total_keypoints_num = 0

From 18dff2492ac17e58ad8f889bf3a6e109f650851e Mon Sep 17 00:00:00 2001
From: mthodoris <thodorisman@gmail.com>
Date: Wed, 21 Dec 2022 16:23:45 +0200
Subject: [PATCH 27/27] typos

---
 .../hr_pose_estimation/high_resolution_learner.py               | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
index 83d62fa036..083af21255 100644
--- a/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
+++ b/src/opendr/perception/pose_estimation/hr_pose_estimation/high_resolution_learner.py
@@ -512,7 +512,7 @@ def infer(self, img, upsample_ratio=4, stride=8, track=True, smooth=True,
             h, w, _ = crop_img.shape
 
             # ------- Second pass of the image, inference for pose estimation -------
-            avg_heatmaps, avg_pafs, scale, pad = self.__second_pass(crop_img,self.second_pass_height,
+            avg_heatmaps, avg_pafs, scale, pad = self.__second_pass(crop_img, self.second_pass_height,
                                                                     max_width, stride, upsample_ratio)
 
             total_keypoints_num = 0