From e18c589c536e6e6496e3bb0667f1d695a4078e73 Mon Sep 17 00:00:00 2001 From: miyamichi Date: Wed, 12 Apr 2023 17:28:30 +0900 Subject: [PATCH 01/17] add spot_human_recognition demo_code --- 202304_human_approach/#hoge.py# | 1 + 202304_human_approach/merge.py | 22 ++++++++++++++++++++++ 202304_human_approach/spot_object_recog.l | 12 ++++++++++++ 3 files changed, 35 insertions(+) create mode 100644 202304_human_approach/#hoge.py# create mode 100644 202304_human_approach/merge.py create mode 100755 202304_human_approach/spot_object_recog.l diff --git a/202304_human_approach/#hoge.py# b/202304_human_approach/#hoge.py# new file mode 100644 index 0000000000..c6d626987f --- /dev/null +++ b/202304_human_approach/#hoge.py# @@ -0,0 +1 @@ +# import numpy as np \ No newline at end of file diff --git a/202304_human_approach/merge.py b/202304_human_approach/merge.py new file mode 100644 index 0000000000..9307541186 --- /dev/null +++ b/202304_human_approach/merge.py @@ -0,0 +1,22 @@ +import rospy +import message_filters +from jsk_recognition_msgs.msg import ClassificationResult +from jsk_recognition_msgs.msg import RectArray +rospy.init_node('miyamichi') +pub = rospy.Publisher('human', RectArray, queue_size = 4) + +def callback(rects,classes): + msg = RectArray() + if "person" in classes.label_names: + for i, label_name in enumerate(classes.label_names): + if label_name == "person": + msg.rects.append(rects.rects[i]) + msg.header = rects.header + pub.publish(msg) + +Rect_sub = message_filters.Subscriber('/edgetpu_panorama_object_detector/output/rects', RectArray) +Class_sub = message_filters.Subscriber('/edgetpu_panorama_object_detector/output/class', ClassificationResult) + +ts = message_filters.TimeSynchronizer([Rect_sub, Class_sub], 10) +ts.registerCallback(callback) +rospy.spin() diff --git a/202304_human_approach/spot_object_recog.l b/202304_human_approach/spot_object_recog.l new file mode 100755 index 0000000000..eeb3dffbf5 --- /dev/null +++ b/202304_human_approach/spot_object_recog.l @@ -0,0 +1,12 @@ +#!/usr/bin/env roseus + +(ros::load-ros-package "jsk_recognition_msgs") +(ros::roseus "test") + +(defun cb (msg) + (if (not (= (length (send msg :rects)) 0)) + (print (send (car (send msg :rects)) :x)))) + ;;(print (send (car (send msg :rects)) :y)))) + +(ros::subscribe "/human" jsk_recognition_msgs::RectArray #'cb) +(ros::spin) From 4ae1855d78a42f349a7bdfc6e12074bcaf5b7cc8 Mon Sep 17 00:00:00 2001 From: miyamichi Date: Wed, 12 Apr 2023 20:48:32 +0900 Subject: [PATCH 02/17] modified --- 202304_human_approach/spot_object_recog.l | 40 +++++++++++++++++++++-- 1 file changed, 37 insertions(+), 3 deletions(-) diff --git a/202304_human_approach/spot_object_recog.l b/202304_human_approach/spot_object_recog.l index eeb3dffbf5..924da9b155 100755 --- a/202304_human_approach/spot_object_recog.l +++ b/202304_human_approach/spot_object_recog.l @@ -4,9 +4,43 @@ (ros::roseus "test") (defun cb (msg) - (if (not (= (length (send msg :rects)) 0)) - (print (send (car (send msg :rects)) :x)))) - ;;(print (send (car (send msg :rects)) :y)))) + (let (rect-list sorted-list max-rect pu pv px py) + (setq rect-list (send msg :rects)) + (if (not (= (length rect-list) 0)) + (progn + (setq sorted-list (sort rect-list #'compare-area-of-rects)) + (setq max-rect (car sorted-list)) + (setq pu (+ (send max-rect :x) (/ (send max-rect :width) 2))) + (setq pv (+ (send max-rect :y) (/ (send max-rect :height) 2))) + (setq px (convert-x pu)) + (setq py (convert-y pv)) + (dolist (x sorted-list) + (progn + (print (area-of-rects x)) + (print px) + (print py) + )) + (print "done") + ) + ) + ) + ) +;;(print (sen (car (send msg :rects)) :y)))) +(defun area-of-rects (x) + (* (send x :width) (send x :height)) + ) +(defun compare-area-of-rects (a b) + (>= (* (send a :width) (send a :height)) (* (send b :width) (send b :height)))) + +(defun convert-x (u) + (- u 2000) + ) +(defun convert-y (v) + (+ (* -1 v) 1000) + ) + + + (ros::subscribe "/human" jsk_recognition_msgs::RectArray #'cb) (ros::spin) From a94c487f13b8f72066dd98d6003a1167297a67b3 Mon Sep 17 00:00:00 2001 From: miyamichi Date: Thu, 13 Apr 2023 13:40:12 +0900 Subject: [PATCH 03/17] modified --- 202304_human_approach/spot_object_recog.l | 38 ++++++++++++++++++----- 1 file changed, 30 insertions(+), 8 deletions(-) diff --git a/202304_human_approach/spot_object_recog.l b/202304_human_approach/spot_object_recog.l index 924da9b155..706fabd0c5 100755 --- a/202304_human_approach/spot_object_recog.l +++ b/202304_human_approach/spot_object_recog.l @@ -1,9 +1,15 @@ #!/usr/bin/env roseus (ros::load-ros-package "jsk_recognition_msgs") + +(load "package://spoteus/spot-interface.l") +(spot-init) + (ros::roseus "test") -(defun cb (msg) + + +(defun move-to-human (msg) (let (rect-list sorted-list max-rect pu pv px py) (setq rect-list (send msg :rects)) (if (not (= (length rect-list) 0)) @@ -14,17 +20,31 @@ (setq pv (+ (send max-rect :y) (/ (send max-rect :height) 2))) (setq px (convert-x pu)) (setq py (convert-y pv)) - (dolist (x sorted-list) - (progn - (print (area-of-rects x)) - (print px) - (print py) - )) + (setq *angle* (* (* -1.0 px) (/ 180.0 2000.0))) + (print *angle*) + (send *ri* :go-pos 0 0 *angle*) + (send *ri* :go-pos 0.8 0 0) + ;;(while (<= (area-of-rects max-rect) 80000) + ;;(send *ri* :go-pos 0.5 0 0) + ;;) + (send *ri* :speak-jp "どちらにいきますか?") + ;;(if (>= (area-of-rects max-rect) 80000) + ;;(send *ri* :go-pos 0 0 0) + ;;) + ;;(dolist (x sorted-list) + ;;(progn + ;;(print (area-of-rects x)) + ;;(print px) + ;;(print py) + ;;(send *ri* :go-pos 0 0 (* (* -1.0 px) (/ 180.0 2000.0))) + ;;)) (print "done") ) + ) ) ) + ;;(print (sen (car (send msg :rects)) :y)))) (defun area-of-rects (x) (* (send x :width) (send x :height)) @@ -40,7 +60,9 @@ ) +(setq *human* (one-shot-subscribe "human" jsk_recognition_msgs::RectArray)) +(move-to-human *human*) -(ros::subscribe "/human" jsk_recognition_msgs::RectArray #'cb) +;; (ros::subscribe "/human" jsk_recognition_msgs::RectArray #'cb) (ros::spin) From 6b5fbdada3589177ed9940ba721c57468553f4af Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Thu, 13 Apr 2023 15:24:01 +0900 Subject: [PATCH 04/17] rework --- 202304_human_approach/#hoge.py# | 1 - jsk_2023_04_human_approach/CMakeLists.txt | 202 ++++++++++++++++++ .../euslisp}/spot_object_recog.l | 0 .../launch/recognition_remote.launch | 41 ++++ jsk_2023_04_human_approach/package.xml | 59 +++++ .../python}/merge.py | 0 6 files changed, 302 insertions(+), 1 deletion(-) delete mode 100644 202304_human_approach/#hoge.py# create mode 100644 jsk_2023_04_human_approach/CMakeLists.txt rename {202304_human_approach => jsk_2023_04_human_approach/euslisp}/spot_object_recog.l (100%) create mode 100644 jsk_2023_04_human_approach/launch/recognition_remote.launch create mode 100644 jsk_2023_04_human_approach/package.xml rename {202304_human_approach => jsk_2023_04_human_approach/python}/merge.py (100%) mode change 100644 => 100755 diff --git a/202304_human_approach/#hoge.py# b/202304_human_approach/#hoge.py# deleted file mode 100644 index c6d626987f..0000000000 --- a/202304_human_approach/#hoge.py# +++ /dev/null @@ -1 +0,0 @@ -# import numpy as np \ No newline at end of file diff --git a/jsk_2023_04_human_approach/CMakeLists.txt b/jsk_2023_04_human_approach/CMakeLists.txt new file mode 100644 index 0000000000..1aafa6224a --- /dev/null +++ b/jsk_2023_04_human_approach/CMakeLists.txt @@ -0,0 +1,202 @@ +cmake_minimum_required(VERSION 3.0.2) +project(jsk_2023_04_human_approach) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES 202304_human_approach +# CATKIN_DEPENDS other_catkin_pkg +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include +# ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/202304_human_approach.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/202304_human_approach_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_202304_human_approach.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/202304_human_approach/spot_object_recog.l b/jsk_2023_04_human_approach/euslisp/spot_object_recog.l similarity index 100% rename from 202304_human_approach/spot_object_recog.l rename to jsk_2023_04_human_approach/euslisp/spot_object_recog.l diff --git a/jsk_2023_04_human_approach/launch/recognition_remote.launch b/jsk_2023_04_human_approach/launch/recognition_remote.launch new file mode 100644 index 0000000000..327454db49 --- /dev/null +++ b/jsk_2023_04_human_approach/launch/recognition_remote.launch @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + frame_fixed: "camera" + image_transport: compressed + dimensions_labels: + person: [0.5, 0.5, 1.5] + + + + + + + + diff --git a/jsk_2023_04_human_approach/package.xml b/jsk_2023_04_human_approach/package.xml new file mode 100644 index 0000000000..116c19860a --- /dev/null +++ b/jsk_2023_04_human_approach/package.xml @@ -0,0 +1,59 @@ + + + jsk_2023_04_human_approach + 0.0.0 + The 202304_human_approach package + + + + + obinata + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + + + + + + + + diff --git a/202304_human_approach/merge.py b/jsk_2023_04_human_approach/python/merge.py old mode 100644 new mode 100755 similarity index 100% rename from 202304_human_approach/merge.py rename to jsk_2023_04_human_approach/python/merge.py From 88cc6b90ff9fb05140bc8ef01c0f0813bc013656 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Thu, 13 Apr 2023 16:34:59 +0900 Subject: [PATCH 05/17] update recognition launch. expected launch in spot PC --- ...ecognition_remote.launch => recognition.launch} | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) rename jsk_2023_04_human_approach/launch/{recognition_remote.launch => recognition.launch} (79%) diff --git a/jsk_2023_04_human_approach/launch/recognition_remote.launch b/jsk_2023_04_human_approach/launch/recognition.launch similarity index 79% rename from jsk_2023_04_human_approach/launch/recognition_remote.launch rename to jsk_2023_04_human_approach/launch/recognition.launch index 327454db49..1935a87323 100644 --- a/jsk_2023_04_human_approach/launch/recognition_remote.launch +++ b/jsk_2023_04_human_approach/launch/recognition.launch @@ -5,15 +5,15 @@ + - + - - - - - + + + + @@ -27,7 +27,7 @@ - frame_fixed: "camera" + frame_fixed: "rear_rail" image_transport: compressed dimensions_labels: person: [0.5, 0.5, 1.5] From 21ceaecdbe9ac375778a4c8807d321cf734aeb28 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Fri, 14 Apr 2023 11:09:33 +0900 Subject: [PATCH 06/17] detect handpose --- .../launch/recognition.launch | 27 ++++++++++++++++--- 1 file changed, 23 insertions(+), 4 deletions(-) diff --git a/jsk_2023_04_human_approach/launch/recognition.launch b/jsk_2023_04_human_approach/launch/recognition.launch index 1935a87323..f7bf6ad5df 100644 --- a/jsk_2023_04_human_approach/launch/recognition.launch +++ b/jsk_2023_04_human_approach/launch/recognition.launch @@ -8,13 +8,17 @@ - + + + + + @@ -34,8 +38,23 @@ - - - + + + + + + + + + + + + + + + + + From dfc2352aa6dd9f284b59eebbe1be885d08916f6f Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Fri, 14 Apr 2023 11:13:08 +0900 Subject: [PATCH 07/17] add rviz --- .../config/miyamichi.rviz | 756 ++++++++++++++++++ jsk_2023_04_human_approach/launch/rviz.launch | 5 + 2 files changed, 761 insertions(+) create mode 100644 jsk_2023_04_human_approach/config/miyamichi.rviz create mode 100644 jsk_2023_04_human_approach/launch/rviz.launch diff --git a/jsk_2023_04_human_approach/config/miyamichi.rviz b/jsk_2023_04_human_approach/config/miyamichi.rviz new file mode 100644 index 0000000000..e774b9b887 --- /dev/null +++ b/jsk_2023_04_human_approach/config/miyamichi.rviz @@ -0,0 +1,756 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /TF1/Frames1 + - /DepthClouds1/FrontLeftDepthCloud1/Autocompute Value Bounds1 + - /DepthClouds1/FrontRightDepthCloud1/Autocompute Value Bounds1 + - /DepthClouds1/LeftDepthCloud1/Autocompute Value Bounds1 + - /DepthClouds1/RightDepthCloud1/Autocompute Value Bounds1 + - /DepthClouds1/RearDepthCloud1/Autocompute Value Bounds1 + - /HandPoseArray1/Status1 + - /DepthCloud1/Auto Size1 + Splitter Ratio: 0.5465393662452698 + Tree Height: 2054 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + - /Current View1/Focal Point1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Name: Time + SyncMode: 0 + SyncSource: DepthCloud +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + arm0.link_el0: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm0.link_el1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm0.link_fngr: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm0.link_hr0: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm0.link_sh0: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm0.link_sh1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm0.link_wr0: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + arm0.link_wr1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + body: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_left_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_left_lower_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_left_upper_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_rail: + Alpha: 1 + Show Axes: false + Show Trail: false + front_right_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_right_lower_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_right_upper_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_left_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_left_lower_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_left_upper_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_rail: + Alpha: 1 + Show Axes: false + Show Trail: false + rear_right_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_right_lower_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + rear_right_upper_leg: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: false + arm0.link_el0: + Value: false + arm0.link_el1: + Value: false + arm0.link_fngr: + Value: false + arm0.link_hr0: + Value: false + arm0.link_sh0: + Value: false + arm0.link_sh1: + Value: false + arm0.link_wr0: + Value: false + arm0.link_wr1: + Value: false + back: + Value: false + back_fisheye: + Value: false + base_link: + Value: false + body: + Value: false + flat_body: + Value: false + front_left_hip: + Value: false + front_left_lower_leg: + Value: false + front_left_upper_leg: + Value: false + front_rail: + Value: false + front_right_hip: + Value: false + front_right_lower_leg: + Value: false + front_right_upper_leg: + Value: false + frontleft: + Value: false + frontleft_fisheye: + Value: false + frontright: + Value: false + frontright_fisheye: + Value: false + gpe: + Value: false + hand: + Value: false + hand_color_image_sensor: + Value: true + hand_depth_sensor: + Value: false + head: + Value: false + insta360_link: + Value: false + left: + Value: false + left_fisheye: + Value: false + link_wr1: + Value: false + odom: + Value: false + rear_left_hip: + Value: false + rear_left_lower_leg: + Value: false + rear_left_upper_leg: + Value: false + rear_rail: + Value: true + rear_right_hip: + Value: false + rear_right_lower_leg: + Value: false + rear_right_upper_leg: + Value: false + right: + Value: false + right_fisheye: + Value: false + vision: + Value: false + Marker Alpha: 1 + Marker Scale: 0.75 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + vision: + body: + arm0.link_sh0: + arm0.link_sh1: + arm0.link_hr0: + arm0.link_el0: + arm0.link_el1: + arm0.link_wr0: + arm0.link_wr1: + arm0.link_fngr: + {} + hand_color_image_sensor: + {} + hand_depth_sensor: + {} + base_link: + {} + flat_body: + {} + front_left_hip: + front_left_upper_leg: + front_left_lower_leg: + {} + front_rail: + {} + front_right_hip: + front_right_upper_leg: + front_right_lower_leg: + {} + hand: + {} + head: + back: + back_fisheye: + {} + frontleft: + frontleft_fisheye: + {} + frontright: + frontright_fisheye: + {} + left: + left_fisheye: + {} + right: + right_fisheye: + {} + link_wr1: + {} + odom: + gpe: + {} + rear_left_hip: + rear_left_upper_leg: + rear_left_lower_leg: + {} + rear_rail: + insta360_link: + {} + rear_right_hip: + rear_right_upper_leg: + rear_right_lower_leg: + {} + Update Interval: 0 + Value: true + - Class: rviz/Group + Displays: + - Alpha: 1 + Auto Size: + Auto Size Factor: 1 + Value: true + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 11.731683731079102 + Min Value: 7.7589921951293945 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: "" + Color Transformer: AxisColor + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /spot/depth/frontleft/image + Depth Map Transport Hint: raw + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: FrontLeftDepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 5 + Selectable: true + Size (Pixels): 3 + Style: Flat Squares + Topic Filter: true + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Auto Size: + Auto Size Factor: 1 + Value: true + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10.185791015625 + Min Value: 7.813115119934082 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: "" + Color Transformer: AxisColor + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /spot/depth/frontright/image + Depth Map Transport Hint: raw + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: FrontRightDepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 5 + Selectable: true + Size (Pixels): 3 + Style: Flat Squares + Topic Filter: true + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Auto Size: + Auto Size Factor: 1 + Value: true + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 8.268538475036621 + Min Value: 7.727081775665283 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: "" + Color Transformer: AxisColor + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /spot/depth/left/image + Depth Map Transport Hint: raw + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LeftDepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 5 + Selectable: true + Size (Pixels): 3 + Style: Flat Squares + Topic Filter: true + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Auto Size: + Auto Size Factor: 1 + Value: true + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 8.739740371704102 + Min Value: 7.83408784866333 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: "" + Color Transformer: AxisColor + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /spot/depth/right/image + Depth Map Transport Hint: raw + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: RightDepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 5 + Selectable: true + Size (Pixels): 3 + Style: Flat Squares + Topic Filter: true + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Auto Size: + Auto Size Factor: 1 + Value: true + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 8.420552253723145 + Min Value: 6.867978572845459 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: "" + Color Transformer: AxisColor + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /spot/depth/back/image + Depth Map Transport Hint: raw + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: RearDepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 5 + Selectable: true + Size (Pixels): 3 + Style: Flat Squares + Topic Filter: true + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: false + Name: DepthClouds + - Class: jsk_rviz_plugin/OverlayImage + Enabled: true + Name: PanoramaImage + Topic: /dual_fisheye_to_panorama/output + Value: true + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 0 + overwrite alpha value: false + top: 0 + transport hint: compressed + width: 700 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: false + Name: PanoramaDetection + Topic: /spot_recognition/object_detection_image + Value: false + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 0 + overwrite alpha value: false + top: 0 + transport hint: raw + width: 700 + - Class: jsk_rviz_plugin/TFTrajectory + Enabled: true + Name: BodyTrajectory + Value: true + color: 25; 255; 240 + duration: 1000 + frame: base_link + line_width: 0.009999999776482582 + - Class: jsk_rviz_plugin/PieChart + Enabled: true + Name: SpotBattery + Topic: /spot/status/battery_percentage + Value: true + auto color change: false + background color: 0; 0; 0 + backround alpha: 0 + clockwise rotate direction: false + foreground alpha: 0.699999988079071 + foreground alpha 2: 0.4000000059604645 + foreground color: 25; 255; 240 + left: 750 + max color: 255; 0; 0 + max color change threthold: 0 + max value: 100 + med color: 255; 0; 0 + med color change threthold: 0 + min value: 0 + show caption: true + size: 128 + text size: 10 + top: 50 + - Class: jsk_rviz_plugin/PieChart + Enabled: true + Name: LaptopBattery + Topic: /spot/status/laptop_battery_percentage + Value: true + auto color change: false + background color: 0; 0; 0 + backround alpha: 0 + clockwise rotate direction: false + foreground alpha: 0.699999988079071 + foreground alpha 2: 0.4000000059604645 + foreground color: 25; 255; 240 + left: 900 + max color: 255; 0; 0 + max color change threthold: 0 + max value: 100 + med color: 255; 0; 0 + med color change threthold: 0 + min value: 0 + show caption: true + size: 128 + text size: 10 + top: 50 + - Class: jsk_rviz_plugin/BoundingBoxArray + Enabled: false + Name: DetectedObjects + Queue Size: 10 + Topic: /spot_recognition/bbox_array + Unreliable: false + Value: false + alpha: 0.800000011920929 + color: 25; 255; 0 + coloring: Label + line width: 0.05000000074505806 + only edge: true + show coords: false + - Class: jsk_rviz_plugin/BoundingBoxArray + Enabled: true + Name: HumanPos + Queue Size: 10 + Topic: /rect_array_in_panorama_to_bounding_box_array/bbox_array + Unreliable: false + Value: true + alpha: 0.800000011920929 + color: 25; 255; 0 + coloring: Auto + line width: 0.004999999888241291 + only edge: false + show coords: false + - Class: jsk_rviz_plugin/HumanSkeletonArray + Enabled: true + Name: HandPoseArray + Queue Size: 10 + Topic: /hand_pose_estimation_2d/skeleton + Unreliable: false + Value: true + alpha: 1 + color: 25; 255; 0 + coloring: Auto + line width: 0.004999999888241291 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: true + Name: OverlayImage + Topic: /hand_pose_estimation_2d/output/vis + Value: true + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 25 + overwrite alpha value: false + top: 375 + transport hint: raw + width: 400 + - Alpha: 1 + Auto Size: + Auto Size Factor: 1 + Value: true + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/DepthCloud + Color: 255; 255; 255 + Color Image Topic: "" + Color Transformer: RGB8 + Color Transport Hint: raw + Decay Time: 0 + Depth Map Topic: /spot/camera/hand_depth/depth_registered/image + Depth Map Transport Hint: raw + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: DepthCloud + Occlusion Compensation: + Occlusion Time-Out: 30 + Value: false + Position Transformer: XYZ + Queue Size: 5 + Selectable: true + Size (Pixels): 3 + Style: Flat Squares + Topic Filter: false + Use Fixed Frame: true + Use rainbow: true + Value: false + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: odom + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 13.387189865112305 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: 4.6255669593811035 + Y: -0.2518952488899231 + Z: -4.357930660247803 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.759796679019928 + Target Frame: base_link + Yaw: 3.1918535232543945 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 2432 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 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 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 4096 + X: 0 + Y: 54 diff --git a/jsk_2023_04_human_approach/launch/rviz.launch b/jsk_2023_04_human_approach/launch/rviz.launch new file mode 100644 index 0000000000..62afa4a906 --- /dev/null +++ b/jsk_2023_04_human_approach/launch/rviz.launch @@ -0,0 +1,5 @@ + + + + From bdfa47532730502077ccc8eecb7dd47e35a5fd24 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Mon, 17 Apr 2023 16:50:25 +0900 Subject: [PATCH 08/17] update rosinstall --- jsk_2023_04_human_approach/rosinstall | 14 ++++++++++++++ 1 file changed, 14 insertions(+) create mode 100644 jsk_2023_04_human_approach/rosinstall diff --git a/jsk_2023_04_human_approach/rosinstall b/jsk_2023_04_human_approach/rosinstall new file mode 100644 index 0000000000..4a9fc251bc --- /dev/null +++ b/jsk_2023_04_human_approach/rosinstall @@ -0,0 +1,14 @@ +- git: +# It can be checked out to origin/master after https://github.com/jsk-ros-pkg/coral_usb_ros/pull/130 has been merged + local-name: coral_usb_ros + uri: https://github.com/mqcmd196/coral_usb_ros.git + version: PR/publish_skel +- git: + local-name: jsk_demos + uri: git@github.com:heissereal/jsk_demos.git + version: master +- git: +# It can be checked out to origin/master after https://github.com/jsk-ros-pkg/jsk_recognition/pull/2769 has been merged + local-name: jsk_recognition + uri: https://github.com/iory/jsk_recognition.git + version: skeleton-with-depth From d13a9cef1c77599d45f675d0e648f6ee242a37c8 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Mon, 17 Apr 2023 17:25:31 +0900 Subject: [PATCH 09/17] add human pose launch with depth --- .../launch/recognition.launch | 27 +++++++++++-------- 1 file changed, 16 insertions(+), 11 deletions(-) diff --git a/jsk_2023_04_human_approach/launch/recognition.launch b/jsk_2023_04_human_approach/launch/recognition.launch index f7bf6ad5df..2164af3800 100644 --- a/jsk_2023_04_human_approach/launch/recognition.launch +++ b/jsk_2023_04_human_approach/launch/recognition.launch @@ -19,10 +19,6 @@ - - - - @@ -39,7 +35,7 @@ - + @@ -49,12 +45,21 @@ - - - - - - + + + + + + + + + + + + + From 97c6deae47dd036989dc31fe374163f790b2aa59 Mon Sep 17 00:00:00 2001 From: miyamichi Date: Tue, 18 Apr 2023 11:15:58 +0900 Subject: [PATCH 10/17] recognition bones --- .../euslisp/human_recog.l | 93 +++++++++++++++++++ 1 file changed, 93 insertions(+) create mode 100755 jsk_2023_04_human_approach/euslisp/human_recog.l diff --git a/jsk_2023_04_human_approach/euslisp/human_recog.l b/jsk_2023_04_human_approach/euslisp/human_recog.l new file mode 100755 index 0000000000..030c1fa10f --- /dev/null +++ b/jsk_2023_04_human_approach/euslisp/human_recog.l @@ -0,0 +1,93 @@ +#!/usr/bin/env roseus + +(ros::load-ros-package "jsk_recognition_msgs") +(load "package://spoteus/spot-interface.l") +(spot-init) +(ros::roseus "human_recog") + +(defun move-to-human (msg) + (let (rect-list distance max-rect x y) + (setq rect-list (send msg :boxes)) + (if (not (= (length rect-list) 0)) + (progn + (print "data-start") + (setq sorted-list (sort rect-list #'compare-distance-of-rects)) + (setq max-rect (car sorted-list)) + (setq x (send (send (send max-rect :pose) :position) :x)) + (setq y (send (send (send max-rect :pose) :position) :y)) + (setq *angle* (rad2deg (atan y x))) + ;; (print *angle*) + (send *ri* :go-pos 0 0 *angle*) + (send *ri* :go-pos 0.5 0 0) + (send *ri* :speak-jp "おつかれさま") + (print "done") + ) + ) + ) + ) + + + +(defun recognition-skeleton (msgs) + (setq *physical-order* (list 'right shoulder->right elbow 'right elbow->right wrist 'left shoulder->left elbow 'left elbow->left wrist)) + (setq *physical-reverse-order* (list 'right eldow->right shoulder 'right wrist->right elbow 'left elbow->left shoulder 'left wrist->left elbow)) + + (ros::ros-info "length ~A" (length (send msgs :skeletons))) + + (if (<= (length (send msgs :skeletons)) 0) + (progn + (ros::ros-info "length inside if ~A" (length (send msgs :skeletons))) + (print "1")) + (progn + (setq skeleton-list (send msgs :skeletons)) + (ros::ros-error "~A" skeleton-list) + (dolist (skeleton skeleton-list) + (if (send skeleton :bone_names) + (setq bone-names-list (send skeleton :bone_names)) + (dolist (bone-name bone-names-list) + (dolist (answer-bone-name *physical-order*) + (if (string= bone-name answer-bone-name) + (setq start-point (send bone-name :start_point)) + (setq end-point (send bone-name :end_point)) + (setq vector (v- end-point start-point)) + ) + ) + ) + ) + ) + ) + ) + ) + (if (= (send skeleton :bone_names) (or "right shoulder->right elbow" ) + (ros::ros-info "bones ~A" (send skeleton :bones)) + (send + + ;;もしbone_namesが1こでもあったら、あってるかどうかをみて、もしあっていたら、スタートをエンドから方向を取る + ;;方向に進む + ;; (if (>= (length (send (send msgs :skeletons) :bone_names)) 1) + ;; (ros::ros-info "~A" (car (send msgs :skeletons))) + ;; (ros::ros-info "~A" (last (send msgs :skeletons))) + ;; (ros::ros-info "~A" (send (car (last (send msgs :skeletons))) :bones)) + ;; (print (send (last (send msgs :skeletons)) :bones))) + ;;(if (= (send (send msg :skeletons) :bone_names) "right shoulder->right elbow") + ;;(progn + ;;) + ;;) + +(defun vector (a b) + (send (send (send b :skeletons) :bones) :start_point) + +(defun compare-distance-of-rects (a b) + (>= (norm (send (send a :pose) :position)) (norm (send (send a :pose) :position))) + ) + +(setq *human* (one-shot-subscribe "/rect_array_in_panorama_to_bounding_box_array/bbox_array" jsk_recognition_msgs::BoundingBoxArray)) +;;(setq *skeleton* (one-shot-subscribe "/skeleton_with_depth/output/skeleton" jsk_recognition_msgs::HumanSkeletonArray)) +(ros::subscribe "/skeleton_with_depth/output/skeleton" jsk_recognition_msgs::HumanSkeletonArray #'recognition-skeleton) + +(print *human*) +(move-to-human *human*) +;;(recognition-skeleton *skeleton*) + +;;(ros::subscribe "/rect_array_in_panorama_to_bounding_box_array/bbox_array" jsk_recognition_msgs::BoundingBoxArray #'cb) +(ros::spin) From 0445db6ef5cdfc8df544d5cccbad0c9af591732a Mon Sep 17 00:00:00 2001 From: miyamichi Date: Tue, 18 Apr 2023 12:11:37 +0900 Subject: [PATCH 11/17] recognition bones --- jsk_2023_04_human_approach/euslisp/human_recog.l | 2 -- 1 file changed, 2 deletions(-) diff --git a/jsk_2023_04_human_approach/euslisp/human_recog.l b/jsk_2023_04_human_approach/euslisp/human_recog.l index 030c1fa10f..5434685ba7 100755 --- a/jsk_2023_04_human_approach/euslisp/human_recog.l +++ b/jsk_2023_04_human_approach/euslisp/human_recog.l @@ -62,8 +62,6 @@ (ros::ros-info "bones ~A" (send skeleton :bones)) (send - ;;もしbone_namesが1こでもあったら、あってるかどうかをみて、もしあっていたら、スタートをエンドから方向を取る - ;;方向に進む ;; (if (>= (length (send (send msgs :skeletons) :bone_names)) 1) ;; (ros::ros-info "~A" (car (send msgs :skeletons))) ;; (ros::ros-info "~A" (last (send msgs :skeletons))) From 04a45a563272521716f566d60591658691c2a51d Mon Sep 17 00:00:00 2001 From: miyamichi Date: Tue, 18 Apr 2023 12:22:33 +0900 Subject: [PATCH 12/17] modified --- jsk_2023_04_human_approach/euslisp/human_recog.l | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_2023_04_human_approach/euslisp/human_recog.l b/jsk_2023_04_human_approach/euslisp/human_recog.l index 5434685ba7..0c16b7352c 100755 --- a/jsk_2023_04_human_approach/euslisp/human_recog.l +++ b/jsk_2023_04_human_approach/euslisp/human_recog.l @@ -50,6 +50,7 @@ (setq start-point (send bone-name :start_point)) (setq end-point (send bone-name :end_point)) (setq vector (v- end-point start-point)) + (print vector) ) ) ) From 1efa5ac0666c9249d07c944c47a1d25416171a1f Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 19 Apr 2023 15:13:48 +0900 Subject: [PATCH 13/17] add coral switcher in launch file --- jsk_2023_04_human_approach/config/coral.yaml | 7 +++++++ .../launch/recognition.launch | 20 +++++++++++-------- 2 files changed, 19 insertions(+), 8 deletions(-) create mode 100644 jsk_2023_04_human_approach/config/coral.yaml diff --git a/jsk_2023_04_human_approach/config/coral.yaml b/jsk_2023_04_human_approach/config/coral.yaml new file mode 100644 index 0000000000..6afa61813e --- /dev/null +++ b/jsk_2023_04_human_approach/config/coral.yaml @@ -0,0 +1,7 @@ +edgetpu_node_manager: + nodes: + - name: edgetpu_panorama_object_detector + type: panorama_object_detector + - name: edgetpu_human_pose_estimator + type: human_pose_estimator + default: edgetpu_panorama_object_detector \ No newline at end of file diff --git a/jsk_2023_04_human_approach/launch/recognition.launch b/jsk_2023_04_human_approach/launch/recognition.launch index 2164af3800..540f6d4b7f 100644 --- a/jsk_2023_04_human_approach/launch/recognition.launch +++ b/jsk_2023_04_human_approach/launch/recognition.launch @@ -46,20 +46,24 @@ - - - - - - + + + + + + + + - + - From c5343334f993017dd670ec2a685aaee58a396fdd Mon Sep 17 00:00:00 2001 From: miyamichi Date: Wed, 19 Apr 2023 22:56:02 +0900 Subject: [PATCH 14/17] modified --- .../euslisp/human_recog.l | 52 ++++++++++++------- 1 file changed, 32 insertions(+), 20 deletions(-) diff --git a/jsk_2023_04_human_approach/euslisp/human_recog.l b/jsk_2023_04_human_approach/euslisp/human_recog.l index 0c16b7352c..168aceb2a5 100755 --- a/jsk_2023_04_human_approach/euslisp/human_recog.l +++ b/jsk_2023_04_human_approach/euslisp/human_recog.l @@ -29,10 +29,10 @@ (defun recognition-skeleton (msgs) - (setq *physical-order* (list 'right shoulder->right elbow 'right elbow->right wrist 'left shoulder->left elbow 'left elbow->left wrist)) - (setq *physical-reverse-order* (list 'right eldow->right shoulder 'right wrist->right elbow 'left elbow->left shoulder 'left wrist->left elbow)) + (setq physical-order (list "right shoulder->right elbow" "right elbow->right wrist" "left shoulder->left elbow" "left elbow->left wrist")) + (setq physical-reverse-order (list "right eldow->right shoulder" "right wrist->right elbow" "left elbow->left shoulder" "left wrist->left elbow")) - (ros::ros-info "length ~A" (length (send msgs :skeletons))) + (ros::ros-info "skeletons ~A" (length (send msgs :skeletons))) (if (<= (length (send msgs :skeletons)) 0) (progn @@ -41,27 +41,37 @@ (progn (setq skeleton-list (send msgs :skeletons)) (ros::ros-error "~A" skeleton-list) + (dolist (skeleton skeleton-list) (if (send skeleton :bone_names) - (setq bone-names-list (send skeleton :bone_names)) - (dolist (bone-name bone-names-list) - (dolist (answer-bone-name *physical-order*) - (if (string= bone-name answer-bone-name) - (setq start-point (send bone-name :start_point)) - (setq end-point (send bone-name :end_point)) - (setq vector (v- end-point start-point)) - (print vector) + (progn + (setq bone-names-list (send skeleton :bone_names)) + (dolist (bone-name bone-names-list) + (print bone-name) + ;;(print (send skelton :bones) + (dolist (target-bone-name physical-order) + (if (string= bone-name target-bone-name) + (progn + (setq bones (send skeleton :bones)) + (ros::ros-info "~A" bone) + + (setq index (position bone-name bone-names-list :test 'equal)) + (setq target-bone (elt bones index)) + (setq start-point (send target-bone :start_point)) + (setq end-point (send target-bone :end_point)) + (print start-point) + (setq porpose-vector (v- (vector end-point) (vector start-point))) + (print porpose-vector) + ) + ) + ) ) ) - ) ) ) - ) - ) - ) - (if (= (send skeleton :bone_names) (or "right shoulder->right elbow" ) - (ros::ros-info "bones ~A" (send skeleton :bones)) - (send + ))) + + ;; (if (>= (length (send (send msgs :skeletons) :bone_names)) 1) ;; (ros::ros-info "~A" (car (send msgs :skeletons))) @@ -73,9 +83,11 @@ ;;) ;;) -(defun vector (a b) - (send (send (send b :skeletons) :bones) :start_point) +(defun vector (a) + (float-vector (send a :x) (send a :y) (send a :z)) + ) + (defun compare-distance-of-rects (a b) (>= (norm (send (send a :pose) :position)) (norm (send (send a :pose) :position))) ) From cb534d7d38dd50126a161af0a1a9ed9542df2e4a Mon Sep 17 00:00:00 2001 From: miyamichi Date: Mon, 15 May 2023 20:53:34 +0900 Subject: [PATCH 15/17] modified --- .../euslisp/human_recog.l | 261 +++++++++++++----- 1 file changed, 191 insertions(+), 70 deletions(-) diff --git a/jsk_2023_04_human_approach/euslisp/human_recog.l b/jsk_2023_04_human_approach/euslisp/human_recog.l index 168aceb2a5..d8dbb9eef7 100755 --- a/jsk_2023_04_human_approach/euslisp/human_recog.l +++ b/jsk_2023_04_human_approach/euslisp/human_recog.l @@ -1,87 +1,153 @@ #!/usr/bin/env roseus (ros::load-ros-package "jsk_recognition_msgs") +(ros::load-ros-package "speech_recognition_msgs") (load "package://spoteus/spot-interface.l") (spot-init) (ros::roseus "human_recog") +(send *ri* :angle-vector (send *spot* :reset-pose)) +(send *ri* :gripper-close) + (defun move-to-human (msg) - (let (rect-list distance max-rect x y) + (let (rect-list distance max-rect) (setq rect-list (send msg :boxes)) (if (not (= (length rect-list) 0)) (progn - (print "data-start") - (setq sorted-list (sort rect-list #'compare-distance-of-rects)) - (setq max-rect (car sorted-list)) - (setq x (send (send (send max-rect :pose) :position) :x)) - (setq y (send (send (send max-rect :pose) :position) :y)) - (setq *angle* (rad2deg (atan y x))) - ;; (print *angle*) + ;;(print "data-start") + (if (= (length rect-list) 1) + (setq max-rect (car rect-list)) + ) + ;;(setq sorted-list (sort rect-list #'compare-distance-of-rects)) + ;;(setq max-rect (car sorted-list)) + (setq max-rect (car rect-list)) + (setq *x* (send (send (send max-rect :pose) :position) :x)) + (setq *y* (send (send (send max-rect :pose) :position) :y)) + (setq *angle* (rad2deg (atan *y* *x*))) + (setq *human-to-spot-vector* (float-vector (* *x* -1) (* *y* -1) 0)) + (print *angle*) (send *ri* :go-pos 0 0 *angle*) - (send *ri* :go-pos 0.5 0 0) - (send *ri* :speak-jp "おつかれさま") - (print "done") - ) + (send *ri* :go-pos 1.0 0 0) + ) ) ) ) +(defun ask() + (send *ri* :gripper-open) + (send *ri* :angle-vector #f(0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 -170.0 150.0 0.0 10.0 45.0 0.0)) + (send *ri* :speak-jp "どちらに行きますか?") + (send *ri* :angle-vector (send *spot* :reset-pose)) + (send *ri* :gripper-close) +) + (defun recognition-skeleton (msgs) - (setq physical-order (list "right shoulder->right elbow" "right elbow->right wrist" "left shoulder->left elbow" "left elbow->left wrist")) - (setq physical-reverse-order (list "right eldow->right shoulder" "right wrist->right elbow" "left elbow->left shoulder" "left wrist->left elbow")) - - (ros::ros-info "skeletons ~A" (length (send msgs :skeletons))) - - (if (<= (length (send msgs :skeletons)) 0) + (if (= *speech-recog-res* 1) (progn - (ros::ros-info "length inside if ~A" (length (send msgs :skeletons))) - (print "1")) - (progn - (setq skeleton-list (send msgs :skeletons)) - (ros::ros-error "~A" skeleton-list) - - (dolist (skeleton skeleton-list) - (if (send skeleton :bone_names) - (progn - (setq bone-names-list (send skeleton :bone_names)) - (dolist (bone-name bone-names-list) - (print bone-name) - ;;(print (send skelton :bones) - (dolist (target-bone-name physical-order) - (if (string= bone-name target-bone-name) + (send *ri* :speak-jp "とまります。") + (move-to-human-call) + (ask) + (send *speech-recog-res* 0) + )) + (if (> *speech-recog-res* 1) + (progn + + (let (physical-order physical-reverse-order skeleton-list bone-names-list bones index target-bone start-point end-point) + (setq physical-order (list "right shoulder->right elbow" "right elbow->right wrist" "left shoulder->left elbow" "left elbow->left wrist")) + (setq physical-reverse-order (list "right eldow->right shoulder" "right wrist->right elbow" "left elbow->left shoulder" "left wrist->left elbow")) + + (ros::ros-info "skeletons ~A" (length (send msgs :skeletons))) + + (if (>= (length (send msgs :skeletons)) 1) + (progn + (setq skeleton-list (send msgs :skeletons)) + ;;(ros::ros-error "~A" skeleton-list) + + (dolist (skeleton skeleton-list) + (if (send skeleton :bone_names) (progn - (setq bones (send skeleton :bones)) - (ros::ros-info "~A" bone) - - (setq index (position bone-name bone-names-list :test 'equal)) - (setq target-bone (elt bones index)) - (setq start-point (send target-bone :start_point)) - (setq end-point (send target-bone :end_point)) - (print start-point) - (setq porpose-vector (v- (vector end-point) (vector start-point))) - (print porpose-vector) - ) - ) - ) - ) - ) - ) - ) - ))) + (setq bone-names-list (send skeleton :bone_names)) + (dolist (bone-name bone-names-list) + (print bone-name) + ;;(print (send skelton :bones) + (dolist (target-bone-name (append physical-order physical-reverse-order)) + (if (string= bone-name target-bone-name) + (progn + (setq bones (send skeleton :bones)) + + (setq index (position bone-name bone-names-list :test 'equal)) + (setq target-bone (elt bones index)) + + (cond ((find target-bone-name physical-order) + (progn + (setq start-point (send target-bone :start_point)) + (setq end-point (send target-bone :end_point)) + ;;(setq *purpose-vector* (v- (vector end-point) (vector start-point))) + )) + ((find bone-name physical-reverse-order) + (progn + (setq end-point (send target-bone :start_point)) + (setq start-point (send target-bone :end_point)) + ;;(setq *purpose-vector* (v- (vector start-point) (vector end-point))) + ))) + ;;(ros::ros-error "purpose-vector ~A" *purpose-vector*) + (setq *tfl* (instance ros::transform-listener :init)) + (send *tfl* :wait-for-transform "base_link" "hand_color_image_sensor" (ros::time 0) 1) + (setq tf-base-to-arm (send *tfl* :lookup-transform "base_link" "hand_color_image_sensor" (ros::time 0))) + ;;(setq target-vector (send tf-base-to-arm :transform-vector *purpose-vector*)) + ;;(send *ri* :angle-vector (send *spot* :head :look-at target-vector)) + + (setq tf-start-point (send tf-base-to-arm :transform-vector (vector start-point))) + (setq tf-end-point (send tf-base-to-arm :transform-vector (vector end-point))) + (print tf-start-point) + (print tf-end-point) + (setq target-vector (v- tf-end-point tf-start-point)) + (ros::ros-error "target-vector ~A" target-vector) + + ;;(send *ri* :go-pos (elt target-vector 0) (elt target-vector 1) 0) + (setq *target-vector-xy* (float-vector (elt target-vector 0) (elt target-vector 1) 0)) + ;;(setq *start-to-spot-vector* (float-vector (elt tf-start-point 0) (elt tf-start-point 1) 0)) + (send *ri* :go-pos 0 0 (degree-vector *start-to-spot-vector* *target-vector-xy*)) + (cond ((= *speech-recog-res* 2) + (progn + (send *ri* :speak-jp "これはキッチンです。") + )) + ((= *speech-recog-res* 3) + (progn + (send *ri* :speak-jp "いきましょう。ついてきてください。") + (send *ri* :go-pos 2.0 0 0) + ))) + (send *speech-recog-res* 0) + ))))))))))))) - - - ;; (if (>= (length (send (send msgs :skeletons) :bone_names)) 1) - ;; (ros::ros-info "~A" (car (send msgs :skeletons))) - ;; (ros::ros-info "~A" (last (send msgs :skeletons))) - ;; (ros::ros-info "~A" (send (car (last (send msgs :skeletons))) :bones)) - ;; (print (send (last (send msgs :skeletons)) :bones))) - ;;(if (= (send (send msg :skeletons) :bone_names) "right shoulder->right elbow") - ;;(progn - ;;) - ;;) + + +(setq *speech-recog-res* 0) + +(defun speech-recognition(msgs) + (setq *recognition-word* (car (send msgs :transcript))) + (print *recognition-word*) + (setq *stop-words-list* (list "止まって" "待って" "ストップ")) + (setq *what-is-it-list* (list "これは何ですか" "あれは何ですか" "これは何" "あれは何" "それは何")) + (setq *where-list* (list "こっちに行きたいです ""あちらに行きたいです" "あっちに行きたいです" "そっちに行きたいです" "こっちに行きたい" "あっちに行きたい" "そっちに行きたい")) + (cond ((find *recognition-word* *stop-words-list* :test #'equal) + (progn + (ros::ros-error "true ~A" *recognition-word*) + (setq *speech-recog-res* 1) + )) + ((find *recognition-word* *what-is-it-list* :test #'equal) + (progn + (send *ri* :speak-jp "承知しました。何をしりたいか指差しして教えてください。") + (setq *speech-recog-res* 2) + )) + ((find *recognition-word* *where-list* :test #'equal) + (progn + (send *ri* :speak-jp "承知しました。どちらに行きたいか指差しして教えてください") + (setq *speech-recog-res* 3) + ))) + ) (defun vector (a) (float-vector (send a :x) (send a :y) (send a :z)) @@ -91,14 +157,69 @@ (defun compare-distance-of-rects (a b) (>= (norm (send (send a :pose) :position)) (norm (send (send a :pose) :position))) ) - -(setq *human* (one-shot-subscribe "/rect_array_in_panorama_to_bounding_box_array/bbox_array" jsk_recognition_msgs::BoundingBoxArray)) -;;(setq *skeleton* (one-shot-subscribe "/skeleton_with_depth/output/skeleton" jsk_recognition_msgs::HumanSkeletonArray)) -(ros::subscribe "/skeleton_with_depth/output/skeleton" jsk_recognition_msgs::HumanSkeletonArray #'recognition-skeleton) -(print *human*) -(move-to-human *human*) -;;(recognition-skeleton *skeleton*) +(defun degree-vector (a b) + (rad2deg (acos (/ (v. a b) (* (norm a) (norm b))))) + ) + + + +(ros::roseus-add-srvs "topic_tools") +(defun call-service-coral (req-topic) + (ros::wait-for-service "/coral_input/image/select") + (setq req (instance topic_tools::MuxSelectRequest :init)) + (send req :topic req-topic) + (ros::service-call "/coral_input/image/select" req) + ) + +(ros::roseus-add-srvs "coral_usb") +(defun call-service-edgetpu (req-topic) + (ros::wait-for-service "/edgetpu_node_manager/start") + (setq req-1 (instance coral_usb::StartNodeRequest :init)) + (send req-1 :name req-topic) + (ros::service-call "/edgetpu_node_manager/start" req-1) + ) + +(defun move-to-human-call () + (call-service-coral "/dual_fisheye_to_panorama/output") + (call-service-edgetpu "edgetpu_panorama_object_detector") + (setq *human* (one-shot-subscribe "/rect_array_in_panorama_to_bounding_box_array/bbox_array" jsk_recognition_msgs::BoundingBoxArray)) + (move-to-human *human*) + ) + +(defun recognition-skeleton-call () + (ros::ros-error "recog-skeleton-call") + ;;(call-service-coral "/spot/camera/hand_color/image") + (call-service-coral "/camera/color/image_raw") + (print "call-coral") + (call-service-edgetpu "edgetpu_human_pose_estimator") + ;;(setq *skeleton* (one-shot-subscribe "/skeleton_with_depth/output/skeleton" jsk_recognition_msgs::HumanSkeletonArray)) + ;;(recognition-skeleton *skeleton*) + (ros::subscribe "/skeleton_with_depth/output/skeleton" jsk_recognition_msgs::HumanSkeletonArray #'recognition-skeleton) + ) + + +(defun main () + (ros::subscribe "/speech_to_text" speech_recognition_msgs::SpeechRecognitionCandidates #'speech-recognition) + (move-to-human-call) + (print "human-call-done") + (ask) + (print "ask-done") + (recognition-skeleton-call) + (ros::spin) + ) + +(main) + + + + + + + + +;;(ros::subscribe "/speech_to_text" speech_recognition_msgs::SpeechRecognitionCandidates #'speech-recognition) + +;;(ros::spin) ;;(ros::subscribe "/rect_array_in_panorama_to_bounding_box_array/bbox_array" jsk_recognition_msgs::BoundingBoxArray #'cb) -(ros::spin) From 50a74680e60b9e4851128bde1285ac09cd88fd6a Mon Sep 17 00:00:00 2001 From: miyamichi Date: Mon, 15 May 2023 20:54:34 +0900 Subject: [PATCH 16/17] modified --- .../launch/recognition.launch | 27 ++++++++++--------- 1 file changed, 15 insertions(+), 12 deletions(-) diff --git a/jsk_2023_04_human_approach/launch/recognition.launch b/jsk_2023_04_human_approach/launch/recognition.launch index 540f6d4b7f..73dba3bedc 100644 --- a/jsk_2023_04_human_approach/launch/recognition.launch +++ b/jsk_2023_04_human_approach/launch/recognition.launch @@ -34,16 +34,15 @@ - - - - - - - - + + + + + + + + @@ -51,7 +50,9 @@ + args="/coral_input/image /dual_fisheye_to_panorama/output /camera/color/image_raw mux:=coral_input/image"/> + + @@ -62,8 +63,10 @@ type="skeleton_with_depth.py" name="skeleton_with_depth"> - - + --> + + + From 5600b97fdc9432e8eb7cc5541001612ef454746c Mon Sep 17 00:00:00 2001 From: miyamichi Date: Mon, 16 Oct 2023 13:50:22 +0900 Subject: [PATCH 17/17] human_recognition --- jsk_2023_04_human_approach/euslisp/#arm.l# | 37 +++ .../euslisp/#spot_object_recog.l# | 68 +++++ jsk_2023_04_human_approach/euslisp/arm.l | 38 +++ jsk_2023_04_human_approach/euslisp/frames.gv | 49 ++++ jsk_2023_04_human_approach/euslisp/frames.pdf | Bin 0 -> 25363 bytes .../euslisp/human_recog.l | 259 ++++++++++-------- .../euslisp/skeleton_test.l | 134 +++++++++ .../launch/#recognition.launch# | 71 +++++ 8 files changed, 536 insertions(+), 120 deletions(-) create mode 100755 jsk_2023_04_human_approach/euslisp/#arm.l# create mode 100755 jsk_2023_04_human_approach/euslisp/#spot_object_recog.l# create mode 100755 jsk_2023_04_human_approach/euslisp/arm.l create mode 100644 jsk_2023_04_human_approach/euslisp/frames.gv create mode 100644 jsk_2023_04_human_approach/euslisp/frames.pdf create mode 100755 jsk_2023_04_human_approach/euslisp/skeleton_test.l create mode 100644 jsk_2023_04_human_approach/launch/#recognition.launch# diff --git a/jsk_2023_04_human_approach/euslisp/#arm.l# b/jsk_2023_04_human_approach/euslisp/#arm.l# new file mode 100755 index 0000000000..7170e059be --- /dev/null +++ b/jsk_2023_04_human_approach/euslisp/#arm.l# @@ -0,0 +1,37 @@ +#!/usr/bin/env roseus + +;;(ros::load-ros-package "jsk_recognition_msgs") +(load "package://spoteus/spot-interface.l") +(spot-init) +(ros::roseus "spot-angle") + +(defun look-at (msg) + (let (rect-list max-rect) + (setq rect-list (send msg :rects)) + (if (not (= (length rect-list) 0)) + (progn + (sort rect-list #'compare-area-of rects) + (setq max-rect (car rect-list)) + (send *ri* :speak-en "start") + (send *ri* :gripper-close) + (send *ri* :angle-vector (send *spot* :reset-pose)) + (send *ri* :angle-vector (send *spot* :head :look-at (float-vector 3000 0 1000))) + + ;;(send *ri* :angle-vector (send *spot* :angle-vector #f(0.0 -150.0 150.0 0.0 0.0 10.0) 2000) + + + ;;(send *ri* :gripper-open) + ) + ) + ) + ) + +(defun compare-area-of-rects (a b) + (>= (* (send a :width) (send a :height)) (* (send b :width) (send b :height)))) + +;;(wait-for-julius-trigger "") + +(setq *human* (one-shot-subscribe "human" jsk_recognition_msgs::RectArray)) +(look-at *human*) +;;(ros::subscribe "/human" jsk_recognition_msgs::RectArray #'cb) +;;(ros::spin) diff --git a/jsk_2023_04_human_approach/euslisp/#spot_object_recog.l# b/jsk_2023_04_human_approach/euslisp/#spot_object_recog.l# new file mode 100755 index 0000000000..706fabd0c5 --- /dev/null +++ b/jsk_2023_04_human_approach/euslisp/#spot_object_recog.l# @@ -0,0 +1,68 @@ +#!/usr/bin/env roseus + +(ros::load-ros-package "jsk_recognition_msgs") + +(load "package://spoteus/spot-interface.l") +(spot-init) + +(ros::roseus "test") + + + +(defun move-to-human (msg) + (let (rect-list sorted-list max-rect pu pv px py) + (setq rect-list (send msg :rects)) + (if (not (= (length rect-list) 0)) + (progn + (setq sorted-list (sort rect-list #'compare-area-of-rects)) + (setq max-rect (car sorted-list)) + (setq pu (+ (send max-rect :x) (/ (send max-rect :width) 2))) + (setq pv (+ (send max-rect :y) (/ (send max-rect :height) 2))) + (setq px (convert-x pu)) + (setq py (convert-y pv)) + (setq *angle* (* (* -1.0 px) (/ 180.0 2000.0))) + (print *angle*) + (send *ri* :go-pos 0 0 *angle*) + (send *ri* :go-pos 0.8 0 0) + ;;(while (<= (area-of-rects max-rect) 80000) + ;;(send *ri* :go-pos 0.5 0 0) + ;;) + (send *ri* :speak-jp "どちらにいきますか?") + ;;(if (>= (area-of-rects max-rect) 80000) + ;;(send *ri* :go-pos 0 0 0) + ;;) + ;;(dolist (x sorted-list) + ;;(progn + ;;(print (area-of-rects x)) + ;;(print px) + ;;(print py) + ;;(send *ri* :go-pos 0 0 (* (* -1.0 px) (/ 180.0 2000.0))) + ;;)) + (print "done") + ) + + ) + ) + ) + +;;(print (sen (car (send msg :rects)) :y)))) +(defun area-of-rects (x) + (* (send x :width) (send x :height)) + ) +(defun compare-area-of-rects (a b) + (>= (* (send a :width) (send a :height)) (* (send b :width) (send b :height)))) + +(defun convert-x (u) + (- u 2000) + ) +(defun convert-y (v) + (+ (* -1 v) 1000) + ) + + +(setq *human* (one-shot-subscribe "human" jsk_recognition_msgs::RectArray)) + +(move-to-human *human*) + +;; (ros::subscribe "/human" jsk_recognition_msgs::RectArray #'cb) +(ros::spin) diff --git a/jsk_2023_04_human_approach/euslisp/arm.l b/jsk_2023_04_human_approach/euslisp/arm.l new file mode 100755 index 0000000000..5928f08269 --- /dev/null +++ b/jsk_2023_04_human_approach/euslisp/arm.l @@ -0,0 +1,38 @@ +#!/usr/bin/env roseus + +(ros::load-ros-package "jsk_recognition_msgs") +(load "package://spoteus/spot-interface.l") +(spot-init) +(ros::roseus "spot-angle") + +(defun look-at (msg) + (let (rect-list max-rect) + (setq rect-list (send msg :rects)) + (if (not (= (length rect-list) 0)) + (progn + (sort rect-list #'compare-area-of rects) + (setq max-rect (car rect-list)) + (send *ri* :speak-en "start") + (send *ri* :gripper-close) + (send *spot* :reset-pose) + (send *spot* :head :look-at (float-vector 3000 0 1000)) + + ;;(send *ri* :angle-vector (send *spot* :angle-vector #f(0.0 -150.0 150.0 0.0 0.0 10.0) 2000) + send *ri* :angle-vector #f(0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 -170.0 150.0 30.0 10.0 45.0 0.0) + + + ;;(send *ri* :gripper-open) + ) + ) + ) + ) + +(defun compare-area-of-rects (a b) + (>= (* (send a :width) (send a :height)) (* (send b :width) (send b :height)))) + +;;(wait-for-julius-trigger "") + +(setq *human* (one-shot-subscribe "human" jsk_recognition_msgs::RectArray)) +(look-at *human*) +;;(ros::subscribe "/human" jsk_recognition_msgs::RectArray #'cb) +;;(ros::spin) diff --git a/jsk_2023_04_human_approach/euslisp/frames.gv b/jsk_2023_04_human_approach/euslisp/frames.gv new file mode 100644 index 0000000000..d46ecb9227 --- /dev/null +++ b/jsk_2023_04_human_approach/euslisp/frames.gv @@ -0,0 +1,49 @@ +digraph G { +"body" -> "base_link"[label="Broadcaster: /robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"vision" -> "body"[label="Broadcaster: /spot/spot_ros\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "front_rail"[label="Broadcaster: /robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"body" -> "rear_rail"[label="Broadcaster: /robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"head" -> "frontleft"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"body" -> "head"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"frontleft" -> "frontleft_fisheye"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"head" -> "frontright"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"frontright" -> "frontright_fisheye"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"head" -> "back"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"back" -> "back_fisheye"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"head" -> "left"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"left" -> "left_fisheye"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"right" -> "right_fisheye"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"head" -> "right"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"arm0.link_wr1" -> "hand_color_image_sensor"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"arm0.link_wr0" -> "arm0.link_wr1"[label="Broadcaster: /robot_state_publisher\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"arm0.link_wr1" -> "hand_depth_sensor"[label="Broadcaster: /spot/spot_ros\nAverage rate: 10000.000 Hz\nMost recent transform: 0.000 ( 1681984981.006 sec old)\nBuffer length: 0.000 sec\n"]; +"arm0.link_hr0" -> "arm0.link_el0"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"arm0.link_sh1" -> "arm0.link_hr0"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"arm0.link_el0" -> "arm0.link_el1"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"arm0.link_wr1" -> "arm0.link_fngr"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"arm0.link_sh0" -> "arm0.link_sh1"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "arm0.link_sh0"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"arm0.link_el1" -> "arm0.link_wr0"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "front_left_hip"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"front_left_hip" -> "front_left_upper_leg"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"front_left_upper_leg" -> "front_left_lower_leg"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "front_right_hip"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"front_right_hip" -> "front_right_upper_leg"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"front_right_upper_leg" -> "front_right_lower_leg"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "rear_left_hip"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"rear_left_hip" -> "rear_left_upper_leg"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"rear_left_upper_leg" -> "rear_left_lower_leg"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "rear_right_hip"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"rear_right_hip" -> "rear_right_upper_leg"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"rear_right_upper_leg" -> "rear_right_lower_leg"[label="Broadcaster: /robot_state_publisher\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "flat_body"[label="Broadcaster: /spot/spot_ros\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "hand"[label="Broadcaster: /spot/spot_ros\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "link_wr1"[label="Broadcaster: /spot/spot_ros\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"body" -> "odom"[label="Broadcaster: /spot/spot_ros\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"odom" -> "gpe"[label="Broadcaster: /spot/spot_ros\nAverage rate: 16.758 Hz\nMost recent transform: 1681984818.480 ( 162.527 sec old)\nBuffer length: 4.893 sec\n"]; +"rear_rail" -> "insta360_link"[label="Broadcaster: /camera_tf_publisher\nAverage rate: 2.222 Hz\nMost recent transform: 1681984818.836 ( 162.170 sec old)\nBuffer length: 4.501 sec\n"]; +edge [style=invis]; + subgraph cluster_legend { style=bold; color=black; label ="view_frames Result"; +"Recorded at time: 1681984981.006"[ shape=plaintext ] ; + }->"vision"; +} \ No newline at end of file diff --git a/jsk_2023_04_human_approach/euslisp/frames.pdf b/jsk_2023_04_human_approach/euslisp/frames.pdf new file mode 100644 index 0000000000000000000000000000000000000000..4e73665e8a73118c99766f03a6cbab766ec6f6fa GIT binary patch literal 25363 zcmZs>1CS*_(*-)VZF|SIv18k|ZQHhOd&jnI?AZ3a+3!dE@5QTgBfBd*>t<)&y3tvA znp93$l!k$p1&Xx!vgRF%nSh?a*1!Uao11`6%Gk!#$&7&IN2LHoKtMnzYHsCZ?C^86 z(swczHa4_1GKS*ig>rOqFxIz*a?85R){Na6jvv{1rJO#P3_R)9y=wtO>x764b%VVS zLc&bJEzhUk^#3IYUlQRJm8Dht$P9Z-R0^1vR};c=j(L7q83dE`}=GM z?&{_jiVyVn_w!vSAMT_D+z#zBj*qKdxk>}n-(4-v!?2R?IVpX7U7xPiIxIsRtK^Le zkyJw+OX-pjp}WfJr8SS2x68YsO7tU8oVmSo)d~EoFAv*^E!XGe&Cl2E;ZEIa?T&Y_ zbDb?s&*!V{j?UD!-OEpCbocDsE9*9{&7Qi~t4dGwJcsyo-Pt?D)~EZ=-0rW-yIS4n zgC@JI8W3pddT`s#y~}*`YHiCpxxMiS?Za&U0B5HcH8(%t3UldMR5`6Yr4Nlsy$aO2 z(@-6!rE0Qe8#u1Z%we>>^#)y?RgK~j!%F<8Tt5vvd^ey!;g%hCU|-Ph7vLZFG+(b9 z;v=Z&%L;ddF96;p#k;3%&{peet`Kv$4h&vh!d9j+_SGEsNVzJOn*}D-0jzJcl6Cgn z1}wpqI&2ZHeit_R1uezt(KK6IvK(NiCA;^JHXh|G_*&tYg2fZjHM`gKFMQ;mVyS{5 z*8QiN+Ii4)Zw>1R`BYWgsO;1|oX2|>6?IfjvXEYx6`NPl#E^L0piQ{CVfqQ3%N7_`ITU(QLNm>yqdpdd9~+0=xgk~-;jj~T5BbmxqO zOv`NpTnMl&k8egi{l@65I<2NpW!s*xwWKV23L7m|@%N~e+1HnhE^2Fgf{96x7uY~u<=mf^y$>b*U7JrN9~_;d$;nTtJk*@US{Zxmk=R4%v$OgG_vQ?I}9ZRg{D zmjueblA``u3fDPoZt%+g5BP<*pp=EYvAH zzfXPo?ci1Q`Edt^|L9O4<6h144Ceb8QZrMjZ9lKWjYuv_k3GS^uVW?EysTa_ z-%_HKe+yJ>h0$hEff_WeV`X%CFNP5t`Ov8f++c``T81)dLIZ8Gh?$&| z-e}rg@6gqvh(?;oAA5(qBq!_9;&wqd6vg+u(h=V zkhqvf*dIOG<%Y60a^x3M%UQI_U1vKDET-1QYBR^MMovh}VextxqGaa$bl&?9kO%#Uf1+ zN_kmkmho6B2mhx1@sj_6G}F{)CwpJMY*x1sk=TZM$$R9Qk^Xt zwd^rT%r7x=h<^dX04TO`WF)R@1iuh*G60DiujBSedPsqQdeMn{^%Dy00utnXmmC~k zLOAIgATAoE6l42+b3=tND**H>nPsm$z$A6}0(qcoG=vTQHr@xyXhDL{#{5&H@MTvm;=P`~t^zm)|sbFacj zMQ7I4?Kcg*waJ%r%o+{*j`|GA1KZ$UO_|WcxdAZ}q_a0DlOWio&AJK)`JyA_m~a@z zGV4E!8)ZF$TKodGB)K>Y``V&%Cwv(<>xw+)8^8=^0qz#zhJ%nN1|aml=s?$Gm^Pd9 zgD?77+B{yxl{F2NyA%K`$oPC3d1}~oj^ibeoxJQlk#rj`h9#(w7PR0$7BO1O0O?@X zTXZx@D&eQAXXGHGMvY?T*BAyLaNmE1Esvx%E$q#&4t1vUJt61|Zu?q=lzTgUDNOTl zb{n5LL=6F+>EhY|Y(z{tEL>`>RL z+nIIqgA3khX2$R=m#wxj0Z|0cFuu_NxMDeh&Xd7`IUD%;SqXN;yN`W-i-gpO%C#uN z1wF4N^)2gZlzlQ8$MSTr79MIg_^L==_OIaseaz-28s^=TYW&ZoZ7^yB@=)Pxf^7wE zLaQbWqzySh@Ss@QU2}h0PFbrHlgKLz4H^~BzbG6BK!}|l4{o!|G&$*L5&?rh%O`Pl zn}aKy=LeqxVYrI8gN}4iF2rG+PKrqNg_OkgLU3VSq8A8vqTJ6=WIrpR(;`MLMH;%^ zxu;1^gY@TV{fx|2^hRxg_G0XY=UXNX0PQ5oez?SNGlMY9>OGiVrotZO@0bo!0K!vg z|AOs2b!^U5KYtJEvcic~7LzH$_`Dbpa~N1kZbH&zNujVhjiXXLj~-}VvOKD)rFOK* zP(ZgP=j#mw1B-ySpI<)PlKxu_5!X(rR`|$+JG5sh0-$dLCwL zcaohE!wRr`*~p>p9J0!e2gY%r6ohBVa$bWGuWEL@a2E7G>c}rK>-%6 zL<5bBC%eCU(GIi6=?Uxs5L(F3AhL@P?oK5(Uxwe0}du$tXoeKa-&s7&F1i6AAQIg$zys3@V$0&MaWnL%Ijl*U&Vli>s% zj1e9hSC=4m?lLEiqq@bhBOTFBJ@_^6V_7*~i*klfO*>2xUsXk&BdEzS&@aJESaQ<@1M7Ozlb*p-$KnSwGD$f8RDqN|7#a!%2eO5!wqDAt8&k%FxbpO< ze5(|pwe^~m7C8-~5<|({ggEg)9IGdE^>sx9dE2>KG4E6oDfR!9v0SspWOyIOl~fM5CAAmRU~hg`N)o+MSt(gA_onT^RF#isVa+ zv}5E{h5({SnWds7@!vGba3oS;C_F**%>q`f5?Ed{z?R4=wPCr|?CZroTDz83i4F16SS_#Y`VsJXFiCPdcFN5p?iDA6lt7#oUsXJ;GG-FBn>;uWWh5>xB}tN5pC_~(bdBMOT!nk4|CMn9; zNf~^;fLv)A3VFT(u~<6 zl$I0RSnNcxO6d7NEWY%~8d;hZnkdosy5R4F`!w4!EI{p>(1%p>k9v2z&7CZ{VSfJL z)$#@$%93I{79cD9av~hiDr5J=T5%mmd2^0W<(Y4WiA;tBzw^7Vbzra07 zGCW{IHAhDfiJ0d@a?a8yrOIO%*7NE@f*tbhTg}XQ$NSr3=1%<|1}RZg9dHd%==VA} z$DDC8_=h(IVmDROzSs*CE823--7Gt}R_vXThyUR^*nadwV$-ZjMBn0fPDw6Oj1b1> zB&*xZ_9znlGtmq^u2gY=eU*rRMFz3G@q(ly=edu0ev^cBsLC}sBboc=-jG{QBak9^ z;e&{q$2h61m{@u^5v+;6$ZnMJ81f+VryVdgp0_BxT^V;UkOh^rXIP5A#hi$rd+yk` z932u`Hs1-HfRur6_utLYG>OEI!SFlygJr}55|`?tM(&o)?0`0|ATmAjAJ74{q;ZyM zQ$i9ml~5ozXGUV*M%eaiUl!Qv7rHbD+*XL_7iAC&I4?+Fp8cdI%o5b0WY?jVR|`S4 zea@vD{&LYWVECGCfg<1lK48G;@}e(Ml$7#?1xLliG43SP-Q%Sely5PHI!9 zb0-ZXSc+Hx>9y}}`Ypnbv=%G?kB#C;7YVywT1y;ol3g*KDKT|}K;CG}BC4a)qW z8@`^o2=0tj9^g+B1sjpb`o7ex(-Rv$KT~JwqrB+o{8_z$pva7Gw4?bJ-5;BjH7FzwAe|H ztJ3`l%rpgdLsnx7GLI4fSa+Q*&Fo=Pmk!qTCWLKMoZJB}R;{iO)v`3=Pj~3Q$koZ! zzuU(m8c!JXVG@-k0!9Pq9?FsUjGH3IGH#{OdQ`$C?V3gwWtLUu2+E2>elv)8jf3v>NXq7Gb-j!n0Oqrc8~KUTE#c_(OIlonI%({IY_IlgLH$Abym7>s<8 zBVVa%&KZLn0WDC0CF|J^*sQ8WN>!B-JG)AgT#i=gADizn?DU`<_oo1Z8rSf7szm z0IfX=)JQI9K)nAf*GL8|4OzmO%2R2K)NH0gg{{;;VU6I3S7fD8Oa7b}wEnLM%~V!{ zmn`x8uu0D80Vu4Jsq`yTf~z&`v#Z+&4O=RVO)Zba^)y>@GOqCZ?-Hy3;o7jWaY&B8 z)H$ZRWMhJN+?9@oQgQ;H-YS>32+8|x-oWZ}9xd}^IY>X#V%t({zgAabjqLS<)EdY_ zii3Ip561Ua{@HeXm6u@$r%#bLU`>&f-Ic>;H>FnZD}rsh^PaNT3b3MBY61PlzT_{- z43nFKo?Fn&z?xS>3RnU+5L#jiIy){^TlW z{dUtgBs^wD$D4fJ0419%)ZAYNi?1UqX{rBF{VI*J6s=UjfPV&umd>^NkVDDjxKn7 zmfEZZYkRJxyVsa{Mwb~^! zB0?+Ak5OLqZ;Kw!=!Mp&bg8+1E8fWW$P&J`aWhU%$7y&Tfw?&?irU;EygX|Y%P+*_ z$wRVZm1G0+!{Q>5OQ6L^8Uu}6Ar6pYGE~5_!F}S!FXj2~Y$TV>T?XA80UKFLB|0)O zAKc{0?FB{h<9NT!-IT18nZb^%l9{2FwI#4rxmD)vR>>tamN%$QZMrnY;dvqw&-sWM z50YkKv>8#Kl{Rx1Z~XyXupSFUFbzRjGgus@TDA|kInU`aX8p&D=hX9TRzbSVK;iSB z3=l)bm_`8Aww$oDleg{|%?s3GtbL$j7IH8dT4!IPbxM!TVBUvta)z+4^eJ0D7SQhJ z^?gd^Jou7&vqNOe+%_oK0g*fC=KxwWo}dP_HzTHhqqE)Lws)ZT)SUh2x%snO<|~d} zT9W_xi?ZDMz_117q^RY-Z;Ye5&U?cs6NsPVikVAzZ~({it$L?5aR8;t<*|%v8H?}S zuzV!GBJIj|;-(Z@qwKc!7M0_84{Oxz?{&u(H{2jme&T@`bRE*`?1iN4g8(U*&yJub z-AvRT-;4T*LhOIe{?V<3=d<$J&|>|cvIiStTggj2gxArA+CboWS}$oPtbgU0CXlM{ zqa<*^+}S6CzvaycNJ=v+$W;j&Lfc{Ncd@_tuK4auMsL+BN3J;CQJecjZx*SCts^h8 zw{)J9{2N++ibnkWOA4X7c*kp5jb;bM77a}zYxv*Qqs(o_8dB!=;2s{F2Pj`pgff+8 zf>|9nF`?3xKz`H$o`gotqeT4$28f5KQ`nDB6oI_Np2VJ9Cg0979(xGvkNxcv1Xc{e zHhYLnlxL10`ys-2R5`Wx~yB+dL4Qk&$n^?ZKbM2S{d?<{cRx*E%3NhZl_{ zes=#%5U`MC4dFjF8v{USY5g)QZQDCg`a6X6l>YPva{=&rA%T?Am~OmMZBRA`{0k%m z+I+I_3TSu{WMg}udppX6ehJDaa-rZ)WI0E7`B=$c8kzsuw!fL*s?EI0h<^XUc_gb| zLI0S)a{Fq8k>Y6Z^!7kIJOLNAR5omS>Y~^9Rl~$tuyW=ov= z2mGWtYj)iTP71oJqFb-__6@gg{*;lQ4AO!M)tXy3ve*h!+VE-ogf)lmCx2Z3{Zlpe zMlQ6K7<9>=^UlE<*4P?8>BA&f-j7;nU_WTu?_iSQ=VCutY~VTwn!`5TEI);f%9(B( zI~hAMWx(Py$Z7O4s6iKjF(ecI2*ErxdoA%;nB#b5@x+83qm|RD{7GBS&1fPpR2-AW z8_ehC{cVG_x{yy&e`eq?qt(^-=Z8s3b*4U7ibMaT*{XWvPt3-~l8oWjW-` zK!e|oKiH)4!xOk|kElrHW?X?fpPt^8q~+x0#sblkhb7AntU5uTgrsMYBLz9D#(5MiWw^T=I zR?$*j6x+LmN=^6U)aP zvQagAzG=JxdB$T`TkM%?d9G_CGv*3a)tR~KD0a}URSEafT8fH3||^aYMwm#@W=$W+KUvo`bAl>+zel9-T-;PB1WP8AlVJ|BX*VBR zs9Ewo_w(3p*cojeOJ&8GuFXZq+O~?Ed8ATphZdqQvpp~XH5g;m#D5DML@-sgraEkw` zg5E}*dgT=6(7Cba;IHJ1@%=Wdwm{N&*CAz7EFb#VMSk28j(fl>Jh3`rxhAaE#4se!RW+-!}GE=e@vr+k@- z;hh-NJ#F?V$j4J-==Fljq~X+*A|m#)TySafaGicu3ocF6_Q{Fj0yYMZ^Mlb395HY! z4&cWcW3GnCLWG*_VMB@?d*wT73W1M|V~6Tv;7H%A%T?l5FMlp~a{M;la$1=4{@8Ds@4dE}xvA=(t_W1y>*5kO&mrX@=t^8qpUz?`9riHA(%YX>6EkeH z8QhF)zFThY5jrOcC^!!vAqU~>Ex~I)St}5I6sWh+Zj1A_vCXRLYMqaj169=#s_aK3 z+op4$ok35aOj4{^T;I}tYVBWd&4)G*sAiJQx6eCYSr&vZC}SI=|E6kx&i;|S|Crr> z#~*H&jfI{0pTWN_)Bke7|6zSa+?>P|oqiZ!0&ebqil0WOPyf>)pc4`xU?89~)c=t` zJn+wj|B`f~wl+@x$J&I3o`#-)^?!KeAETeoe>-FRUuOh#O73>X1axxxrp5%M1PuRi zE~oEc{PSH5|1*|O+StfkU(nW#K=VgMPr$;+%0j@v%)m;Z{U3XwAJ0Dn90~pr+5g2_ zi#gaj+x?%r`7ba3(f&_3ia)*`^lcpN{&_QW{~xtDfs=!?@&ELMeyoIzUCa%Q6~qMp zDgQfI1!G5BX9q)LM}mJ7r|^GbWBcj$9|GlmMKQjH_)czOi&OpFO&&K}G%YQ2v zf1;#kqyIk|CIS{_mj5^Z-f66aGrrCO(YHlvc5rniW9QmBytTCjd3A*r&?#i+3X4b5 zhKw=Ye$6wM{p{mw@->xVLeuf=Q{i&yVWIkbhA%BzlqW@QWMB${(%R@;Vpw2$2sWy| ziqXzaxwbaCWz$8Pjj@+Jk7oAPThdqd zqtbZaCB~$;=ed8hZxSev+0~`x*hG)sn=buJxxkgNxD}L>>5pYX_*zET>e|QOVMw&6 z+OYz(82*FjDNp*3)Ev#V_4YN7&(?_Y;Oa45XaFg#3rr`Jtue-c`efW>g7dC4%%l(7L*pS#@%9~Hf z<%zLbR0um4C%`wiPxTjBkcmMM`g(d7Fbu#cYAb!;%AN)O1z&x2AyYAES3g$bPfta_ zDBsV|dx>WrNHUj}WxSry3Cwi>Kp3JBv=|rPly2SZC}li&rhE-G5|0&-x6$ocePH6fM1Ha z0@KrL{TMHJS-$(_1Ea$)Ig`)iCEr*Z-(}y(+ux?{pOTV?bj3RYpSo~E+EvxxSEPS? z_Cefc67y+xc@zLJdv((rSe-t05@D>Vt9ZU-7rs{PoOgS!&c4NE=GSh#*#uimmcMN{ z{QCOEH~VqT3iS4@tiJf_KUD>mmO)O;to5Ol>Kq$h&b>kSM+Qei; z6F*&H%`ES7Cm6%lur|`wRx<$8)>Z*SVq!w@>Y}dwjZ6%I-53D3>5yhWuR8(s@>-i6 zeR6^7ThPEg_SSeYc~g&Y3t78bD@bHt1HMC!~RxD zd3NN1ZNT5`I=fFpkn{J3Yqo3r$)}i|1C#em_h+aN_-CtY6>FL==DVxK)#>%CXObsZ z%>11bZNV4(!CM=NeKrsD#7}Vh?v%VQ=r5InL*OAztqSri( zU*Mm~uwaRNyPlzbzP&x`_uyW(F>ClYT`Whwy{=4XKLT0hN1!kN2yE6K!i7%Q4Zht@ z*v^0Aop1NOBj#tE%pv^Cw&d|YUFtuv@=vtx#JzfJ$Nsa)@g4YX!ycxMx%PMddY`)b z-2cGN)cB(-M=*=~vq`~lf=lr5@N?D9K^9ln%$k9jD12K3~|m)6Ha4_Kc|_xy;wgFM7!&wSk!lN_#52dJlG5#2bX zX*w}2piCK+Tfi?G{fi0-9gHt9?k*r3o@H)o1YWg$Cr=iiN!)6`E+bJ}-O3%2l{ORt zVznx6RILX?S6Su+yM<)$h^Dmu7@B1t1&*Zpi|$3s&D+eNP{7sogLoeZAz~p(uII7I z_6k?o1j#kIp6ekjFf!}&1PGncw@e9d9A{Lm-~Xk_c;xML=nDOOT5H;CQUIKwpj z7z&Kl8Iv5(BYDs6gq#`a3B{%>_Z~1dI>2DKm*W?9sH|R;4m8E6tRVB5HN2jSni+q)vNNWEYK%Fa^^x5*cXleO!wyiqU~H z-^<|OOyL)iEw6xF%I1M8>TYhw4c3DE&9(tIsx^_7zzmYIC5&N+iL7fgkE%Ir4z1D1 z1d&CAb=Mmc{q*z9V8$kyf=^1hGz1Z-R;cu91vZ>0jGQ3Q`>7ZzG3*`nt`F)NFB!ov z94VK{_mQ3W7d(DKYjk&90pJ{WKEI1u>oEF5fhUx7PhLn3U1fqWTn}Gu3Io&P^5FF) zU{y`9)s7e`k6*_11blm(NL(Y6F< z^cSM3E?PpFZwH1o=c(@6eWH&Yzsww{V&QVKy9(~d45cmx*&eJyvex_>3d=ih;DFhN z;hu&AQ-zGF{9SEOKs;pxF4Y}h-F&tRA%}A(oq3#1q*3q8 z6~RW=I$=&dMeZQEa>l2W*6R7nCM-N?5XF;_% zmJ{J%asPl#%aV4qA{NmNu!U@aGh{(T>ei98X~w6+WaxC!GKEA~hsY)twM}EL1e-5hgp%LSPQB3a-Tsp(IWG#AA1~F%NYLnJG z>SL`nTUmte=TYr}A%({$X0fYGJ%#g%MRy)^_$U0cAz~V`paCe53SN`u80vK}+>^U_ zk^>zX8fmHjA{#E@1K`%hhA5msHV)gq<*hCZL+*X7u!&D8Ii>qKVj_|!o3Lfi5q}2A zAVL<%UD*f7ElBa5$LY22DWNV=dg(G1WNHOc)4GxRMWCz_J60#yI@Yx5U0M7q?q-NU zU3YEdeylQf4_pVYbwt+_!Bg#_vsojo`!$jCjPJ&`6&@jev;ko3)26})p>T4v-kbf^ zyC%lH7OQH=IRwiqSK?13Rjh%jW6;HEM9tU6NWr2VN-FoxqvAz3`xz&985GpmR$<(G z^H~afknYfu$9v^+RNDK>&6=CNzNSk}lFVf?w=9bpUgIO}F?d?CfO%f8+L6DAUO8HS zzFNq<&_+I-u5##OYFKedhB%KAU?&c>r`uB{2I}hFJKX zDi|POZC0o zKv@E+)Ad^{ZIDUDQs9)kVBqS3`Cc)TN6T)H>9mykvAHmAQpk8P$EfrcZcMZjpQ~gm zcXe_0<=rZkj}>$1LfA%NFky$9_2s*BL7ge>DhFV-7dp3x648kVW+R`VWjVTTX1j9k zY4P}DvI5t=KQE81tFlh*(cmL2JcLH=4vbdJu0f=5jOcHOKK2{btqmFMDslZZ(CDn?k#|`;YLg9-{ zUBXMCpX&hplE#L>bUEN=fr~xFh9kC~#CCV*kFh#@J>YjsloI`w29j}i6@#i~o#Od- zN@Fqs>o^$odaE0xp)Ow@!Juq4A?(Z4_#l4pXpeV^d<*#gnqFb=We8iQPfRX7W<7|B z_BeLUVmtrqz1QoSNsn>pSOJ&w)Ji)tr8Bv1o;LH2=LWC<49At(AO~C_GxceRyshEL zG3yV7xcwe1Eg`dRqE(fpR=*w5=|iB$nmpl0E8Leug%*?dmC#~P(iH9-dZF7a9W|tJ zi0A#8HhvKWN1)^osDkU(#O10uZQ_Iy(yBCHITl}DGG|ZU+(V?=jav{sogwS=4o&HlSf?eA$4cMz|Sd^#j`6%_J$#{n@; zptVT`q~mabTZ;7QxMTl6vzn;kM!5)@mCUui!hzhy)nI(qj>&P?gmHZ(B32zj*4;jx z6q)R%@zAoWyfOoOXuH`n?0&f{EUs?E@6nJ6!&s3_4gD301%6=C{ntWX4?)c;xsa!p zXQGT*In{ygtuLAwB$rtV)q@hHa1Xf4ox(kEXv^u8BE!v=~IU|ZFb z9o@}EVETd4t`I$j<>cN~61P<^5J?Cv=zy`z+>6Uftf8zK302*jeE-|NxOaU_*WS** zH%QiV&|Xiam}k4FhP(C|lr~3|AkLMANX;Mjl$WiLo@wQUH3E{dmas~rOR*B2S(tjf zTIm}VGad0mRj80v%977>0#2m(B*TrLVYp+Zk)p|451PopGfPbr^k=hKj{GF$>xg+-R|KqG!D5Tn9;m0>E-e>~qdv0* zCEFy#p7Pzj=%lH&DU+!IOvMFEjR!j0IYWt!Drdo17%4oub!Y!14;3L3Hiji;tN&%` zB?~YhemabERdDaux4KYDWVAUIJQ48d13e?_7idiq>ZPz$bD}*?xfQ&&|HFc4#fml3 z&Pt?0-~HIvF;tyX;Q1i@6h2=CB}_Mqy_rO#4o^m5XZ(;~z|hYNhLG_`wA5})eQeg% zrhI{RQ^}Pl|d!7X9I|lMG~b_LHM zQ0X~jAFU{$b}gB%0cqXhrANza(Fh?~H~LsSjNYZz^WxttMXTyQYdbKz2|KX>2*zmJm8IJoAYJ zW%R2seC&70(Y=Nx(;u)eev4|GCuP)Dt+eXqFA-HcZ9N11gIe99oS8R5^DXNG!qK%Z z(bm3o=bO(AQ6cfP;ElOhh_B0o4;hq&+ZnKMGKYP#s^zZ9MlisxUv&h?u1iGrD~pCC z))p9SlZ_=YANV$gs8!XtX5oqt{O4J7!-}}AdV$hT1@sI+ANH$v$#N) z_bihl0-+M$@mP>Iaw=iFtRd_*!Glcmnh!hx*iRoEp&Tul$&XcrQY)JO4iO=o@ypm> zb+PW*UKyN(d>B^=cG^u!+c!du?MAOYowrTv(yGePTg6MH&z)LDCrh4XdVrApRTqVq zxF2o+q-n1C7df@OB`m|t;dLvqmfecoMB{!!b}$X2q}sACR8Kbv)CUSV;T&>1q29f7 z;a2-O=*Ya^ph#A!$P>nzoiU@6(PTcFWu>|8Y+j1c$fRB|1|OlPTE4StU-To)w*f@e ztja$bc0!Z=oprYVfJQ}<`B74Yb0nXV$eZe6QOnat(SmC8%E0TF9Q45Q#8`(kL;_dnkiZBe52VJR{Dkih7 zC`Up1-V(@RK~@9#k&E&MV2Y=ul8#X%6(rs1BrTArHC;LW5!7kT-nCF1?wh~y_CJ7$ z9_DMOeuHhE>n=>F%pY|30Y^*UH@k)h7Z}3XU?slR6X@%}#;(0C^PU@dK_92^z04dN&!v*~G!owfg#6@&0w*Gv( z?Nwob9~n4eS2QA<*XTIfghDGwT!QuLNl?pFpj79DZ0L-aB$jN27xj*Uq#KW+)O&qf z${Pqb{<+J+70Pmy1s8t~pQb35)C zQu@I}%gzppTz&6nEu<)Qrl2AIP1l0csH0T&m(#7o0G(iQDb<}85QIyul3_~s;t}ND zRhzEtV5gHcNI0jeBf6VD%kMYlz!qa7N4CODHC~g3QVsk92O|7Jxt5AERqv!w+hQ#Y6V7{7{1p(>ED` zo1r~$zmXub8(1IRLEFLHikfPEioRd@~wH@S;Z4Pc9riuf(Q^Y_d7~!nJdaCa1 z$ulAuwDIOww0n@k!pGBpR|Se_$VHtRgE%`q5{3Ae_&-*J*2#;p^Y=_Rdt4c0DR52Q zLPgPKkUhXa%c|EKoteRdPRPj|aj|h*FQ=z2PUJ2ml?hzg(O1q`32c}NxBKd;?PaZ_ znaWK8H0g3O7oG#5AEDFLB;~{Nj}SS_O&ej`rKx9H0p)bQ9HW??T&Ksv^m(ViV7Vl4 zoojt~o1Vv6Pq=LMKS`-L%x9WFNiT~x5>Dsy7e~pMdr;>#b&1~-V zN#{w@*JH=lA-%J2XGDl7_MYz)p0G?(N;MWm2*^UJ#K<}IYJk*DEYs@D&fXU6W&yy( zt{VEwb)O?fxHp{2MO}>HSKsd9um!lt#Qy}O-tzLV^1k+rNLm}<^G$?bZyXHFK824*xVZG8V!2k-*RLjCpwDc{%Zf=>_9_6>@ zIi!jD%S)k*COlcC*f0MN&v{rIv@eH(NH0U5+;crS`1v{l5it6e?YL>PLYXy!R1A+v zRKDO^0@)j*(!YMfEd9L5>|#5UdkSZw!dRwjxjAF{oJi_nPZ)#_B}eX5er_x}PTWLd zg}bdjC_DVE?Y4Ck>+>2Cd&*alrE|Tb%1AL8su zBVo0T&MAj8HY{Q}Rdrr<&QnG>rLE$s>bqG4eMT0F5qYEuI zYFFm|;_h^ft?pK{8yR;lzC>uXsq#Gai&CLbo|u<66a0GlXsfnHpr9q0$|aE=V^!41 zSb7uQ(u{U6!pRwTV04nOCUA>q= z7*8oniCK|m3oQ&C-wbvS6EXEQ;|;2OAFt$1hqxg zfNCpfA4vTjf(DVbD#k(#H9o|u*fr_R*<~e6J@nOy&FOvJ`!JLFLo%d$ZGIPj#UU0Z zLM`%Xy_-fNgwH%5j^RAKp~mEv%8*C;>8~g_u%_Nd^fk=H$1}b#7@vz-k0ktGX;S1Gf4ys%xZYrJLAANZWCE1cN3zS8 z=~yMk{o;yM?5SpQINOP&^Ht1Jq2{P$9|gsNOUm2%lyN(m z&`)gIuA?9@ZV!pM&eKBqaFnI#@61h!cCVztV3)R{SG4MSJ`~RTyfxLqr*5SprbA@J3+JPBgdb9JRKe?>Wj zFI^yVucj9eL4WnvMWL1Exy`t>T$!fL6G9qSHCtfKldhbiW|lBcqnqG`n%}I6O4}}B zX~FlcvSeu5HzxFD4)`q4ycjAm{$kES(a(l2S7no*p1J4D@+g14v=LNPGGkF|7)j_r zw;c@0iwY3lUga;aGhun|mnn8}Qiuh}yE)?*?+*|=Vcz*@At0pQmHbHsJ69T+8M z&HN`n278cY_uV7iOlW&_Un2PAix^Bw-=1C6kxD^Mv+<>{r@Mp>>h=;&B`2x9UL=8J$(n7Sa!@0Fz$;JUPd?cngHAJVejZDOI*+xK^N z8L|q_g2rS~%49}9VCXW5L?Q}jp=(i12mTR^euKgsV15FXI+&Mxqyx-d7EQuH1$vMoa!qVbaiXR!&A0q53YV{IVT`u0) zV#$^vx2WulW?r&IrEaly9`~{zrq_J%eg-!u0h-7+;}U{i#d#WY@L06ulcPD9>{)~Q z3eABggaiI`SCtCnFg&=a^|X-4pSR2=Qpp^cc*sgcM6SQeC+?(aY8WB)25Ox$vBm%m z*^iYkW$QK*dTxN8W+?cHtT|OUiI_x%N2$JDz3`5kWOE&JTgIDqv$1|v7m8E_ajHbc+k}`F+!ePXE-9+OA-7bfnR|Lwo9VM+du96bv zgio~5+fgKz-f^*eqIJylvw5l2p>mrCwl{EacGRLpdnS$*HYPKM59P{jPJ<$w3JQyK zY2$u(s!XWxiJ^~sIGjo(Jq?ZxIh#(%s~4u^>ioSIElH|kKod$Tg)0#$-03Iaz6Be; zgD$yLw-Tlh-}T%hjWqK7VL4gzX_X5UMexpv{_YigU8KhX`wNj~*zXQ|OLb~0Jd_IH zOTl@5ST$hvHMb^ih}k^9!8)DW7j$rr&i%wp&5#MSOptfgEM7xv(PDUML=p(n2ns6E zF%2KVR=kTGN@u=jK=bXbJeruS2!Wwk!>}9?hzQBB>EeFN{sWz2F??TP6^q-w8{`qp zQEG-!Mlk*|KRC{N$f5nx7iEbd)egN~t}EGnKhOqfU$^yND@26uNEU>ID2h6I8`&;Y@LJAnYf-3hLNAVCw{ArF$9 z@7?d-zv_SI)YLh>s(0_*ySq=#)SR_i*Qch`TGz=+C$gInyH6dbp*)P?(Ceo!$Z%7< zkZ3>l)n;2rneSTgtW5W?kJp(j5tKk0AEUwm^p^%C3NNBWC7_#JNVw?iyE&L>Z`kF@vDw5r#YY z@!1pgV~K0jKDZdHHP;wd!-J}JEiYk_a-R=(M9BYbypC_Yl@NNmbEVkRHS+X83XyLY zW?{z_fC-s!0s5Lv*g*&7g?XE0OBPNTayQ;3xp6DF)8Z{rs0Te~X`s;aZ#E;BLnUeN z#YM2lp8#o+j-Lt_UhNA$#N9`HGGy>xUmnU89&_wl$aE#T> z?GlT4T7yol{;PM@R+>@|Y~@I~ya1YnWlKB)^`>8(Mzyw>(d3i#53@AdfO5wC$CW$| zuhLENNL~|2SjP^Tl_p4vpEKDMikN?r`R=k^a`ABL?#+Gq5Q4I`@YnBq5M&8f@tw#= zDUou&ze+&LwGrEzR50tNJB`}>#(avF3qT>o#!B_uuf#Ps*BYxHvxx1|@z-USA#0;o zAHI#5$l68v(ArbZRCzv+DUukq&MW46T+oc#bInsU;cXFDQ%hb)4yn5R;G`-lM(A~! z2p!!u-Ll*Km^-wq)@+qJxj28G)3Wj^bh;@{pX}%>)Kbfa)ig!Sw2ki3S9+CpBCV-w z-*+S`mi2H#dZE1AD)6B`a+pv}-3FS|5^}OX$YOzX1X?tGC%~Xr#O9rnP-kS`v(?S1 zi~K7120cef#@y93L6257C-ajY(449}*8MWcyN?9hc_R$g-b$B>_JoEgA7?~Ral^si z5LeQlQfZ1#mXYeq<~Ea`W50AEBI=_G%II}k`TQ1U$&sRAgFexZb%i@k(5-Glte=2o zRg#&fKS8YYMCEX3>m_FjGGSJPb61_I}QZD^Ai|nG$N?=S43!I zT?@~>IJUN(R-oQ2lkwXa3eZ4lCjgt#HTNufWOzE~)iL{ZIQ&#%Iw!s}TH2RnAhK zpt0-mbuBptbcBY;#$WEmR(%$y0^DwLcsAxaHwRM-JtFqMC zSInNvjxkc-sq|TLhv!kzVs^}<_eBAJxfLuxc&&cmgZtic7-%gl1RjQWN- zrC;`J;Gp=TRz`|yi+!dn7{z&H?6AMOKw`e#H1WFTY}+cmnEW)~W>H*`mC&-)RBMXH zLZ=L*PXY?_V3LSnYc6jIi#o;fCR0^5m(ktTPu@;S4>+nu<8zLfIT%{QpdbDb8xX@J z$RTRCc5^2kVtk}zfwCKy9H|0fKXxyFEqyZj)}BN5HKKCgCuaakHR@R}3SILY8t_=; zCaxSFJ;0&)rV0-aZr%M5_L5S*x_-B<3B)^vL;V~gf#GW2D^5l682&{E(*S+rjQR=TBF`%P5I+ z)s){%hF%6!laT%NhvQIF^A&ZHJQ~lHS8yv>J;b=E=ZtE~70AV7u4waUN^Uk&v=GM1 z&J7?L65o8-4w5J>FPzfKw*lnr*W2w7P7;ZgX|l^|3OB-itTGgm)I3#!)w#JAm<&lb z#b=&0TPtPP(E5r=`T|_$e*&;6NxgP_ltFA&3s&n@hOk!oN~!~l`Ld3ShGXaY9l>?Y zVU{>(HLb#$O!AahRyT3q?K8XP1DU4H&E$)jV~HJwsF9g=M(40?_Mf*xHn^S4g;9^Z z=?BA7 z6NdV8TlV5$WIP2o#|T#>HO9}Cx|cOfb&TPcv0}EEV|&-jo;eshOx`nwcwR3F-^m51 zBH$0Ilxb);o76#&xzefRc{h@+RJym;3AeCReQ!7t`qV_0IzHotSn zZxaj|_ZxqbK3&X+OQyYABN?pj=VgK#Lir z97KINY!OnM%0%-T7cnbUg7LDj>2GZWp<{VVIW6thHC=z+SeCIXng^8|C*eF}`mtl9 z3JF^OIo`6g0iL%ZUamX0da(iOGa8^fMwN6ytdcIQz%&FGKK!`F-Wa6aZFUtQIJ?(0 z?$=v|lTuS6cq;$8a?Yw;eE!X5Ij38lZ!%Jv2WR{sdyHtK#rGY>rnT^{AS!hN)ssmt zSmxm3Q{m+UMQ`C?fui~=%Y&SY9o@Gg)<6$B;foi;HaHA3*VcfHYoN|68X|Tizh1{h zeSF%&l8|o2YZBxK*0J`@CTPqTM)CromUydk`D7jx{O>U@CV(-R(vrii$66K>aQVze zBCezyE(8C^;x%4~g-Cn&j9=4Vg`f>k>_NJ%1N}lTOQR=a2ZdcR*q{e*sl;Bixv%_) zwei_9|4gq=m!ygoXwgHYg*(cH1R+l7q3-j5mFBzeMvqzH^vz7?(@|S=l4f_k8?RvT zf+W%CCKylU)HWUZS4|$~2A_5G*q@-#dFADgDAGlnT*Q-eF!6@)HDH?!3j zCwr32BrdO*oO79`vjEMOb#QJM=Wz9+2juwn^p%lu?I`E=k*=stja#Jr3^kl+sMfP2N9%DWx0|*3$KUNT(XlM zBA>KFvFOK7xr*eNDA^9d3OU!CY(~kPA6_H6rztV>R=wQdE;ux!qyRSLLxNPiTQ@kZ2b9Hzp1~O@j zNSc(d=9#E4xm6ry8P%slYbm*9dn4kXWGXruAKaq!T*H4BQ}eBye_!geb*Dp$*i$mv zj?o^e(L0PUf8h4m(3g?+CxQ5D_EbGXLI&T~3}*ve_z_j1m{+%gK8L)PXcMI*c^6ED zD`KREM0engkem0ZGRfO%oN2SGo@y3^?l&ZjwE_cEv#t4W zqZa5q{76vOPt9$$S>jv-3|*WONyw$kF1%zPb(v}W*p^=q>2;}ChBB0(G-_;_wAbg? zRW4&!BPpxBqv4IG$sV56W8IJ}!+2b2)Ooy^(O?$@?GjE;z6`BwiaZjYkCtxyxJ74K z_IUZoNA|Ge=ut@}KTquY_cY|5X(F^xyT>rXo?l0s?^gT`QuFZ^ z(&20i(Huo{4X|X?qqevt<6-m>VX6#S!BBh)`6`E2eMIe9v97Gw&_Xg<^ofB)0G0t^ zKMDO8l7{{RGH>d1llZTMPS~;NZVauotn{7m!1c@xwUh*|%>&3umLqTGY^tlp?Y^5b z@)JEQ2}X?XMr-DQp9!-*KP2p}lhn=C6mp?C7eGTiH@(EGqPJnk6c$xH9h6ZXhjAE> z8B(gV7NvBac@}GF7Wli;JzJ6%NB5Vs{gzsKle;{ROOAv&W&VRI4?ps zxS>-t9ueOw^>AIwtd~4=)6oW{Is};9oETYzUF^59bWjn)2f7`miID<;m1=U$I6Axy zJ;svwwl?v~WHttP1cIIn8eMRCq*o|NKm6b)i1YwQQOshO2#0qTg^bCyqW>4WyjN%seG=8IEn8;o0RZ9V_kt0jZ)&_^R;A!BVFR8miaTwD$ko%zhgv&ZFXrz9~k zKZ9lcqu=MCk2Gbl_p5O?67dj4z9k;DQIafix*c}_8HZ)v8)>}ym7k)I@lKEWz#nqL zInsw21zg-;%w38rv`9#4+f4M57%Z0fub!i4pw@}mM17sD%W27edlEO`k}5JF6HVEF zrkazDlzl}US{o1kUa1;0!x%%?BK=XX0-7Mnr5d^PJ?ZjMtt)y&ZOJ1O2|tp7P+?J# z59rZ%f3|q#<#b~E>Y=9~v{|>Fc1vqySe!drc*_;G44XrDf>6^@r9wwK-5_ZfrH~Tt zgYl1TD!MHr7V`@I=qQR(-<8xvEp7lP_m!DkY$95sOHnrjr(v=oK}f!fR85I~uQE`3~!%4HL0M;WH$1yj>J7 z0h`AbdvP06CTL5XA!AU5*F4QhS=Dlmic&^VLi&N4L@69qt_`cg$8y`F;&MI?X69$$ zH@7irsZcN=x?ulU&8p#7rSckS)U=}Fpg>evgwZh$t|TZE`cq99qo9I$>fK!bYp+dn zOp83?w2-3_H8J%>zV7TqC!$48>DQ3f#0G1!G_y$6O2%2`-G|PE<=6gwV~mM2Q9lFo z_O|-2t!WC6;GVb`A2HENm_qeR0+|c!G(I?wvww;{QQ(fTX*}nT-YJmjrF!op5~N zn}=JL-}C1EsT^GzhD#wSXSQ$1^p=5UlZs;VpQRs{B#8O&LDZ{BP)fW`EKcM=iZ)n2 zk>7NlVu+7^3|&0We+-Tnf}RfA_$F>tH&6=VCyQHZ-Y?}J4P2p(Q zlCfZZB($A9d(`}j+4LCE-W1VA7R|u(LLHc_PCxh7CXjKO>4N|k5mLN{fAw+*-%MI| zF0#7V1ASK!>w$Dq>-7N6#!>h<(dj4H)RlnAj!(x&R0^}e+Q zJ;$Cd{b=u{K4IHz5>`vSlXA0!>4J^$rh<;!3I|z_%BL_cJR~@i3WLqfEU-7XxkhGno9JV2#sZ5 zi*#dcZpSI|ianv2;?*5jOozJEf%Qzw#qa$uwXdun<9IAz?0C@N+cb^5zxwK9RdmHB zR{`BN&F_!XttEbv*hUs8buDi{#vxHVfM|pznZZ)Mg*QX|Lk`WGZc>FYXp~Z>XBQ$iA56c}bSJT7jCsV!^YFm!F>&#%`qsOFmUL?>H7s zr{8Ch7ahX#8{Omhs&lzj$$`P=$G!gY`rV9;g~b7=OBj#2Z^!wxEtDu|ZrE}WQRkYz ze1!taJ8SilQi`C=@35Pe)DaE)1rmt7pa8eRD;GE zciRUli68Ha$-v-$#G0v>q@WH}Ckvf(7wN`#Ag~vw7He|vjHTtbT0HTMAFl8|K;xIy}Y)XA?wmOscS`wj=lPN^x>zRhJF9-jMQD4EHn1RDV zLsa6{IXlq7Wu*IgfBbIrN9^qDJpGprcrTi47s`kQk@3#+ZwW3Hs9sthtXOTz`=jLu zCK)OPD-i-d9=XXdJzJlY?9Q+we;qD^cN}y)t~%_Z>BD14S$xnzBQ`R4iD{CFf$3kV z2Kwx(-cFObqwMasK?AWN9<@9rb{Wwjd%rlFC8eSb9oSg^V5Vog$cg`{6wZ?-*BCs3 zn#1aa6*8pyY74?MpLc~Qptxnln|?U5^Tv6+bD@m{p&yVun);;KG@y+*#PE99~4yoWPi`H5LWH}~`Eb#;X=u}um zKvA6JR3SnIdiy0KClsl{HOR-jf)$tC=a@Z`_DrcN76QIb~UjzU8*crFCX}+P~82{#ZN$FG+WjL z8>J&6X$5#uGNNFx9cUx`pmpWIss&I{8}gB? zmH@Tj+YMaE{PC*68;4^a1`)gS5mw}6Q#~NZ7cc(;tgrI{ZVN??Rd^Ngm5sg{frd>O zg-iT3aR&sXS)uA>?;c~V#+eZT#V$Qx*JJbioI3PNwJy6N8{-gtFBTxv3u!UM3kvw0 zWg#fb;_WgSj&|R7=1hh#16&tMma_nqP*ff(6x#0ihWhI$<^|G6&c+O zZZMS_A9SnZb>pUOgr_m8h?F`_^{)7ND%EJ{*v|x9Qsw6n2A0@pDOo)3fK;Yu?Yj~` z@Z@t&9*WM=MN;HxHkLi{lpMemH>asWAC9%t%5gE70yxfFZC-19Y(M{bh;a22>-xE5 z>kPTg=B9(S`KArZ&N@0A_QCaf=l%DJik~DUmfF|=05hMycMo~?&}InUlG`{yTyQV0;!?XF zZPJW+3PWO%8oWgOM4uc%(|%YgSugGJaDLo({FKz`zBbU599-?Cd^N9rqcUv@icB7f zo*$kb=Pu3v;dlfwS~@+fP{}+LJVY}ub!<)?v^3&4-J0GZo49Cpe16_P0M&ODo*Rr$ zxZ-v&4r80oPt8=(T^hMs)phtuBt}i4ubuhOhNU#cX+EYNdmvQl%LmzcmGQCtxSu}X zgmk)DZm7by%<*jJ`%N$RE6oIuJzC!`lfHWu)L3XHAcf?l>I5Id}5cH8W+6{B)%ntD~wxBZFg zqu0=o#Ht3QH=V~7Q6;gbDffr~1{i7!^hlI-((r){=L!(sl>=jfDI0{H^t0`AuWp+& zw~WF|tZtaMmAApeSS`=_<{Ju&Z*LKK#b)vTJu`j{_g_0*X)6EUn#s*K;tn zzGKz@$42ru2mc8dm>=+jo1Y871q5*c1h{$rBI3)#O&x5_C7{+0mVn=^bqQDVdn*53 zm0ykA$8lf2H~s}cOr7N{ZLMwow~9L4(oqY*|J(e&Aor(mAN3u9-V$(6vHv^e{$6C@ z-+lhozPg(k{FlJMeJ*~xlr(j<{H0a!|LeRh%oPr?F@*s@+`rmVH2tg0#r+%j@5};z z<^J~yl!o5vlPzk83?H}M*L)x|$a2wY|GU;7^!N4NGZ4VT!}BYK zzhCcT{S()3-}j~aJHCHJ4gA$F(4EJ>_vd#s_cr&f{*rUJlVxzygxcP3Gyu2{@9!i1 z@7aAX9O3#as|vOjzjAtS@*iOcw|gClzo|2D{at!O73O5&W`4K10kgTOEzAkP#lgkP zaksFTZQyWcLC!mki#yaBX6kHXYwpV71hZyg`Q-_6xAg(s)(I+guaChjCCClr1_61v zfm{MW5Ri)vD8K{+vi#lY|B7q;(Yt_{-Ypd;>tD_N>cU@Y7yqk~;R&;}!UWz4Kwtv@ za{$1+ydYkH72r3<&BF)2%gFr!fc}Nu2}l6%rocZiu)tj={~H4Wx$dMu{u|>1^WCkb z|H8O=xcUC&gCEHKPaoVMo;y*Ff7pU}?kCtk+5-ab((zA>``>=~{~wqD&);m}Fw?uI z0qobd73#L$miM{3*UnILa=IJz`<(w?jPg*cyRp3=_+L}W6>bWH|H>{mkAMIelYv26 IMF#VK00}0YbN~PV literal 0 HcmV?d00001 diff --git a/jsk_2023_04_human_approach/euslisp/human_recog.l b/jsk_2023_04_human_approach/euslisp/human_recog.l index d8dbb9eef7..56eac441ad 100755 --- a/jsk_2023_04_human_approach/euslisp/human_recog.l +++ b/jsk_2023_04_human_approach/euslisp/human_recog.l @@ -3,135 +3,124 @@ (ros::load-ros-package "jsk_recognition_msgs") (ros::load-ros-package "speech_recognition_msgs") (load "package://spoteus/spot-interface.l") -(spot-init) +;;(spot-init) (ros::roseus "human_recog") -(send *ri* :angle-vector (send *spot* :reset-pose)) -(send *ri* :gripper-close) - (defun move-to-human (msg) + ;;(print "move-to-human-do") (let (rect-list distance max-rect) (setq rect-list (send msg :boxes)) (if (not (= (length rect-list) 0)) (progn - ;;(print "data-start") - (if (= (length rect-list) 1) - (setq max-rect (car rect-list)) - ) + (print "data-start") + (if (= (length rect-list) 1) + (setq max-rect (car rect-list)) + ) ;;(setq sorted-list (sort rect-list #'compare-distance-of-rects)) ;;(setq max-rect (car sorted-list)) - (setq max-rect (car rect-list)) - (setq *x* (send (send (send max-rect :pose) :position) :x)) - (setq *y* (send (send (send max-rect :pose) :position) :y)) - (setq *angle* (rad2deg (atan *y* *x*))) - (setq *human-to-spot-vector* (float-vector (* *x* -1) (* *y* -1) 0)) - (print *angle*) - (send *ri* :go-pos 0 0 *angle*) - (send *ri* :go-pos 1.0 0 0) - ) + (setq max-rect (car rect-list)) + (setq *x* (send (send (send max-rect :pose) :position) :x)) + (setq *y* (send (send (send max-rect :pose) :position) :y)) + (setq *angle* (rad2deg (atan *y* *x*))) + (setq *human-to-spot-vector* (float-vector (* *x* -1) (* *y* -1) 0)) + (print *angle*) + ;;;(send *ri* :go-pos 0 0 *angle*) + ;;;(send *ri* :go-pos 1.0 0 0) + ) ) ) ) (defun ask() - (send *ri* :gripper-open) - (send *ri* :angle-vector #f(0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 -170.0 150.0 0.0 10.0 45.0 0.0)) - (send *ri* :speak-jp "どちらに行きますか?") - (send *ri* :angle-vector (send *spot* :reset-pose)) - (send *ri* :gripper-close) + (print "ask-do") + ;; (send *ri* :angle-vector #f(0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 45.0 -90.0 0.0 -170.0 150.0 0.0 10.0 45.0 0.0)) + ;; (send *ri* :gripper-open) + ;; (send *ri* :speak-jp "どちらに行きますか? また、何かわからないことがありますか?") + ;; (unix::sleep 7) + ;; (send *ri* :angle-vector (send *spot* :reset-pose)) + ;; (send *ri* :gripper-close) ) - - (defun recognition-skeleton (msgs) - (if (= *speech-recog-res* 1) - (progn - (send *ri* :speak-jp "とまります。") - (move-to-human-call) - (ask) - (send *speech-recog-res* 0) - )) - (if (> *speech-recog-res* 1) - (progn - - (let (physical-order physical-reverse-order skeleton-list bone-names-list bones index target-bone start-point end-point) - (setq physical-order (list "right shoulder->right elbow" "right elbow->right wrist" "left shoulder->left elbow" "left elbow->left wrist")) - (setq physical-reverse-order (list "right eldow->right shoulder" "right wrist->right elbow" "left elbow->left shoulder" "left wrist->left elbow")) - - (ros::ros-info "skeletons ~A" (length (send msgs :skeletons))) - - (if (>= (length (send msgs :skeletons)) 1) - (progn - (setq skeleton-list (send msgs :skeletons)) - ;;(ros::ros-error "~A" skeleton-list) - - (dolist (skeleton skeleton-list) - (if (send skeleton :bone_names) - (progn - (setq bone-names-list (send skeleton :bone_names)) - (dolist (bone-name bone-names-list) - (print bone-name) - ;;(print (send skelton :bones) - (dolist (target-bone-name (append physical-order physical-reverse-order)) - (if (string= bone-name target-bone-name) - (progn - (setq bones (send skeleton :bones)) - - (setq index (position bone-name bone-names-list :test 'equal)) - (setq target-bone (elt bones index)) - - (cond ((find target-bone-name physical-order) - (progn - (setq start-point (send target-bone :start_point)) - (setq end-point (send target-bone :end_point)) - ;;(setq *purpose-vector* (v- (vector end-point) (vector start-point))) - )) - ((find bone-name physical-reverse-order) - (progn - (setq end-point (send target-bone :start_point)) - (setq start-point (send target-bone :end_point)) - ;;(setq *purpose-vector* (v- (vector start-point) (vector end-point))) - ))) - ;;(ros::ros-error "purpose-vector ~A" *purpose-vector*) - (setq *tfl* (instance ros::transform-listener :init)) - (send *tfl* :wait-for-transform "base_link" "hand_color_image_sensor" (ros::time 0) 1) - (setq tf-base-to-arm (send *tfl* :lookup-transform "base_link" "hand_color_image_sensor" (ros::time 0))) - ;;(setq target-vector (send tf-base-to-arm :transform-vector *purpose-vector*)) - ;;(send *ri* :angle-vector (send *spot* :head :look-at target-vector)) - - (setq tf-start-point (send tf-base-to-arm :transform-vector (vector start-point))) - (setq tf-end-point (send tf-base-to-arm :transform-vector (vector end-point))) - (print tf-start-point) - (print tf-end-point) - (setq target-vector (v- tf-end-point tf-start-point)) - (ros::ros-error "target-vector ~A" target-vector) - - ;;(send *ri* :go-pos (elt target-vector 0) (elt target-vector 1) 0) - (setq *target-vector-xy* (float-vector (elt target-vector 0) (elt target-vector 1) 0)) - ;;(setq *start-to-spot-vector* (float-vector (elt tf-start-point 0) (elt tf-start-point 1) 0)) - (send *ri* :go-pos 0 0 (degree-vector *start-to-spot-vector* *target-vector-xy*)) - (cond ((= *speech-recog-res* 2) - (progn - (send *ri* :speak-jp "これはキッチンです。") - )) - ((= *speech-recog-res* 3) - (progn - (send *ri* :speak-jp "いきましょう。ついてきてください。") - (send *ri* :go-pos 2.0 0 0) - ))) - (send *speech-recog-res* 0) - ))))))))))))) + (print "recog-skeleton-do") + (let (physical-order physical-reverse-order skeleton-list bone-names-list bones index target-bone) + (setq physical-order (list "right elbow->right wrist" "left elbow->left wrist")) + (setq physical-reverse-order (list "right wrist->right elbow" "left wrist->left elbow")) + (ros::ros-info "skeletons ~A" (length (send msgs :skeletons))) + (if (>= (length (send msgs :skeletons)) 1) + (progn + (setq skeleton-list (send msgs :skeletons)) + (dolist (skeleton skeleton-list) + (if (send skeleton :bone_names) + (progn + (setq bone-names-list (send skeleton :bone_names)) + (dolist (bone-name bone-names-list) + (print bone-name) + ;;(print (send skelton :bones) + + (dolist (target-bone-name (append physical-order physical-reverse-order)) + (if (string= bone-name target-bone-name) + (progn + (setq bones (send skeleton :bones)) + (setq index (position bone-name bone-names-list :test 'equal)) + (setq target-bone (elt bones index)) + + (cond ((find target-bone-name physical-order) + (progn + (setq *bone-start-point* (send target-bone :start_point)) + (setq *bone-end-point* (send target-bone :end_point)) + )) + ((find bone-name physical-reverse-order) + (progn + (setq *bone-end-point* (send target-bone :start_point)) + (setq *bone-start-point* (send target-bone :end_point)) + ))) + (tf-vector) + (send *ri* :go-pos 0 0 (degree-vector *human-to-spot-vector* *target-vector-xy*)) + (switch-mode) + (setq *skeleton-recog-flag* t) + (setq *speech-recog-res* 0) + )))))))))) + ) +(defun switch-mode() + (cond ((= *speech-recog-res* 2) + (progn + (send *ri* :speak-jp "これはキッチンです。") + (send *ri* :go-pos 0 0 (* -1 (degree-vector *human-to-spot-vector* *target-vector-xy*))))) + ((= *speech-recog-res* 3) + (progn + (send *ri* :speak-jp "いきましょう。ついてきてください。") + (unix::sleep 5) + (send *ri* :go-pos 2.0 0 0) + ))) + ) -(setq *speech-recog-res* 0) +(defun tf-vector() + (let (tf-base-to-arm tf-start-point tf-end-point target-vector) + (setq *tfl* (instance ros::transform-listener :init)) + (send *tfl* :wait-for-transform "base_link" "hand_color_image_sensor" (ros::time 0) 1) + (setq tf-base-to-arm (send *tfl* :lookup-transform "base_link" "hand_color_image_sensor" (ros::time 0))) + + (setq tf-start-point (send tf-base-to-arm :transform-vector (vector *bone-start-point*))) + (setq tf-end-point (send tf-base-to-arm :transform-vector (vector *bone-end-point*))) + (print tf-start-point) + (print tf-end-point) + (setq target-vector (v- tf-end-point tf-start-point)) + + (setq *target-vector-xy* (float-vector (elt target-vector 0) (elt target-vector 1) 0)) + ) + ) + (defun speech-recognition(msgs) (setq *recognition-word* (car (send msgs :transcript))) (print *recognition-word*) - (setq *stop-words-list* (list "止まって" "待って" "ストップ")) + (setq *stop-words-list* (list "止まって" "待って" "ストップ" "こっちに来て" "おいで")) (setq *what-is-it-list* (list "これは何ですか" "あれは何ですか" "これは何" "あれは何" "それは何")) (setq *where-list* (list "こっちに行きたいです ""あちらに行きたいです" "あっちに行きたいです" "そっちに行きたいです" "こっちに行きたい" "あっちに行きたい" "そっちに行きたい")) + (setq *finish-words-list* (list "終了" "終わり" "ありがとう")) (cond ((find *recognition-word* *stop-words-list* :test #'equal) (progn (ros::ros-error "true ~A" *recognition-word*) @@ -139,20 +128,28 @@ )) ((find *recognition-word* *what-is-it-list* :test #'equal) (progn - (send *ri* :speak-jp "承知しました。何をしりたいか指差しして教えてください。") + ;;(send *ri* :speak-jp "承知しました。何をしりたいか指差しして教えてください。") (setq *speech-recog-res* 2) + (unix::sleep 10) )) ((find *recognition-word* *where-list* :test #'equal) (progn - (send *ri* :speak-jp "承知しました。どちらに行きたいか指差しして教えてください") + ;;(send *ri* :speak-jp "承知しました。どちらに行きたいか指差しして教えてください") (setq *speech-recog-res* 3) - ))) + (unix::sleep 10) + )) + ((find *recognition-word* *finish-words-list* :test #'equal) + (progn + ;;(send *ri* :speak-jp "これにて終了します。お疲れ様でした。") + (setq *speech-recog-flag* t) + )) + ) + (ros::ros-error "~A" *speech-recog-res*) ) (defun vector (a) (float-vector (send a :x) (send a :y) (send a :z)) ) - (defun compare-distance-of-rects (a b) (>= (norm (send (send a :pose) :position)) (norm (send (send a :pose) :position))) @@ -162,11 +159,10 @@ (rad2deg (acos (/ (v. a b) (* (norm a) (norm b))))) ) - - (ros::roseus-add-srvs "topic_tools") (defun call-service-coral (req-topic) (ros::wait-for-service "/coral_input/image/select") + ;; when input image has not come successfully, wait-for-service hang at this point. (setq req (instance topic_tools::MuxSelectRequest :init)) (send req :topic req-topic) (ros::service-call "/coral_input/image/select" req) @@ -182,7 +178,9 @@ (defun move-to-human-call () (call-service-coral "/dual_fisheye_to_panorama/output") + (print "call-coral-human") (call-service-edgetpu "edgetpu_panorama_object_detector") + (print "call-edgetpu-human") (setq *human* (one-shot-subscribe "/rect_array_in_panorama_to_bounding_box_array/bbox_array" jsk_recognition_msgs::BoundingBoxArray)) (move-to-human *human*) ) @@ -191,7 +189,7 @@ (ros::ros-error "recog-skeleton-call") ;;(call-service-coral "/spot/camera/hand_color/image") (call-service-coral "/camera/color/image_raw") - (print "call-coral") + (print "call-coral-skeleton") (call-service-edgetpu "edgetpu_human_pose_estimator") ;;(setq *skeleton* (one-shot-subscribe "/skeleton_with_depth/output/skeleton" jsk_recognition_msgs::HumanSkeletonArray)) ;;(recognition-skeleton *skeleton*) @@ -199,21 +197,42 @@ ) -(defun main () +(defun main() + (initialization-and-move) (ros::subscribe "/speech_to_text" speech_recognition_msgs::SpeechRecognitionCandidates #'speech-recognition) - (move-to-human-call) + (until *speech-recog-flag* + (cond ((= *speech-recog-res* 1) + (progn + ;;(send *ri* :speak-jp "とまります。") + ;;(send *ri* :go-pos 0 0 0) + (move-to-human-call) + ;;(move-to-human) + )) + ((> *speech-recog-res* 1) + (progn + (until *skeleton-recog-flag* + (recognition-skeleton-call) + ;;(recognition-skeleton) + ;;(ros::unsubscribe "/skeleton_with_depth/output/skeleton") + )))) + (ros::spin-once) + ;;(print "*speech-recog-res*: ~A" *speech-recog-res*) + (ros::sleep)) + ) + +(defun initialization-and-move() + (setq *speech-recog-flag* nil) + (setq *skeleton-recog-flag* nil) + (setq *speech-recog-res* 0) + ;;(send *ri* :angle-vector (send *spot* :reset-pose)) + ;;(send *ri* :gripper-close) + (move-to-human) (print "human-call-done") - (ask) - (print "ask-done") - (recognition-skeleton-call) - (ros::spin) + ;;(ask) + ;;(print "ask-done") ) (main) - - - - diff --git a/jsk_2023_04_human_approach/euslisp/skeleton_test.l b/jsk_2023_04_human_approach/euslisp/skeleton_test.l new file mode 100755 index 0000000000..17dcaba54a --- /dev/null +++ b/jsk_2023_04_human_approach/euslisp/skeleton_test.l @@ -0,0 +1,134 @@ +#!/usr/bin/env roseus + +(ros::load-ros-package "jsk_recognition_msgs") +(ros::load-ros-package "speech_recognition_msgs") +(load "package://spoteus/spot-interface.l") +(ros::roseus "human_recog") + +(defun move-to-human (msg) + (let (rect-list distance max-rect) + (setq rect-list (send msg :boxes)) + (if (not (= (length rect-list) 0)) + (progn + ;;(print "data-start") + (if (= (length rect-list) 1) + (setq max-rect (car rect-list)) + ) + (setq sorted-list (sort rect-list #'compare-distance-of-rects)) + (setq max-rect (car sorted-list)) + (setq *x* (send (send (send max-rect :pose) :position) :x)) + (setq *y* (send (send (send max-rect :pose) :position) :y)) + (setq *angle* (rad2deg (atan *y* *x*))) + (setq *human-to-spot-vector* (float-vector (* *x* -1) (* *y* -1) 0)) + (print *angle*) + (send *ri* :go-pos 0 0 *angle*) + (send *ri* :go-pos 1.0 0 0) + ) + ) + ) + ) + + +(defun recognition-skeleton (msgs) + ;;(send *ri* :gripper-open) + ;;(send *ri* :angle-vector (send *spot* :reset-pose)) + (let (physical-order physical-reverse-order skeleton-list bone-names-list bones index target-bone start-point end-point) + (setq physical-order (list "right shoulder->right elbow" "right elbow->right wrist" "left shoulder->left elbow" "left elbow->left wrist")) + (setq physical-reverse-order (list "right eldow->right shoulder" "right wrist->right elbow" "left elbow->left shoulder" "left wrist->left elbow")) + + (ros::ros-info "skeletons ~A" (length (send msgs :skeletons))) + + (if (>= (length (send msgs :skeletons)) 1) + (progn + (setq skeleton-list (send msgs :skeletons)) + ;;(ros::ros-error "~A" skeleton-list) + + (dolist (skeleton skeleton-list) + (if (send skeleton :bone_names) + (progn + (setq bone-names-list (send skeleton :bone_names)) + (dolist (bone-name bone-names-list) + (print bone-name) + ;;(print (send skelton :bones) + (dolist (target-bone-name (append physical-order physical-reverse-order)) + (if (string= bone-name target-bone-name) + (progn + (setq bones (send skeleton :bones)) + (ros::ros-error "target-bone ~A" bone-name) + + (setq index (position bone-name bone-names-list :test 'equal)) + (setq target-bone (elt bones index)) + + (cond ((find target-bone-name physical-order) + (progn + (setq start-point (send target-bone :start_point)) + (setq end-point (send target-bone :end_point)) + (setq *purpose-vector* (v- (vector end-point) (vector start-point))) + (print *purpose-vector*) + )) + ((find bone-name physical-reverse-order) + (progn + (setq end-point (send target-bone :start_point)) + (setq start-point (send target-bone :end_point)) + ;;(setq *purpose-vector* (v- (vector start-point) (vector end-point))) + )) + ) + ;;(ros::ros-error "purpose-vector ~A" *purpose-vector*) + ;;(setq *tfl* (instance ros::transform-listener :init)) + ;;(send *tfl* :wait-for-transform "base_link" "hand_color_image_sensor" (ros::time 0) 1) + ;;(setq tf-base-to-arm (send *tfl* :lookup-transform "base_link" "hand_color_image_sensor" (ros::time 0))) + ;;(setq target-vector (send tf-base-to-arm :transform-vector *purpose-vector*)) + ;;(send *ri* :angle-vector (send *spot* :head :look-at target-vector)) + + ;;(setq tf-start-point (send tf-base-to-arm :transform-vector (vector start-point))) + ;;(setq tf-end-point (send tf-base-to-arm :transform-vector (vector end-point))) + ;;(print tf-start-point) + ;;(print tf-end-point) + ;;(setq target-vector (v- tf-end-point tf-start-point)) + ;;(ros::ros-error "target-vector ~A" target-vector) + + ;;(send *ri* :go-pos (elt target-vector 0) (elt target-vector 1) 0) + ;;(setq *target-vector-xy* (float-vector (elt target-vector 0) (elt target-vector 1) 0)) + ;;(setq *start-to-spot-vector* (float-vector (elt tf-start-point 0) (elt tf-start-point 1) 0)) + ;;(send *ri* :go-pos 0 0 (degree-vector *start-to-spot-vector* *target-vector-xy*)) + ))))))))))) + +(defun vector (a) + (float-vector (send a :x) (send a :y) (send a :z)) + ) + + +(defun compare-distance-of-rects (a b) + (>= (norm (send (send a :pose) :position)) (norm (send (send a :pose) :position))) + ) + +(defun degree-vector (a b) + (rad2deg (acos (/ (v. a b) (* (norm a) (norm b))))) + ) + +(ros::roseus-add-srvs "topic_tools") +(defun call-service-coral (req-topic) + (ros::wait-for-service "/coral_input/image/select") + (setq req (instance topic_tools::MuxSelectRequest :init)) + (send req :topic req-topic) + (ros::service-call "/coral_input/image/select" req) + ) + +(ros::roseus-add-srvs "coral_usb") +(defun call-service-edgetpu (req-topic) + (ros::wait-for-service "/edgetpu_node_manager/start") + (setq req-1 (instance coral_usb::StartNodeRequest :init)) + (send req-1 :name req-topic) + (ros::service-call "/edgetpu_node_manager/start" req-1) + ) + + + +;;(call-service-coral "/spot/camera/hand_color/image") +(call-service-coral "/camera/color/image_raw") +(call-service-edgetpu "edgetpu_human_pose_estimator") +;;(setq *skeleton* (one-shot-subscribe "/skeleton_with_depth/output/skeleton" jsk_recognition_msgs::HumanSkeletonArray)) +;;(recognition-skeleton *skeleton*) +(ros::subscribe "/skeleton_with_depth/output/skeleton" jsk_recognition_msgs::HumanSkeletonArray #'recognition-skeleton) + +(ros::spin) diff --git a/jsk_2023_04_human_approach/launch/#recognition.launch# b/jsk_2023_04_human_approach/launch/#recognition.launch# new file mode 100644 index 0000000000..5940ce9b95 --- /dev/null +++ b/jsk_2023_04_human_approach/launch/#recognition.launch# @@ -0,0 +1,71 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + frame_fixed: "rear_rail" + image_transport: compressed + dimensions_labels: + person: [0.5, 0.5, 1.5] + + + + + + + + + + + + + + + + + + + + + + + + + + + + --> + + + + +