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