diff --git a/humanoid_robot_intelligence_control_system_configure/CMakeLists.txt b/humanoid_robot_intelligence_control_system_configure/CMakeLists.txt new file mode 100644 index 0000000..0277ccd --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/CMakeLists.txt @@ -0,0 +1,77 @@ +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# 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. + +cmake_minimum_required(VERSION 3.0.2) +project(humanoid_robot_intelligence_control_system_object_detector) + +if($ENV{ROS_VERSION} EQUAL 1) + find_package(catkin REQUIRED COMPONENTS + rospy + std_msgs + sensor_msgs + geometry_msgs + cv_bridge + ) + + catkin_package( + CATKIN_DEPENDS + rospy + std_msgs + sensor_msgs + geometry_msgs + cv_bridge + ) + +else() + find_package(ament_cmake REQUIRED) + find_package(ament_cmake_python REQUIRED) + find_package(rclpy REQUIRED) + find_package(std_msgs REQUIRED) + find_package(sensor_msgs REQUIRED) + find_package(geometry_msgs REQUIRED) + find_package(cv_bridge REQUIRED) +endif() + +if($ENV{ROS_VERSION} EQUAL 1) + catkin_python_setup() + + catkin_install_python(PROGRAMS + src/face_tracker.py + src/face_follower.py + src/object_tracker.py + src/object_follower.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + + install(DIRECTORY config launch rviz + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + ) + +else() + ament_python_install_package(${PROJECT_NAME}) + + install(PROGRAMS + src/face_tracker.py + src/face_follower.py + src/object_tracker.py + src/object_follower.py + DESTINATION lib/${PROJECT_NAME} + ) + + install(DIRECTORY config launch rviz + DESTINATION share/${PROJECT_NAME} + ) + + ament_package() +endif() diff --git a/humanoid_robot_intelligence_control_system_configure/launch/face_follower.launch.py b/humanoid_robot_intelligence_control_system_configure/launch/face_follower.launch.py new file mode 100644 index 0000000..051f56a --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/launch/face_follower.launch.py @@ -0,0 +1,114 @@ +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +#!/usr/bin/env python3 + +#!/usr/bin/env python3 + +import os +import sys +import subprocess +from launch import LaunchDescription +from launch_ros.actions import Node + +def ros1_launch_description(): + # Get command-line arguments + args = sys.argv[1:] + + # Construct the ROS 1 launch command + roslaunch_command = ["roslaunch", "humanoid_robot_intelligence_control_system_object_detector", "object_follow.launch"] + args + + roslaunch_command.extend([ + "usb_cam", "usb_cam_node", "name:=camera", + "video_device:=/dev/video0", + "image_width:=640", + "image_height:=480", + "pixel_format:=yuyv", + "camera_frame_id:=usb_cam", + "io_method:=mmap" + ]) + + roslaunch_command.extend([ + "humanoid_robot_intelligence_control_system_object_detector", "object_detection_processor.py", "name:=object_detection_processor_node" + ]) + + roslaunch_command.extend([ + "humanoid_robot_intelligence_control_system_object_detector", "object_follower.py", "name:=object_follower_node" + ]) + + roslaunch_command.extend([ + "rviz", "rviz", "name:=rviz", + "args:=-d $(find humanoid_robot_intelligence_control_system_object_detector)/rviz/object_follow_visualization.rviz" + ]) + + # Execute the launch command + subprocess.call(roslaunch_command) + +def ros2_launch_description(): + nodes_to_launch = [] + + nodes_to_launch.append(Node( + package='usb_cam', + executable='usb_cam_node', + name='camera', + output='screen', + parameters=[{ + 'video_device': '/dev/video0', + 'image_width': 640, + 'image_height': 480, + 'pixel_format': 'yuyv', + 'camera_frame_id': 'usb_cam', + 'io_method': 'mmap' + }] + )) + + nodes_to_launch.append(Node( + package='humanoid_robot_intelligence_control_system_object_detector', + executable='object_detection_processor.py', + name='object_detection_processor_node', + output='screen', + parameters=[{'yaml_path': '$(find humanoid_robot_intelligence_control_system_object_detector)/config/object_detection_params.yaml'}] + )) + + nodes_to_launch.append(Node( + package='humanoid_robot_intelligence_control_system_object_detector', + executable='object_follower.py', + name='object_follower_node', + output='screen', + parameters=[{ + 'p_gain': 0.4, + 'i_gain': 0.0, + 'd_gain': 0.0 + }] + )) + + nodes_to_launch.append(Node( + package='rviz2', + executable='rviz2', + name='rviz', + arguments=['-d', '$(find humanoid_robot_intelligence_control_system_object_detector)/rviz/object_follow_visualization.rviz'] + )) + + return LaunchDescription(nodes_to_launch) + +if __name__ == "__main__": + ros_version = os.getenv("ROS_VERSION") + if ros_version == "1": + ros1_launch_description() + elif ros_version == "2": + ros2_launch_description() + else: + print("Unsupported ROS version. Please set the ROS_VERSION environment variable to '1' for ROS 1 or '2' for ROS 2.") + sys.exit(1) diff --git a/humanoid_robot_intelligence_control_system_configure/launch/face_tracker.launch.py b/humanoid_robot_intelligence_control_system_configure/launch/face_tracker.launch.py new file mode 100644 index 0000000..91a9896 --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/launch/face_tracker.launch.py @@ -0,0 +1,112 @@ +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +#!/usr/bin/env python3 + +import os +import sys +import subprocess +from launch import LaunchDescription +from launch_ros.actions import Node + +def ros1_launch_description(): + # Get command-line arguments + args = sys.argv[1:] + + # Construct the ROS 1 launch command + roslaunch_command = ["roslaunch", "humanoid_robot_intelligence_control_system_configure", "object_tracker.launch"] + args + + roslaunch_command.extend([ + "usb_cam", "usb_cam_node", "name:=camera", + "video_device:=/dev/video0", + "image_width:=640", + "image_height:=480", + "pixel_format:=yuyv", + "camera_frame_id:=usb_cam", + "io_method:=mmap" + ]) + + roslaunch_command.extend([ + "humanoid_robot_intelligence_control_system_object_detector", "object_detection_processor.py", "name:=object_detection_processor_node" + ]) + + roslaunch_command.extend([ + "humanoid_robot_intelligence_control_system_configure", "object_tracker.py", "name:=object_tracker_node" + ]) + + roslaunch_command.extend([ + "rviz", "rviz", "name:=rviz", + "args:=-d $(find humanoid_robot_intelligence_control_system_object_detector)/rviz/object_tracking_visualization.rviz" + ]) + + # Execute the launch command + subprocess.call(roslaunch_command) + +def ros2_launch_description(): + nodes_to_launch = [] + + nodes_to_launch.append(Node( + package='usb_cam', + executable='usb_cam_node', + name='camera', + output='screen', + parameters=[{ + 'video_device': '/dev/video0', + 'image_width': 640, + 'image_height': 480, + 'pixel_format': 'yuyv', + 'camera_frame_id': 'usb_cam', + 'io_method': 'mmap' + }] + )) + + nodes_to_launch.append(Node( + package='humanoid_robot_intelligence_control_system_object_detector', + executable='object_detection_processor.py', + name='object_detection_processor_node', + output='screen', + parameters=[{'yaml_path': '$(find humanoid_robot_intelligence_control_system_object_detector)/config/object_detection_params.yaml'}] + )) + + nodes_to_launch.append(Node( + package='humanoid_robot_intelligence_control_system_object_detector', + executable='object_tracker.py', + name='object_tracker_node', + output='screen', + parameters=[{ + 'p_gain': 0.4, + 'i_gain': 0.0, + 'd_gain': 0.0 + }] + )) + + nodes_to_launch.append(Node( + package='rviz2', + executable='rviz2', + name='rviz', + arguments=['-d', '$(find humanoid_robot_intelligence_control_system_object_detector)/rviz/object_tracking_visualization.rviz'] + )) + + return LaunchDescription(nodes_to_launch) + +if __name__ == "__main__": + ros_version = os.getenv("ROS_VERSION") + if ros_version == "1": + ros1_launch_description() + elif ros_version == "2": + ros2_launch_description() + else: + print("Unsupported ROS version. Please set the ROS_VERSION environment variable to '1' for ROS 1 or '2' for ROS 2.") + sys.exit(1) diff --git a/humanoid_robot_intelligence_control_system_configure/launch/object_follower.launch.py b/humanoid_robot_intelligence_control_system_configure/launch/object_follower.launch.py new file mode 100644 index 0000000..e61d87a --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/launch/object_follower.launch.py @@ -0,0 +1,108 @@ +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +import os +import sys +import subprocess +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration + +def ros1_launch_description(): + # Get command-line arguments + args = sys.argv[1:] + + # Construct the ROS 1 launch command + roslaunch_command = ["roslaunch", "humanoid_robot_intelligence_control_system_object_detector", "object_detector_processor.launch"] + args + + roslaunch_command.extend([ + "usb_cam", "usb_cam_node", "name:=camera", + "video_device:=/dev/video0", + "image_width:=640", + "image_height:=480", + "pixel_format:=yuyv", + "camera_frame_id:=usb_cam", + "io_method:=mmap" + ]) + + roslaunch_command.extend([ + "ros_web_api_bellande_2d_computer_vision", "bellande_2d_computer_vision_object_detection.py", "name:=object_detection_node" + ]) + + roslaunch_command.extend([ + "humanoid_robot_intelligence_control_system_ball_detector", "object_detection_processor.py", "name:=object_detection_processor_node" + ]) + + roslaunch_command.extend([ + "rviz", "rviz", "name:=rviz", + "args:=-d $(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz" + ]) + + # Execute the launch command + subprocess.call(roslaunch_command) + +def ros2_launch_description(): + nodes_to_launch = [] + + nodes_to_launch.append(Node( + package='usb_cam', + executable='usb_cam_node', + name='camera', + output='screen', + parameters=[{ + 'video_device': '/dev/video0', + 'image_width': 640, + 'image_height': 480, + 'pixel_format': 'yuyv', + 'camera_frame_id': 'usb_cam', + 'io_method': 'mmap' + }] + )) + + nodes_to_launch.append(Node( + package='ros_web_api_bellande_2d_computer_vision', + executable='bellande_2d_computer_vision_object_detection.py', + name='object_detection_node', + output='screen', + remappings=[('camera/image_raw', '/usb_cam/image_raw')] + )) + + nodes_to_launch.append(Node( + package='humanoid_robot_intelligence_control_system_object_detector', + executable='object_detection_processor.py', + name='object_detection_processor_node', + output='screen', + parameters=[{'yaml_path': '$(find ros_web_api_bellande_2d_computer_vision)/yaml/object_detection_params.yaml'}] + )) + + nodes_to_launch.append(Node( + package='rviz2', + executable='rviz2', + name='rviz', + arguments=['-d', '$(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz'] + )) + + return LaunchDescription(nodes_to_launch) + +if __name__ == "__main__": + ros_version = os.getenv("ROS_VERSION") + if ros_version == "1": + ros1_launch_description() + elif ros_version == "2": + ros2_launch_description() + else: + print("Unsupported ROS version. Please set the ROS_VERSION environment variable to '1' for ROS 1 or '2' for ROS 2.") + sys.exit(1) diff --git a/humanoid_robot_intelligence_control_system_configure/launch/object_tracker.launch.py b/humanoid_robot_intelligence_control_system_configure/launch/object_tracker.launch.py new file mode 100644 index 0000000..e61d87a --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/launch/object_tracker.launch.py @@ -0,0 +1,108 @@ +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +import os +import sys +import subprocess +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration + +def ros1_launch_description(): + # Get command-line arguments + args = sys.argv[1:] + + # Construct the ROS 1 launch command + roslaunch_command = ["roslaunch", "humanoid_robot_intelligence_control_system_object_detector", "object_detector_processor.launch"] + args + + roslaunch_command.extend([ + "usb_cam", "usb_cam_node", "name:=camera", + "video_device:=/dev/video0", + "image_width:=640", + "image_height:=480", + "pixel_format:=yuyv", + "camera_frame_id:=usb_cam", + "io_method:=mmap" + ]) + + roslaunch_command.extend([ + "ros_web_api_bellande_2d_computer_vision", "bellande_2d_computer_vision_object_detection.py", "name:=object_detection_node" + ]) + + roslaunch_command.extend([ + "humanoid_robot_intelligence_control_system_ball_detector", "object_detection_processor.py", "name:=object_detection_processor_node" + ]) + + roslaunch_command.extend([ + "rviz", "rviz", "name:=rviz", + "args:=-d $(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz" + ]) + + # Execute the launch command + subprocess.call(roslaunch_command) + +def ros2_launch_description(): + nodes_to_launch = [] + + nodes_to_launch.append(Node( + package='usb_cam', + executable='usb_cam_node', + name='camera', + output='screen', + parameters=[{ + 'video_device': '/dev/video0', + 'image_width': 640, + 'image_height': 480, + 'pixel_format': 'yuyv', + 'camera_frame_id': 'usb_cam', + 'io_method': 'mmap' + }] + )) + + nodes_to_launch.append(Node( + package='ros_web_api_bellande_2d_computer_vision', + executable='bellande_2d_computer_vision_object_detection.py', + name='object_detection_node', + output='screen', + remappings=[('camera/image_raw', '/usb_cam/image_raw')] + )) + + nodes_to_launch.append(Node( + package='humanoid_robot_intelligence_control_system_object_detector', + executable='object_detection_processor.py', + name='object_detection_processor_node', + output='screen', + parameters=[{'yaml_path': '$(find ros_web_api_bellande_2d_computer_vision)/yaml/object_detection_params.yaml'}] + )) + + nodes_to_launch.append(Node( + package='rviz2', + executable='rviz2', + name='rviz', + arguments=['-d', '$(find ros_web_api_bellande_2d_computer_vision)/rviz/visualization.rviz'] + )) + + return LaunchDescription(nodes_to_launch) + +if __name__ == "__main__": + ros_version = os.getenv("ROS_VERSION") + if ros_version == "1": + ros1_launch_description() + elif ros_version == "2": + ros2_launch_description() + else: + print("Unsupported ROS version. Please set the ROS_VERSION environment variable to '1' for ROS 1 or '2' for ROS 2.") + sys.exit(1) diff --git a/humanoid_robot_intelligence_control_system_configure/launch/ros1/face_follower.launch b/humanoid_robot_intelligence_control_system_configure/launch/ros1/face_follower.launch new file mode 100644 index 0000000..6799e95 --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/launch/ros1/face_follower.launch @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/humanoid_robot_intelligence_control_system_configure/launch/ros1/face_tracker.launch b/humanoid_robot_intelligence_control_system_configure/launch/ros1/face_tracker.launch new file mode 100644 index 0000000..6799e95 --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/launch/ros1/face_tracker.launch @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/humanoid_robot_intelligence_control_system_configure/launch/ros1/object_follower.launch b/humanoid_robot_intelligence_control_system_configure/launch/ros1/object_follower.launch new file mode 100644 index 0000000..6799e95 --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/launch/ros1/object_follower.launch @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/humanoid_robot_intelligence_control_system_configure/launch/ros1/object_tracker.launch b/humanoid_robot_intelligence_control_system_configure/launch/ros1/object_tracker.launch new file mode 100644 index 0000000..6799e95 --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/launch/ros1/object_tracker.launch @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/humanoid_robot_intelligence_control_system_configure/package.xml b/humanoid_robot_intelligence_control_system_configure/package.xml new file mode 100644 index 0000000..740f1f7 --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/package.xml @@ -0,0 +1,61 @@ + + + + + humanoid_robot_intelligence_control_system_configure + 0.0.1 + + This Package is for Configuration of Tracker and Follower related to it + + Apache 2.0 + Ronaldson Bellande + + catkin + ament_cmake + ament_cmake_python + + + rospy + std_msgs + sensor_msgs + geometry_msgs + cv_bridge + image_transport + dynamic_reconfigure + message_generation + message_runtime + + + rclpy + std_msgs + sensor_msgs + geometry_msgs + cv_bridge + image_transport + rosidl_default_generators + rosidl_default_runtime + + + python3-opencv + python3-yaml + usb_cam + + + catkin + ament_cmake + + diff --git a/humanoid_robot_intelligence_control_system_configure/setup.py b/humanoid_robot_intelligence_control_system_configure/setup.py new file mode 100644 index 0000000..690d947 --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/setup.py @@ -0,0 +1,26 @@ +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +# fetch values from package.xml +setup_args = generate_distutils_setup( + scripts=['src/face_tracker.py', "src/face_follower.py", "src/object_tracker.py", "src/object_follower.py"], + packages=['humanoid_robot_intelligence_control_system_configure'], + package_dir={'': 'src'}, +) + +setup(**setup_args) diff --git a/humanoid_robot_intelligence_control_system_configure/src/face_follower.py b/humanoid_robot_intelligence_control_system_configure/src/face_follower.py new file mode 100644 index 0000000..0f11ade --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/src/face_follower.py @@ -0,0 +1,173 @@ +#!/usr/bin/env python3 + +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +import rospy +import math +from sensor_msgs.msg import JointState +from std_msgs.msg import String, Bool +from geometry_msgs.msg import Point +from humanoid_robot_intelligence_control_system_walking_module_msgs.msg import WalkingParam +from humanoid_robot_intelligence_control_system_walking_module_msgs.srv import GetWalkingParam + +class FaceFollower: + def __init__(self): + rospy.init_node('face_follower') + + self.FOV_WIDTH = 35.2 * math.pi / 180 + self.FOV_HEIGHT = 21.6 * math.pi / 180 + self.count_not_found = 0 + self.count_to_approach = 0 + self.on_following = False + self.approach_face_position = "NotFound" + self.CAMERA_HEIGHT = 0.46 + self.NOT_FOUND_THRESHOLD = 50 + self.MAX_FB_STEP = 40.0 * 0.001 + self.MAX_RL_TURN = 15.0 * math.pi / 180 + self.IN_PLACE_FB_STEP = -3.0 * 0.001 + self.MIN_FB_STEP = 5.0 * 0.001 + self.MIN_RL_TURN = 5.0 * math.pi / 180 + self.UNIT_FB_STEP = 1.0 * 0.001 + self.UNIT_RL_TURN = 0.5 * math.pi / 180 + self.SPOT_FB_OFFSET = 0.0 * 0.001 + self.SPOT_RL_OFFSET = 0.0 * 0.001 + self.SPOT_ANGLE_OFFSET = 0.0 + self.hip_pitch_offset = 7.0 + self.current_pan = -10 + self.current_tilt = -10 + self.current_x_move = 0.005 + self.current_r_angle = 0 + self.curr_period_time = 0.6 + self.accum_period_time = 0.0 + self.DEBUG_PRINT = False + + self.current_joint_states_sub = rospy.Subscriber( + "/humanoid_robot_intelligence_control_system/goal_joint_states", JointState, self.current_joint_states_callback) + self.set_walking_command_pub = rospy.Publisher( + "/humanoid_robot_intelligence_control_system/walking/command", String, queue_size=1) + self.set_walking_param_pub = rospy.Publisher( + "/humanoid_robot_intelligence_control_system/walking/set_params", WalkingParam, queue_size=1) + self.get_walking_param_client = rospy.ServiceProxy( + "/humanoid_robot_intelligence_control_system/walking/get_params", GetWalkingParam) + + self.face_position_sub = rospy.Subscriber( + "/face_detector/face_position", Point, self.face_position_callback) + + self.prev_time = rospy.Time.now() + self.current_walking_param = WalkingParam() + + def start_following(self): + self.on_following = True + rospy.loginfo("Start Face following") + self.set_walking_command("start") + result = self.get_walking_param() + if result: + self.hip_pitch_offset = self.current_walking_param.hip_pitch_offset + self.curr_period_time = self.current_walking_param.period_time + else: + self.hip_pitch_offset = 7.0 * math.pi / 180 + self.curr_period_time = 0.6 + + def stop_following(self): + self.on_following = False + self.count_to_approach = 0 + rospy.loginfo("Stop Face following") + self.set_walking_command("stop") + + def current_joint_states_callback(self, msg): + for i, name in enumerate(msg.name): + if name == "head_pan": + self.current_pan = msg.position[i] + elif name == "head_tilt": + self.current_tilt = msg.position[i] + + def face_position_callback(self, msg): + if self.on_following: + self.process_following(msg.x, msg.y, msg.z) + + def calc_footstep(self, target_distance, target_angle, delta_time): + next_movement = self.current_x_move + target_distance = max(0, target_distance) + fb_goal = min(target_distance * 0.1, self.MAX_FB_STEP) + self.accum_period_time += delta_time + if self.accum_period_time > (self.curr_period_time / 4): + self.accum_period_time = 0.0 + if (target_distance * 0.1 / 2) < self.current_x_move: + next_movement -= self.UNIT_FB_STEP + else: + next_movement += self.UNIT_FB_STEP + fb_goal = min(next_movement, fb_goal) + fb_move = max(fb_goal, self.MIN_FB_STEP) + + rl_goal = 0.0 + if abs(target_angle) * 180 / math.pi > 5.0: + rl_offset = abs(target_angle) * 0.2 + rl_goal = min(rl_offset, self.MAX_RL_TURN) + rl_goal = max(rl_goal, self.MIN_RL_TURN) + rl_angle = min(abs(self.current_r_angle) + self.UNIT_RL_TURN, rl_goal) + if target_angle < 0: + rl_angle *= -1 + else: + rl_angle = 0 + + return fb_move, rl_angle + + def process_following(self, x_angle, y_angle, face_size): + curr_time = rospy.Time.now() + delta_time = (curr_time - self.prev_time).to_sec() + self.prev_time = curr_time + + self.count_not_found = 0 + + if self.current_tilt == -10 and self.current_pan == -10: + rospy.logerr("Failed to get current angle of head joints.") + self.set_walking_command("stop") + self.on_following = False + self.approach_face_position = "NotFound" + return False + + self.approach_face_position = "OutOfRange" + + distance_to_face = self.CAMERA_HEIGHT * math.tan(math.pi * 0.5 + self.current_tilt - self.hip_pitch_offset - face_size) + distance_to_face = abs(distance_to_face) + + distance_to_approach = 0.5 # Adjust this value as needed + + if (distance_to_face < distance_to_approach) and (abs(x_angle) < 25.0): + self.count_to_approach += 1 + if self.count_to_approach > 20: + self.set_walking_command("stop") + self.on_following = False + self.approach_face_position = "OnLeft" if x_angle > 0 else "OnRight" + return True + elif self.count_to_approach > 15: + self.set_walking_param(self.IN_PLACE_FB_STEP, 0, 0) + return False + else: + self.count_to_approach = 0 + + distance_to_walk = distance_to_face - distance_to_approach + fb_move, rl_angle = self.calc_footstep(distance_to_walk, self.current_pan, delta_time) + self.set_walking_param(fb_move, 0, rl_angle) + return False + + def set_walking_command(self, command): + if command == "start": + self.get_walking_param() + self.set_walking_param(self.IN_PLACE_FB_STEP, 0, 0, True) + msg = String() + msg.data = command + self.set_walking_command_pub. diff --git a/humanoid_robot_intelligence_control_system_configure/src/face_tracker.py b/humanoid_robot_intelligence_control_system_configure/src/face_tracker.py new file mode 100644 index 0000000..046f5b0 --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/src/face_tracker.py @@ -0,0 +1,179 @@ +#!/usr/bin/env python3 + +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + + +import rospy +import math +from sensor_msgs.msg import JointState +from std_msgs.msg import String +from geometry_msgs.msg import Point + +class FaceTracker: + def __init__(self): + rospy.init_node('face_tracker') + + self.FOV_WIDTH = 35.2 * math.pi / 180 + self.FOV_HEIGHT = 21.6 * math.pi / 180 + self.NOT_FOUND_THRESHOLD = 50 + self.WAITING_THRESHOLD = 5 + self.use_head_scan = True + self.count_not_found = 0 + self.on_tracking = False + self.current_face_pan = 0 + self.current_face_tilt = 0 + self.x_error_sum = 0 + self.y_error_sum = 0 + self.tracking_status = "NotFound" + self.DEBUG_PRINT = False + + self.p_gain = rospy.get_param('~p_gain', 0.4) + self.i_gain = rospy.get_param('~i_gain', 0.0) + self.d_gain = rospy.get_param('~d_gain', 0.0) + + rospy.loginfo(f"Face tracking Gain : {self.p_gain}, {self.i_gain}, {self.d_gain}") + + self.head_joint_pub = rospy.Publisher( + "/humanoid_robot_intelligence_control_system/head_control/set_joint_states", JointState, queue_size=1) + self.head_scan_pub = rospy.Publisher( + "/humanoid_robot_intelligence_control_system/head_control/scan_command", String, queue_size=1) + + self.face_position_sub = rospy.Subscriber( + "/face_detector/face_position", Point, self.face_position_callback) + self.face_tracking_command_sub = rospy.Subscriber( + "/face_tracker/command", String, self.face_tracker_command_callback) + + self.face_position = Point() + self.prev_time = rospy.Time.now() + + def face_position_callback(self, msg): + self.face_position = msg + + def face_tracker_command_callback(self, msg): + if msg.data == "start": + self.start_tracking() + elif msg.data == "stop": + self.stop_tracking() + elif msg.data == "toggle_start": + if not self.on_tracking: + self.start_tracking() + else: + self.stop_tracking() + + def start_tracking(self): + self.on_tracking = True + rospy.loginfo("Start Face tracking") + + def stop_tracking(self): + self.go_init() + self.on_tracking = False + rospy.loginfo("Stop Face tracking") + self.current_face_pan = 0 + self.current_face_tilt = 0 + self.x_error_sum = 0 + self.y_error_sum = 0 + + def process_tracking(self): + if not self.on_tracking: + self.face_position.z = 0 + self.count_not_found = 0 + return "NotFound" + + if self.face_position.z <= 0: + self.count_not_found += 1 + if self.count_not_found < self.WAITING_THRESHOLD: + tracking_status = "Waiting" + elif self.count_not_found > self.NOT_FOUND_THRESHOLD: + self.scan_face() + self.count_not_found = 0 + tracking_status = "NotFound" + else: + tracking_status = "NotFound" + else: + self.count_not_found = 0 + tracking_status = "Found" + + if tracking_status != "Found": + self.tracking_status = tracking_status + return tracking_status + + x_error = -math.atan(self.face_position.x * math.tan(self.FOV_WIDTH)) + y_error = -math.atan(self.face_position.y * math.tan(self.FOV_HEIGHT)) + + curr_time = rospy.Time.now() + delta_time = (curr_time - self.prev_time).to_sec() + self.prev_time = curr_time + + x_error_diff = (x_error - self.current_face_pan) / delta_time + y_error_diff = (y_error - self.current_face_tilt) / delta_time + self.x_error_sum += x_error + self.y_error_sum += y_error + x_error_target = x_error * self.p_gain + x_error_diff * self.d_gain + self.x_error_sum * self.i_gain + y_error_target = y_error * self.p_gain + y_error_diff * self.d_gain + self.y_error_sum * self.i_gain + + if self.DEBUG_PRINT: + rospy.loginfo(f"Error: {x_error * 180 / math.pi} | {y_error * 180 / math.pi}") + rospy.loginfo(f"Error diff: {x_error_diff * 180 / math.pi} | {y_error_diff * 180 / math.pi} | {delta_time}") + rospy.loginfo(f"Error sum: {self.x_error_sum * 180 / math.pi} | {self.y_error_sum * 180 / math.pi}") + rospy.loginfo(f"Error target: {x_error_target * 180 / math.pi} | {y_error_target * 180 / math.pi}") + + self.publish_head_joint(x_error_target, y_error_target) + + self.current_face_pan = x_error + self.current_face_tilt = y_error + + self.tracking_status = tracking_status + return tracking_status + + def publish_head_joint(self, pan, tilt): + min_angle = 1 * math.pi / 180 + if abs(pan) < min_angle and abs(tilt) < min_angle: + return + + head_angle_msg = JointState() + head_angle_msg.name = ["head_pan", "head_tilt"] + head_angle_msg.position = [pan, tilt] + + self.head_joint_pub.publish(head_angle_msg) + + def go_init(self): + head_angle_msg = JointState() + head_angle_msg.name = ["head_pan", "head_tilt"] + head_angle_msg.position = [0.0, 0.0] + + self.head_joint_pub.publish(head_angle_msg) + + def scan_face(self): + if not self.use_head_scan: + return + + scan_msg = String() + scan_msg.data = "scan" + + self.head_scan_pub.publish(scan_msg) + + def run(self): + rate = rospy.Rate(30) # 30Hz + while not rospy.is_shutdown(): + self.process_tracking() + rate.sleep() + +if __name__ == '__main__': + try: + tracker = FaceTracker() + tracker.run() + except rospy.ROSInterruptException: + pass diff --git a/humanoid_robot_intelligence_control_system_configure/src/object_follower.py b/humanoid_robot_intelligence_control_system_configure/src/object_follower.py new file mode 100644 index 0000000..87c320a --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/src/object_follower.py @@ -0,0 +1,218 @@ +#!/usr/bin/env python3 + +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +import rospy +import math +from sensor_msgs.msg import JointState +from std_msgs.msg import String +from humanoid_robot_intelligence_control_system_walking_module_msgs.msg import WalkingParam +from humanoid_robot_intelligence_control_system_walking_module_msgs.srv import GetWalkingParam +from geometry_msgs.msg import Point + + +class ObjectFollower: + def __init__(self): + rospy.init_node('object_follower') + + self.FOV_WIDTH = 35.2 * math.pi / 180 + self.FOV_HEIGHT = 21.6 * math.pi / 180 + self.count_not_found = 0 + self.count_to_approach = 0 + self.on_tracking = False + self.approach_object_position = "NotFound" + self.CAMERA_HEIGHT = 0.46 + self.NOT_FOUND_THRESHOLD = 50 + self.MAX_FB_STEP = 40.0 * 0.001 + self.MAX_RL_TURN = 15.0 * math.pi / 180 + self.IN_PLACE_FB_STEP = -3.0 * 0.001 + self.MIN_FB_STEP = 5.0 * 0.001 + self.MIN_RL_TURN = 5.0 * math.pi / 180 + self.UNIT_FB_STEP = 1.0 * 0.001 + self.UNIT_RL_TURN = 0.5 * math.pi / 180 + self.SPOT_FB_OFFSET = 0.0 * 0.001 + self.SPOT_RL_OFFSET = 0.0 * 0.001 + self.SPOT_ANGLE_OFFSET = 0.0 + self.hip_pitch_offset = 7.0 + self.current_pan = -10 + self.current_tilt = -10 + self.current_x_move = 0.005 + self.current_r_angle = 0 + self.curr_period_time = 0.6 + self.accum_period_time = 0.0 + self.DEBUG_PRINT = False + + self.current_joint_states_sub = rospy.Subscriber( + "/humanoid_robot_intelligence_control_system/goal_joint_states", JointState, self.current_joint_states_callback) + self.set_walking_command_pub = rospy.Publisher( + "/humanoid_robot_intelligence_control_system/walking/command", String, queue_size=1) + self.set_walking_param_pub = rospy.Publisher( + "/humanoid_robot_intelligence_control_system/walking/set_params", WalkingParam, queue_size=1) + self.get_walking_param_client = rospy.ServiceProxy( + "/humanoid_robot_intelligence_control_system/walking/get_params", GetWalkingParam) + + # Subscribe to object detection results + self.object_detection_sub = rospy.Subscriber( + "/object_detection_result", Point, self.object_detection_callback) + + self.prev_time = rospy.Time.now() + self.current_walking_param = WalkingParam() + + def start_following(self): + self.on_tracking = True + rospy.loginfo("Start Object following") + self.set_walking_command("start") + result = self.get_walking_param() + if result: + self.hip_pitch_offset = self.current_walking_param.hip_pitch_offset + self.curr_period_time = self.current_walking_param.period_time + else: + self.hip_pitch_offset = 7.0 * math.pi / 180 + self.curr_period_time = 0.6 + + def stop_following(self): + self.on_tracking = False + self.count_to_approach = 0 + rospy.loginfo("Stop Object following") + self.set_walking_command("stop") + + def current_joint_states_callback(self, msg): + for i, name in enumerate(msg.name): + if name == "head_pan": + self.current_pan = msg.position[i] + elif name == "head_tilt": + self.current_tilt = msg.position[i] + + def calc_footstep(self, target_distance, target_angle, delta_time): + next_movement = self.current_x_move + target_distance = max(0, target_distance) + fb_goal = min(target_distance * 0.1, self.MAX_FB_STEP) + self.accum_period_time += delta_time + if self.accum_period_time > (self.curr_period_time / 4): + self.accum_period_time = 0.0 + if (target_distance * 0.1 / 2) < self.current_x_move: + next_movement -= self.UNIT_FB_STEP + else: + next_movement += self.UNIT_FB_STEP + fb_goal = min(next_movement, fb_goal) + fb_move = max(fb_goal, self.MIN_FB_STEP) + + rl_goal = 0.0 + if abs(target_angle) * 180 / math.pi > 5.0: + rl_offset = abs(target_angle) * 0.2 + rl_goal = min(rl_offset, self.MAX_RL_TURN) + rl_goal = max(rl_goal, self.MIN_RL_TURN) + rl_angle = min(abs(self.current_r_angle) + self.UNIT_RL_TURN, rl_goal) + if target_angle < 0: + rl_angle *= -1 + else: + rl_angle = 0 + + return fb_move, rl_angle + + def process_following(self, x_angle, y_angle, object_size): + curr_time = rospy.Time.now() + delta_time = (curr_time - self.prev_time).to_sec() + self.prev_time = curr_time + + self.count_not_found = 0 + + if self.current_tilt == -10 and self.current_pan == -10: + rospy.logerr("Failed to get current angle of head joints.") + self.set_walking_command("stop") + self.on_tracking = False + self.approach_object_position = "NotFound" + return False + + self.approach_object_position = "OutOfRange" + + distance_to_object = self.CAMERA_HEIGHT * math.tan(math.pi * 0.5 + self.current_tilt - self.hip_pitch_offset - object_size) + distance_to_object = abs(distance_to_object) + + distance_to_approach = 0.22 + + if (distance_to_object < distance_to_approach) and (abs(x_angle) < 25.0): + self.count_to_approach += 1 + if self.count_to_approach > 20: + self.set_walking_command("stop") + self.on_tracking = False + self.approach_object_position = "OnLeft" if x_angle > 0 else "OnRight" + return True + elif self.count_to_approach > 15: + self.set_walking_param(self.IN_PLACE_FB_STEP, 0, 0) + return False + else: + self.count_to_approach = 0 + + distance_to_walk = distance_to_object - distance_to_approach + fb_move, rl_angle = self.calc_footstep(distance_to_walk, self.current_pan, delta_time) + self.set_walking_param(fb_move, 0, rl_angle) + return False + + def decide_object_position(self, x_angle, y_angle): + if self.current_tilt == -10 and self.current_pan == -10: + self.approach_object_position = "NotFound" + return + object_x_angle = self.current_pan + x_angle + self.approach_object_position = "OnLeft" if object_x_angle > 0 else "OnRight" + + def wait_following(self): + self.count_not_found += 1 + if self.count_not_found > self.NOT_FOUND_THRESHOLD * 0.5: + self.set_walking_param(0.0, 0.0, 0.0) + + def set_walking_command(self, command): + if command == "start": + self.get_walking_param() + self.set_walking_param(self.IN_PLACE_FB_STEP, 0, 0, True) + msg = String() + msg.data = command + self.set_walking_command_pub.publish(msg) + + def set_walking_param(self, x_move, y_move, rotation_angle, balance=False): + self.current_walking_param.balance_enable = balance + self.current_walking_param.x_move_amplitude = x_move + self.SPOT_FB_OFFSET + self.current_walking_param.y_move_amplitude = y_move + self.SPOT_RL_OFFSET + self.current_walking_param.angle_move_amplitude = rotation_angle + self.SPOT_ANGLE_OFFSET + self.set_walking_param_pub.publish(self.current_walking_param) + self.current_x_move = x_move + self.current_r_angle = rotation_angle + + def get_walking_param(self): + try: + response = self.get_walking_param_client() + self.current_walking_param = response.parameters + return True + except rospy.ServiceException as e: + rospy.logerr("Failed to get walking parameters: %s" % e) + return False + + def object_detection_callback(self, msg): + if self.on_tracking: + x_angle = msg.x + y_angle = msg.y + object_size = msg.z + self.process_following(x_angle, y_angle, object_size) + else: + self.wait_following() + +if __name__ == '__main__': + try: + follower = ObjectFollower() + follower.start_following() + rospy.spin() + except rospy.ROSInterruptException: + pass diff --git a/humanoid_robot_intelligence_control_system_configure/src/object_tracker.py b/humanoid_robot_intelligence_control_system_configure/src/object_tracker.py new file mode 100644 index 0000000..2d54fba --- /dev/null +++ b/humanoid_robot_intelligence_control_system_configure/src/object_tracker.py @@ -0,0 +1,194 @@ +#!/usr/bin/env python3 + +# Copyright (C) 2024 Bellande Robotics Sensors Research Innovation Center, Ronaldson Bellande +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +import rospy +import math +from sensor_msgs.msg import JointState +from std_msgs.msg import String, Float64MultiArray +from humanoid_robot_intelligence_control_system_ball_detector.msg import CircleSetStamped +from geometry_msgs.msg import Point + +class ObjectTracker: + def __init__(self): + rospy.init_node('object_tracker') + + self.FOV_WIDTH = 35.2 * math.pi / 180 + self.FOV_HEIGHT = 21.6 * math.pi / 180 + self.NOT_FOUND_THRESHOLD = 50 + self.WAITING_THRESHOLD = 5 + self.use_head_scan = True + self.count_not_found = 0 + self.on_tracking = False + self.current_object_pan = 0 + self.current_object_tilt = 0 + self.x_error_sum = 0 + self.y_error_sum = 0 + self.current_object_bottom = 0 + self.tracking_status = "NotFound" + self.DEBUG_PRINT = False + + param_nh = rospy.get_param("~") + self.p_gain = param_nh.get("p_gain", 0.4) + self.i_gain = param_nh.get("i_gain", 0.0) + self.d_gain = param_nh.get("d_gain", 0.0) + + rospy.loginfo(f"Object tracking Gain : {self.p_gain}, {self.i_gain}, {self.d_gain}") + + self.head_joint_offset_pub = rospy.Publisher( + "/humanoid_robot_intelligence_control_system/head_control/set_joint_states_offset", JointState, queue_size=0) + self.head_joint_pub = rospy.Publisher( + "/humanoid_robot_intelligence_control_system/head_control/set_joint_states", JointState, queue_size=0) + self.head_scan_pub = rospy.Publisher( + "/humanoid_robot_intelligence_control_system/head_control/scan_command", String, queue_size=0) + + self.object_position_sub = rospy.Subscriber( + "/object_detector_node/object_position", Point, self.object_position_callback) + self.object_tracking_command_sub = rospy.Subscriber( + "/object_tracker/command", String, self.object_tracker_command_callback) + + self.object_position = Point() + self.prev_time = rospy.Time.now() + + def object_position_callback(self, msg): + self.object_position = msg + + def object_tracker_command_callback(self, msg): + if msg.data == "start": + self.start_tracking() + elif msg.data == "stop": + self.stop_tracking() + elif msg.data == "toggle_start": + if not self.on_tracking: + self.start_tracking() + else: + self.stop_tracking() + + def start_tracking(self): + self.on_tracking = True + rospy.loginfo("Start Object tracking") if self.DEBUG_PRINT else None + + def stop_tracking(self): + self.go_init() + self.on_tracking = False + rospy.loginfo("Stop Object tracking") if self.DEBUG_PRINT else None + self.current_object_pan = 0 + self.current_object_tilt = 0 + self.x_error_sum = 0 + self.y_error_sum = 0 + + def set_using_head_scan(self, use_scan): + self.use_head_scan = use_scan + + def process_tracking(self): + if not self.on_tracking: + self.object_position.z = 0 + self.count_not_found = 0 + return "NotFound" + + if self.object_position.z <= 0: + self.count_not_found += 1 + if self.count_not_found < self.WAITING_THRESHOLD: + if self.tracking_status in ["Found", "Waiting"]: + tracking_status = "Waiting" + else: + tracking_status = "NotFound" + elif self.count_not_found > self.NOT_FOUND_THRESHOLD: + self.scan_object() + self.count_not_found = 0 + tracking_status = "NotFound" + else: + tracking_status = "NotFound" + else: + self.count_not_found = 0 + tracking_status = "Found" + + if tracking_status != "Found": + self.tracking_status = tracking_status + self.current_object_pan = 0 + self.current_object_tilt = 0 + self.x_error_sum = 0 + self.y_error_sum = 0 + return tracking_status + + x_error = -math.atan(self.object_position.x * math.tan(self.FOV_WIDTH)) + y_error = -math.atan(self.object_position.y * math.tan(self.FOV_HEIGHT)) + object_size = self.object_position.z + + curr_time = rospy.Time.now() + delta_time = (curr_time - self.prev_time).to_sec() + self.prev_time = curr_time + + x_error_diff = (x_error - self.current_object_pan) / delta_time + y_error_diff = (y_error - self.current_object_tilt) / delta_time + self.x_error_sum += x_error + self.y_error_sum += y_error + x_error_target = x_error * self.p_gain + x_error_diff * self.d_gain + self.x_error_sum * self.i_gain + y_error_target = y_error * self.p_gain + y_error_diff * self.d_gain + self.y_error_sum * self.i_gain + + if self.DEBUG_PRINT: + rospy.loginfo(f"Error: {x_error * 180 / math.pi} | {y_error * 180 / math.pi}") + rospy.loginfo(f"Error diff: {x_error_diff * 180 / math.pi} | {y_error_diff * 180 / math.pi} | {delta_time}") + rospy.loginfo(f"Error sum: {self.x_error_sum * 180 / math.pi} | {self.y_error_sum * 180 / math.pi}") + rospy.loginfo(f"Error target: {x_error_target * 180 / math.pi} | {y_error_target * 180 / math.pi}") + + self.publish_head_joint(x_error_target, y_error_target) + + self.current_object_pan = x_error + self.current_object_tilt = y_error + self.current_object_bottom = object_size + + self.object_position.z = 0 + + self.tracking_status = tracking_status + return tracking_status + + def publish_head_joint(self, pan, tilt): + min_angle = 1 * math.pi / 180 + if abs(pan) < min_angle and abs(tilt) < min_angle: + return + + head_angle_msg = JointState() + head_angle_msg.name = ["head_pan", "head_tilt"] + head_angle_msg.position = [pan, tilt] + + self.head_joint_offset_pub.publish(head_angle_msg) + + def go_init(self): + head_angle_msg = JointState() + head_angle_msg.name = ["head_pan", "head_tilt"] + head_angle_msg.position = [0.0, 0.0] + + self.head_joint_pub.publish(head_angle_msg) + + def scan_object(self): + if not self.use_head_scan: + return + + scan_msg = String() + scan_msg.data = "scan" + + self.head_scan_pub.publish(scan_msg) + +if __name__ == '__main__': + try: + tracker = ObjectTracker() + rate = rospy.Rate(30) + while not rospy.is_shutdown(): + tracker.process_tracking() + rate.sleep() + except rospy.ROSInterruptException: + pass