diff --git a/.github/labeler_conf/develop_fetch_labeler.yml b/.github/labeler_conf/develop_fetch_labeler.yml new file mode 100644 index 0000000000..e0fe1fbe40 --- /dev/null +++ b/.github/labeler_conf/develop_fetch_labeler.yml @@ -0,0 +1,2 @@ +develop/fetch: + - '**' diff --git a/.github/workflows/develop_fetch_labeler.yml b/.github/workflows/develop_fetch_labeler.yml new file mode 100644 index 0000000000..f85a2a913d --- /dev/null +++ b/.github/workflows/develop_fetch_labeler.yml @@ -0,0 +1,16 @@ +name: "Pull Request Labeler for develop/fetch" +on: + pull_request_target: + branches: + - develop/fetch + +jobs: + triage: + runs-on: ubuntu-latest + steps: + - uses: actions/labeler@v4.1.0 + with: + configuration-path: ".github/labeler_conf/develop_fetch_labeler.yml" + repo-token: "${{ secrets.GITHUB_TOKEN }}" + sync-labels: true + dot: true diff --git a/jsk_fetch_robot/README.md b/jsk_fetch_robot/README.md index 9aab1b786d..51c6144640 100644 --- a/jsk_fetch_robot/README.md +++ b/jsk_fetch_robot/README.md @@ -33,26 +33,49 @@ ## How to Run +### Setup Environment (For Remote PC) -### Setup Environment - -First, you need to install ros. For ros indigo, please refer to install guide like [here](http://wiki.ros.org/indigo/Installation/Ubuntu) +First, you need to install ROS. For ROS melodic, please refer to install guide like [here](http://wiki.ros.org/melodic/Installation/Ubuntu). +Please make sure your ROS Distribution is indigo, kinetic or melodic. ```bash mkdir -p catkin_ws/src cd catkin_ws/src wstool init . -wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -y -if [[ $ROS_DISTRO =~ ^(indigo|kinetic|melodic)$ ]]; then - wstool merge -t . https://raw.githubusercontent.com/jsk-ros-pkg/jsk_robot/master/jsk_fetch_robot/jsk_fetch_user.rosinstall.$ROS_DISTRO -else - echo "Your ROS distribution $ROS_DISTRO is not supported." -fi +wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -v develop/fetch -y +wstool merge -t . https://raw.githubusercontent.com/jsk-ros-pkg/jsk_robot/master/jsk_fetch_robot/jsk_fetch_user.rosinstall.$ROS_DISTRO + +# (optional): the two lines below are necessary when you want to use roseus_resume +wstool merge -t . https://gist.githubusercontent.com/Affonso-Gui/25518fef9dc7af0051147bdd2a94b116/raw/e3fcbf4027c876329801a25e32f4a4746200ddae/guiga_system.rosinstall wstool update -t . + +# (optional): the two lines below are necessary when you want to use eus10 +wget https://raw.githubusercontent.com/jsk-ros-pkg/jsk_roseus/master/setup_upstream.sh -O /tmp/setup_upstream.sh +bash /tmp/setup_upstream.sh -w ../ -p jsk-ros-pkg/geneus -p euslisp/jskeus + source /opt/ros/$ROS_DISTRO/setup.bash rosdep install -y -r --from-paths . --ignore-src cd ../ +# (optional): if you want to use roseus_resume, build roseus_resume, too. catkin build fetcheus jsk_fetch_startup + +source devel/setup.bash +``` + +#### Setup Environment (For Robot Internal PC, only for advanced developer) + +```bash +mkdir -p catkin_ws/src +cd catkin_ws/src +wstool init . +wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -v develop/fetch -y +wstool update -t . +wstool merge -t . jsk-ros-pkg/jsk_robot/jsk_fetch_robot/jsk_fetch.rosinstall.$ROS_DISTRO +wstool update -t . +source /opt/ros/$ROS_DISTRO/setup.bash +rosdep install -y -r --from-paths . --ignore-src +cd ../ +catkin build source devel/setup.bash ``` diff --git a/jsk_fetch_robot/fetcheus/fetch-interface.l b/jsk_fetch_robot/fetcheus/fetch-interface.l index 5dd33840df..238d964a7f 100644 --- a/jsk_fetch_robot/fetcheus/fetch-interface.l +++ b/jsk_fetch_robot/fetcheus/fetch-interface.l @@ -22,11 +22,11 @@ (defclass fetch-interface :super robot-move-base-interface - :slots (gripper-action moveit-robot fetch-controller-action) + :slots (gripper-action moveit-robot fetch-controller-action point-head-action) ) (defmethod fetch-interface - (:init (&key (default-collision-object t) &rest args) + (:init (&rest args &key (default-collision-object t) &allow-other-keys) (prog1 (send-super* :init :robot fetch-robot :base-frame-id "base_link" :odom-topic "/odom_combined" :base-controller-action-name nil args) (send self :add-controller :arm-controller) (send self :add-controller :torso-controller) @@ -43,16 +43,18 @@ (setq moveit-robot (instance fetch-robot :init)) (send self :set-moveit-environment (instance fetch-moveit-environment :init :robot moveit-robot)) (when (and (boundp '*co*) default-collision-object) - (send self :delete-headbox-collision-object) (send self :delete-keepout-collision-object) (send self :delete-ground-collision-object) - (send self :add-headbox-collision-object) (send self :add-keepout-collision-object) (send self :add-ground-collision-object)) (setq fetch-controller-action (instance ros::simple-action-client :init "/query_controller_states" robot_controllers_msgs::QueryControllerStatesAction)) + (setq point-head-action + (instance ros::simple-action-client :init + "/head_controller/point_head" + control_msgs::PointHeadAction)) )) (:state (&rest args) "We do not have :wait-until-update option for :state :worldcoords. @@ -131,8 +133,8 @@ Example usage: (subseq args (+ (position :use-torso args) 2)))))) (return-from :angle-vector (send* self :angle-vector-raw av tm ctype start-time args))) ;; - (when (not (numberp tm)) - (ros::warn ":angle-vector tm is not a number, use :angle-vector av tm args")) + (when (and (not (numberp tm)) (not (eql tm :fast))) + (ros::warn ":angle-vector tm is not a number, use :angle-vector av tm args~%")) (send* self :angle-vector-motion-plan av :ctype ctype :move-arm :rarm :total-time tm :start-offset-time (if start-offset-time start-offset-time start-time) :clear-velocities clear-velocities :use-torso use-torso args))) @@ -205,6 +207,17 @@ Example usage: (:stop-grasp (&rest args &key &allow-other-keys) (send* self :go-grasp :pos 0.1 args)) + (:point-head (pos &key (frame-id "base_link") (wait t)) + (let ((goal (instance control_msgs::PointHeadGoal :init))) + (send goal :target :header :stamp (ros::time-now)) + (send goal :target :header :frame_id frame-id) + (send goal :target :point (ros::pos->tf-point pos)) + (if wait + (send point-head-action :send-goal goal) + (send point-head-action :send-goal-and-wait goal) + ) + ) + ) (:go-grasp (&key (pos 0) (effort 50) (wait t)) (when (send self :simulation-modep) @@ -257,18 +270,6 @@ Example: (send self :gripper :position) => 0.00" (:delete-workspace () (send *co* :delete-attached-object-by-id "workspace") (send *co* :delete-object-by-id "workspace")) - (:add-headbox-collision-object () - (let () - ;; fetch must be :reset-pose when we run this method - (setq *fetch-headbox* (make-cube 100 201 120)) - (send *fetch-headbox* :move-coords (send robot :head_pan_link_lk :worldcoords) - (send robot :base_link_lk :worldcoords)) - (send *fetch-headbox* :translate #f(33.75 0 150) (send robot :head_pan_link_lk :worldcoords)) - (send *co* :add-attached-object *fetch-headbox* "head_pan_link" - :frame_id "head_pan_link" - :object_id "fetchheadbox"))) - (:delete-headbox-collision-object () - (send *co* :delete-attached-object-by-id "fetchheadbox")) (:add-keepout-collision-object () (let ((cube (make-cube 200 350 10)) (keepout (make-cylinder 300 10))) diff --git a/jsk_fetch_robot/fetcheus/fetch-utils.l b/jsk_fetch_robot/fetcheus/fetch-utils.l index ea4a1d27e2..67932a47fe 100644 --- a/jsk_fetch_robot/fetcheus/fetch-utils.l +++ b/jsk_fetch_robot/fetcheus/fetch-utils.l @@ -5,16 +5,40 @@ (defmethod fetch-robot (:inverse-kinematics - (target-coords &rest args &key link-list move-arm (use-torso t) move-target &allow-other-keys) + (target-coords &rest args &key link-list move-arm (use-torso t) + use-base (start-coords (send self :copy-worldcoords)) + (base-range (list :min #f(-30 -30 -30) + :max #f( 30 30 30))) + move-target &allow-other-keys) (unless move-arm (setq move-arm :rarm)) (unless move-target (setq move-target (send self :rarm :end-coords))) (unless link-list (setq link-list (send self :link-list (send move-target :parent) (unless use-torso (car (send self :rarm)))))) - (send-super* :inverse-kinematics target-coords - :move-target move-target - :link-list link-list - args)) + (cond + (use-base + (let ((diff-pos-rot + (concatenate float-vector + (send start-coords :difference-position self) + (send start-coords :difference-rotation self)))) + (send self :move-to start-coords :world) + (with-append-root-joint + (ll self link-list + :joint-class omniwheel-joint + :joint-args base-range) + (send (caar ll) :joint :joint-angle + (float-vector (elt diff-pos-rot 0) + (elt diff-pos-rot 1) + (rad2deg (elt diff-pos-rot 5)))) + (send-super* :inverse-kinematics target-coords + :move-target move-target + :link-list ll ;; link-list + args)))) + (t + (send-super* :inverse-kinematics target-coords + :move-target move-target + :link-list link-list + args)))) (:go-grasp (&key (pos 0)) ;; pos is between 0.0 and 0.1 (send self :l_gripper_finger_joint :joint-angle (/ (* pos 1000) 2)) ;; m -> mm diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 2ecfc0bdfb..5f505796b3 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -5,10 +5,12 @@ # https://github.com/PR2/app_manager/pull/50 # In order to run multiple app_managers in one master, we need this PR # https://github.com/PR2/app_manager/pull/54 +# This PR add run_name entry to specif node name when we use run entry +# https://github.com/PR2/app_manager/pull/64 - git: local-name: PR2/app_manager - uri: https://github.com/knorth55/app_manager.git - version: fetch15 + uri: https://github.com/tkmtnt7000/app_manager.git + version: add-run-name-entry-fetch15 # we need this for proximity sensors - git: local-name: RoboticMaterials/FA-I-sensor @@ -70,7 +72,7 @@ local-name: jsk-ros-pkg/jsk_recognition uri: https://github.com/jsk-ros-pkg/jsk_recognition.git version: master -# we need to use the development branch (fetch15 branch in knorth55's fork) +# we need to use the development branch (develop/fetch branch in jsk-ros-pkg) # until it is merged to master - git: local-name: jsk-ros-pkg/jsk_robot @@ -185,3 +187,15 @@ local-name: BehaviorTree/BehaviorTree.ROS uri: https://github.com/BehaviorTree/BehaviorTree.ROS version: master +# we need this for smart device ros system +- git: + local-name: sktometometo/smart_device_protocol + uri: https://github.com/sktometometo/smart_device_protocol.git + version: v0.5.1 +# melodic version of robot_localization causes TF_REPEATED_DATA Errors to noetic client +# So we have to adopt https://github.com/cra-ros-pkg/robot_localization/pull/595 (Using noetic-devel causes some localization trouble) +# After https://github.com/cra-ros-pkg/robot_localization/pull/840 has been merged, we can use upstream melodic-devel branch +- git: + local-name: cra-ros-pkg/robot_localization + uri: https://github.com/mqcmd196/robot_localization.git + version: 2.6.9-suppress diff --git a/jsk_fetch_robot/jsk_fetch_accessories/finger_tip_collision/finger_tip_collision.STL b/jsk_fetch_robot/jsk_fetch_accessories/finger_tip_collision/finger_tip_collision.STL new file mode 100644 index 0000000000..ff1925fd32 Binary files /dev/null and b/jsk_fetch_robot/jsk_fetch_accessories/finger_tip_collision/finger_tip_collision.STL differ diff --git a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt index be9259dac6..41d435037b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt +++ b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt @@ -10,16 +10,47 @@ endif() ## 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) +find_package(catkin REQUIRED COMPONENTS + dynamic_reconfigure + roscpp + std_msgs + sensor_msgs + geometry_msgs + tf + tf2 + tf2_geometry_msgs + tf2_ros + tf2_eigen + tf2_msgs +) +find_package(Boost REQUIRED COMPONENTS) + +generate_dynamic_reconfigure_options( + cfg/TimeSignal.cfg +) ################################### ## catkin specific configuration ## ################################### -catkin_package() +catkin_package( + CATKIN_DEPENDS dynamic_reconfigure +) catkin_add_env_hooks(99.jsk_fetch_startup SHELLS bash zsh sh DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/env-hooks) +########### +## Build ## +########### +include_directories( + ${catkin_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} +) +add_executable(trashbins_pose_estimator src/trashbins_pose_estimator.cpp) +target_link_libraries(trashbins_pose_estimator + ${catkin_LIBRARIES} +) + ############# ## Install ## ############# @@ -51,8 +82,38 @@ macro(configure_icon_files icol iname) endif() endmacro(configure_icon_files) +macro(configure_dialogflow_hotword_yaml dname) + set(FETCH_NAME ${dname}) + if (${FETCH_NAME} STREQUAL "fetch15") + set(ROBOT_NICKNAME_KANA "ヘンゼル") + set(ROBOT_NICKNAME_HIRA "へんぜる") + configure_file(${CMAKE_CURRENT_SOURCE_DIR}/config/dialogflow_hotword.yaml.in + ${CMAKE_CURRENT_SOURCE_DIR}/config/${FETCH_NAME}_dialogflow_hotword.yaml) + elseif (${FETCH_NAME} STREQUAL "fetch1075") + set(ROBOT_NICKNAME_KANA "グレーテル") + set(ROBOT_NICKNAME_HIRA "ぐれーてる") + configure_file(${CMAKE_CURRENT_SOURCE_DIR}/config/dialogflow_hotword.yaml.in + ${CMAKE_CURRENT_SOURCE_DIR}/config/${FETCH_NAME}_dialogflow_hotword.yaml) + endif() +endmacro(configure_dialogflow_hotword_yaml) + +macro(configure_email_topic_yaml rname) + cmake_host_system_information(RESULT FETCH_NAME QUERY HOSTNAME) + if (${FETCH_NAME} MATCHES ^${rname}) + set(RECEIVER_MAIL ${rname}) + set(EMAIL_SENDER_ADDRESS ${FETCH_NAME}@jsk.imi.i.u-tokyo.ac.jp) + set(EMAIL_RECEIVER_ADDRESS ${RECEIVER_MAIL}@jsk.imi.i.u-tokyo.ac.jp) + configure_file(${CMAKE_CURRENT_SOURCE_DIR}/config/email_topic.yaml.in + ${CMAKE_CURRENT_SOURCE_DIR}/config/${FETCH_NAME}_email_topic.yaml) + endif() +endmacro(configure_email_topic_yaml) + + configure_icon_files(blue fetch15) configure_icon_files(red fetch1075) +configure_dialogflow_hotword_yaml(fetch15) +configure_dialogflow_hotword_yaml(fetch1075) +configure_email_topic_yaml(fetch) ############# diff --git a/jsk_fetch_robot/jsk_fetch_startup/README.md b/jsk_fetch_robot/jsk_fetch_startup/README.md index a509050a34..d23cac2634 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/README.md +++ b/jsk_fetch_robot/jsk_fetch_startup/README.md @@ -1,5 +1,28 @@ # jsk_fetch_startup +- [jsk_fetch_startup](#jsk_fetch_startup) + - [SetUp (Running following commands in the first time)](#setup-running-following-commands-in-the-first-time) + - [Install a udev rule](#install-a-udev-rule) + - [For realsense](#for-realsense) + - [supervisor](#supervisor) + - [cron](#cron) + - [mongodb](#mongodb) + - [Teleoperation](#teleoperation) + - [Maintenance](#maintenance) + - [re-roslaunch jsk_fetch_startup fetch_bringup.launch](#re-roslaunch-jsk_fetch_startup-fetch_bringuplaunch) + - [re-roslaunch fetch_bringup fetch.launch](#re-roslaunch-fetch_bringup-fetchlaunch) + - [Clock Synchronization](#clock-synchronization) + - [Network](#network) + - [General description](#general-description) + - [Case description](#case-description) + - [Access point](#access-point) + - [Log](#log) + - [Apps](#apps) + - [Note](#note) + - [Add fetch to rwt_app_chooser](#add-fetch-to-rwt_app_chooser) + - [Execute demos](#execute-demos) + - [Administration](#administration) + ## SetUp (Running following commands in the first time) ### Install a udev rule @@ -7,80 +30,137 @@ rosrun jsk_fetch_startup install_udev.sh ``` -#### For realsense -udev rule have to be manually installed according to [this issue](https://github.com/IntelRealSense/realsense-ros/issues/1426) when using realsense-ros from ROS repository. +### For realsense + +Before start this, remove `librealsense2` and `realsense2-ros` from ROS repository and set not to be installed. + +```bash +sudo apt purge ros-melodic-librealsense2* ros-melodic-realsense* +sudo apt-mark hold ros-melodic-librealsense2 ros-melodic-realsense2-camera +``` + +After that, please add Intel repository and install `librealsense2` packages. (see [this page](https://github.com/IntelRealSense/librealsense/blob/master/doc/distribution_linux.md#installing-the-packages)) + +```bash +sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE || sudo apt-key adv --keyserver hkp://keyserver.ubuntu.com:80 --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE +sudo add-apt-repository "deb https://librealsense.intel.com/Debian/apt-repo $(lsb_release -cs) main" -u +sudo apt install librealsense2=2.45.0-0~realsense0.4551 +sudo apt install librealsense2-dev=2.45.0-0~realsense0.4551 +sudo apt-mark hold librealsense2 librealsense2-dev +``` + +### Install config.bash + +JSK fetch system uses some enviroment variables. To set them, copy `config.bash` to `/var/lib/robot/config.bash` and modify it. + +```bash +roscd jsk_fetch_startup +sudo cp config/config.bash /var/lib/robot/config.bash +``` + +descriptions of each variable are below. + +- `USE_BASE_CAMERA_MOUNT` + + Flag for robot model +- `USE_HEAD_BOX` + + Flag for robot model +- `USE_HEAD_L515` + + Flag for robot model +- `USE_INSTA360_STAND` + + Flag for robot model +- `RS_SERIAL_NO_T265` + + Serial number of Realsense T265 for visual odometry. + + realsense will not be launched when this is blank. +- `RS_SERIAL_NO_D435_FRONTRIGHT` + + Serial number of Realsense D435 on the base + + realsense will not be launched when this is blank. +- `RS_SERIAL_NO_D435_FRONTLEFT` + + Serial number of Realsense D435 on the base + + realsense will not be launched when this is blank. +- `RS_SERIAL_NO_L515_HEAD` + + Serial number of Realsense L515 on the head + + realsense will not be launched when this is blank. +- `NETWORK_DEFAULT_WIFI_INTERFACE` + + Wi-Fi network interface for network management scripts (e.g. `network_monitor.py` and `network-log-wifi.sh`) +- `NETWORK_DEFAULT_PROFILE_ID` + + Network manager profile ID for network management scripts (`network_monitor.py`) ++ `NETWORK_DEFAULT_ROS_INTERFACE` + + Network interface or IP address or hostname which is used for ROS connection. + + `rossetclient $NETWORK_DEFAULT_ROS_INTERFACE` is executed to set `ROS_IP` or `ROS_HOSTNAME`. + +It is also recommended to add lines below to each users's bashrc in the robot PC. ```bash -wget https://github.com/IntelRealSense/librealsense/raw/master/config/99-realsense-libusb.rules -sudo mv 99-realsense-libusb.rules /etc/udev/rules.d/ -sudo udevadm control --reload-rules && sudo udevadm trigger +source /var/lib/robot/config.bash +rossetmaster localhost +rossetip $NETWORK_DEFAULT_ROS_INTERFACE ``` ### supervisor + Important jobs for fetch operation are managed by supervisor. Here is a list of jobs that are managed by supervisor. - - roscore +- roscore Start roscore - - robot +- robot Launch Minimum ROS programs to run fetch - - jsk-fetch-startup +- jsk-fetch-startup Launch ROS programs extended by JSK - - jsk-network-monitor +- jsk-network-monitor Restart the network manager automatically if ping does not work. - - jsk-log-wifi +- jsk-log-wifi Monitor network condition - - jsk-app-scheduler +- jsk-app-scheduler Scheduler to launch [app](https://github.com/knorth55/app_manager_utils/tree/master/app_scheduler) at a fixed time - - jsk-object-detector +- jsk-object-detector Object detection using fetch's head camera and [coral_usb_ros](https://github.com/knorth55/coral_usb_ros) - - jsk-panorama-object-detector: +- jsk-panorama-object-detector: Object detection using fetch's 360 camera and [coral_usb_ros](https://github.com/knorth55/coral_usb_ros) - - jsk-human-pose-estimator +- jsk-human-pose-estimator Human pose estimation using fetch's head camera and [coral_usb_ros](https://github.com/knorth55/coral_usb_ros) - - jsk-panorama-human-pose-estimator +- jsk-panorama-human-pose-estimator Human pose estimation using fetch's 360 camera and [coral_usb_ros](https://github.com/knorth55/coral_usb_ros) - - jsk-dialog +- jsk-dialog Launch [dialogflow_task_exective](https://github.com/jsk-ros-pkg/jsk_3rdparty/tree/master/dialogflow_task_executive) - - jsk-gdrive +- jsk-gdrive Launch [app](https://github.com/knorth55/app_manager_utils/tree/master/app_uploader) to upload data to Goole Drive - - jsk-dstat +- jsk-dstat Monitor fetch's resource using dstat command - - jsk-lifelog +- jsk-lifelog Launch program to save fetch's [lifelog](https://github.com/jsk-ros-pkg/jsk_robot/tree/master/jsk_robot_common/jsk_robot_startup/lifelog) - Install supervisor config files. e.g. `robot.conf`, `jsk_fetch_startup.conf` ... -``` +```bash su -c 'rosrun jsk_fetch_startup install_supervisor.sh' ``` @@ -90,17 +170,17 @@ Previously, upstart was used, but it has been moved to supervisor. This is becau ![supervisor_status](https://user-images.githubusercontent.com/19769486/119499716-f142c000-bda1-11eb-9b96-0cfa7e04a1b2.png) - ### cron + Install cron jobs for root user and fetch user. e.g. `shutdown`, `update_workspace`. -``` +```bash su -c 'rosrun jsk_fetch_startup install_cron.sh' ``` ### mongodb -``` +```bash sudo mkdir -p /var/lib/robot/mongodb_store/ # to see the db items from http://lcoalhost/rockmongo @@ -112,11 +192,7 @@ sudo mv rockmongo-1.1.7 /var/www/html/rockmongo # $MONGO["servers"][$i]["control_auth"] = false; // true;//enable control users, works only if mongo_auth=false ``` -### Coral Edge TPU -Create ROS workspace for Coral Edge TPU. Please see: -https://github.com/knorth55/coral_usb_ros - -### Teleoperation +## Teleoperation For the JSK safe teleop system, please see [data flow diagram of safe_teleop.launch](https://github.com/jsk-ros-pkg/jsk_robot/tree/master/jsk_robot_common/jsk_robot_startup#launchsafe_teleoplaunch) @@ -128,19 +204,22 @@ The numbers assigned to the joystick are as follows. ## Maintenance ### re-roslaunch jsk_fetch_startup fetch_bringup.launch -``` + +```bash sudo supervisorctl restart jsk-fetch-startup ``` ### re-roslaunch fetch_bringup fetch.launch -``` + +```bash sudo supervisorctl restart robot ``` ### [Clock Synchronization](https://github.com/fetchrobotics/docs/blob/0c1c63ab47952063bf60280e74b4ff3ae07fd914/source/computer.rst) install `chrony` and add ```server `gethostip -d fetch15` offline minpoll 8``` to /etc/chrony/chrony.conf, restart chronyd by `sudo /etc/init.d/chrony restart` and wait for few seconds, if you get -``` + +```bash $ chronyc tracking Reference ID : 133.11.216.145 (fetch15.jsk.imi.i.u-tokyo.ac.jp) Stratum : 4 @@ -156,21 +235,22 @@ Root dispersion : 0.018803 seconds Update interval : 2.1 seconds Leap status : Normal ``` -it works, if you get `127.127.1.1` for `Reference ID`, something wrong +it works, if you get `127.127.1.1` for `Reference ID`, something wrong ## Network + ### General description + Fetch has wired and wireless network connections. If we use both of wired and wireless connections as DHCP, DNS holds two IP addresses for same hostname (fetch15 in this case). This cause problems in network such as ROS communication or ssh connection. -The solution we take now (2016/11/01) is using wired connection as static IP. -By doing so, DNS holds only one IP adress (for wireless connection) for fetch hostname. - ### Case description + If you see the following result, it is OK. -``` + +```bash $ nslookup fetch15.jsk.imi.i.u-tokyo.ac.jp Server: 127.0.1.1 Address: 127.0.1.1#53 @@ -180,24 +260,70 @@ Address: 133.11.216.145 ``` If two or more IP addresses apper, something is wrong. -Please connect display, open a window of network manager, and check that wired connection uses static IP. +Please connect display, open a window of network manager. -### Access point -Define access point setting, such as ssid: -``` +### Network configuration + +Ubuntu 18.04 uses [NetworkManager](https://wiki.archlinux.jp/index.php/NetworkManager) for network configuration. +Network manager's profiles are in `/etc/NetworkManager/system-connections`. + +```bash cd /etc/NetworkManager/system-connections ``` -### Log +You can also see profiles with `nmcli`, `nmtui` or `nm-connection-editor` (GUI) command. + +To see available connection profiles. + +```bash +fetch@fetch1075:~$ nmcli connection +NAME UUID TYPE DEVICE +netplan-eth1 433e484b-3493-3640-9368-395c0c752304 ethernet eth1 +sanshiro-73B2 1f0f9db6-e448-41ef-9d27-e1ed4e48a4f5 wifi wlan1 +Wired connection 1 eb557bda-e1bf-3ab7-89e9-1f839cd6b88a ethernet -- +fetch1075-hotspot b85c6a8f-9d28-4cf3-95a0-6dc37229863d wifi -- +sanshiro-outside d7ee2165-c93a-4050-862d-d0c381a546ab wifi -- +fetch@fetch1075:~$ nmcli c show sanshiro-73B2 +``` + +To activate some connection. + +```bash +fetch@fetch1075:~$ sudo nmcli c up sanshiro-outside +[sudo] password for fetch: +Connection successfully activated (D-Bus active path: /org/freedesktop/NetworkManager/ActiveConnection/5) +fetch@fetch1075:~$ sudo nmcli c up sanshiro-73B2 +Connection successfully activated (D-Bus active path: /org/freedesktop/NetworkManager/ActiveConnection/6) +``` + +To edit connection profiles, use `nmtui` or `nm-connection-editor` + +### Default connection profiles + +fetch15 and fetch1075 has `sanshiro-73B2` and `sanshiro-outside` connections by default. (If not, please make them) + +- `sanshiro-73B2` (Connect `sanshiro` with fixed BSSID) +- `sanshiro-outside` (Connect `sanshiro` without fixed BSSID) + +By default, `sanshiro-73B2` is activated for stable connection in 73B2. +If you want to use fetch outside of 73B2, it is recommended to activate `sanshiro-outside`. + +```bash +sudo nmcli c up sanshiro-outside +``` + +## Log tmuxinator makes it easy to check the important logs of fetch from command line. Currently, it shows the logs of the supervisor jobs. Install tmuxinator config. + ```bash rosrun jsk_fetch_startup install_tmuxinator.sh ``` Show logs + ```bash tmuxinator log ``` @@ -234,6 +360,7 @@ tmuxinator log You can not run this on Firefox. Please use Google Chrome. ### Add fetch to rwt_app_chooser + 1. Access [http://tork-a.github.io/visualization_rwt/rwt_app_chooser](http://tork-a.github.io/visualization_rwt/rwt_app_chooser "website"). - Be careful to access the site via http, not https, to to enable websocket communication. - Modern browsers may automatically redirect from http to https. @@ -244,7 +371,27 @@ You can not run this on Firefox. Please use Google Chrome. 1. Click `ADD ROBOT` button ### Execute demos + 1. Click `fetch15` at `Select Robot` window 1. Select task which are shown with icons. ![select_app](https://user-images.githubusercontent.com/19769486/40872010-7d21d2bc-6681-11e8-8c0b-621f199638dd.png) + +## Administration + +- 2016/10/26 add `allow 133.11.216/8` to /etc/chrony/chrony.conf +- 2018/08/26 add `0 10 * * 1-5 /home/fetch/ros/indigo_robot/devel/env.sh rosservice call /fetch15/start_app "name: 'jsk_fetch_startup/go_to_kitchen'"` to crontab + - `fetch` goes to 73B2 kitchen at 10:00 AM from Monday to Friday. +- 2019/04/19: add `fetch` user in `pulse-access` group. +- 2019/04/19: set `start on runlevel [2345]` in `/etc/init/pulseaudio.conf`. + - this modification is needed for starting `pulseaudio` in boot. + - `pulseaudio` is required to register USB speaker on head in boot. +- 2019/04/19: set `env DISALLOW_MODULE_LOADING=0` in `/etc/init/pulseaudio.conf`. + - this modification is needed for overriding default speaker setting in `/etc/init/jsk-fetch-startup.conf` + - overriding default speaker setting to use USB speaker on head is done with `pactl set-default-sink $AUDIO_DEVICE` in `/etc/init/jsk-fetch-startup.conf` +- 2019/04/19: launch `jsk_fetch_startup/fetch_bringup.launch` by `fetch` user in `/etc/init/jsk-fetch-startup.conf` + - some nodes save files by `fetch` user +- 2019/04/19: add arg `launch_teleop` in `/etc/ros/indigo/robot.launch`. + - We sent PR to upstream [fetchrobotics/fetch_robots PR#40](https://github.com/fetchrobotics/fetch_robots/pull/40). +- 2019/04/19: run `/etc/ros/indigo/robot.launch` with `arg` `launch_teleop:=false`. + - `teleop` in `/etc/ros/indigo/robot.launch` nodes were conflicted with `teleop` nodes in [jsk_fetch_startup/launch/fetch_teleop.xml](https://github.com/jsk-ros-pkg/jsk_robot/blob/master/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/auto_dock/auto_dock.app b/jsk_fetch_robot/jsk_fetch_startup/apps/auto_dock/auto_dock.app index d628e8e57a..fd09baa3eb 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/auto_dock/auto_dock.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/auto_dock/auto_dock.app @@ -1,5 +1,5 @@ display: Fetch auto dock platform: fetch -launch: jsk_fetch_startup/auto_dock.xml +run: jsk_fetch_startup/auto-dock.l interface: jsk_fetch_startup/auto_dock.interface icon: jsk_fetch_startup/auto_dock.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/call_k_okada/call_k_okada.app b/jsk_fetch_robot/jsk_fetch_startup/apps/call_k_okada/call_k_okada.app index acfcb25162..4577ac55ae 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/call_k_okada/call_k_okada.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/call_k_okada/call_k_okada.app @@ -1,5 +1,5 @@ display: Call k-okada platform: fetch -launch: jsk_fetch_startup/call_k_okada.xml +run: jsk_fetch_startup/call-k-okada.l interface: jsk_fetch_startup/call_k_okada.interface icon: jsk_fetch_startup/call_k_okada.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/dock/dock.app b/jsk_fetch_robot/jsk_fetch_startup/apps/dock/dock.app index 916d8fb34c..6c034bd9aa 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/dock/dock.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/dock/dock.app @@ -1,5 +1,5 @@ display: Fetch dock platform: fetch -launch: jsk_fetch_startup/dock.xml +run: jsk_fetch_startup/dock.l interface: jsk_fetch_startup/dock.interface icon: jsk_fetch_startup/dock.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed b/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed index e47207b282..c1bad9ee46 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed @@ -29,3 +29,9 @@ apps: display: light on - app: jsk_fetch_startup/light_off display: light off + - app: jsk_fetch_startup/upload_notification + display: Upload notification + - app: jsk_fetch_startup/plug_spot_power_connector + display: Plug Spot Power Connector + - app: jsk_fetch_startup/unplug_spot_power_connector + display: Unplug Spot Power Connector diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index e81df30945..b5a69c054e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -3,53 +3,18 @@ platform: fetch launch: jsk_fetch_startup/go_to_kitchen.xml interface: jsk_fetch_startup/go_to_kitchen.interface icon: jsk_fetch_startup/go_to_kitchen.png +timeout: 1200 plugins: - name: service_notification_saver_plugin type: app_notification_saver/service_notification_saver - name: smach_notification_saver_plugin type: app_notification_saver/smach_notification_saver - - name: head_camera_video_recorder_plugin - type: app_recorder/audio_video_recorder_plugin - launch_args: - video_path: /tmp - video_title: go_to_kitchen_head_camera.avi - audio_topic_name: /audio - audio_channels: 1 - audio_sample_rate: 16000 - audio_format: wave - audio_sample_format: S16LE - video_topic_name: /head_camera/rgb/image_rect_color - video_height: 480 - video_width: 640 - video_framerate: 30 - video_encoding: RGB - - name: object_detection_video_recorder_plugin - type: app_recorder/video_recorder_plugin - launch_args: - video_path: /tmp - video_title: go_to_kitchen_object_detection.avi - video_topic_name: /edgetpu_object_detector_visualization/output - video_fps: 5.0 - - name: panorama_video_recorder_plugin - type: app_recorder/video_recorder_plugin - launch_args: - video_path: /tmp - video_title: go_to_kitchen_panorama.avi - video_topic_name: /dual_fisheye_to_panorama/output - video_fps: 1.0 - - name: respeaker_audio_recorder_plugin - type: app_recorder/audio_recorder_plugin - launch_args: - audio_path: /tmp - audio_title: go_to_kitchen_audio.wav - audio_topic_name: /audio - audio_format: wave - name: rosbag_recorder_plugin type: app_recorder/rosbag_recorder_plugin launch_args: rosbag_path: /tmp rosbag_title: go_to_kitchen_rosbag.bag - compress: true + compress: false rosbag_topic_names: - /rosout - /tf @@ -70,16 +35,74 @@ plugins: - /move_base/global_costmap/costmap - /particlecloud - /base_scan/throttled + - /dual_fisheye_to_panorama/quater/output/compressed + - /edgetpu_object_detector/output/image/compressed - /head_camera/rgb/throttled/camera_info - /head_camera/depth_registered/throttled/camera_info - /head_camera/rgb/throttled/image_rect_color/compressed - - /head_camera/depth_registered/throttled/image_rect/compressedDepth + - /head_camera/depth_registered/throttled/image_rect/zdepth - /photo_taken - /server_name/smach/container_init - /server_name/smach/container_status - /server_name/smach/container_structure - /audio - /rviz/throttled/image/compressed + - /smach_image_publisher/image/compressed + - name: head_camera_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /head_camera/rgb/throttled/image_rect_color/compressed + image_fps: 5 + audio_topic_name: /audio + audio_sample_rate: 16000 + audio_channels: 1 + video_path: /tmp/go_to_kitchen_head_camera.mp4 + - name: object_detection_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /edgetpu_object_detector/output/image/compressed + image_fps: 5 + audio_topic_name: /audio + audio_sample_rate: 16000 + audio_channels: 1 + video_path: /tmp/go_to_kitchen_object_detection.mp4 + - name: panorama_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /dual_fisheye_to_panorama/quater/output/compressed + image_fps: 1 + video_path: /tmp/go_to_kitchen_panorama.mp4 + - name: rviz_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /rviz/throttled/image/compressed + image_fps: 5 + video_path: /tmp/go_to_kitchen_rviz.mp4 + - name: smach_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /smach_image_publisher/image/compressed + image_fps: 2 + video_path: /tmp/go_to_kitchen_smach.mp4 + - name: respeaker_audio_converter_plugin + type: app_recorder/rosbag_audio_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + audio_topic_name: /audio + audio_sample_rate: 16000 + audio_channels: 1 + audio_path: /tmp/go_to_kitchen_audio.wav - name: result_recorder_plugin type: app_recorder/result_recorder_plugin plugin_args: @@ -90,20 +113,33 @@ plugins: plugin_args: upload_file_paths: - /tmp/go_to_kitchen_result.yaml - - /tmp/go_to_kitchen_head_camera.avi - - /tmp/go_to_kitchen_object_detection.avi - - /tmp/go_to_kitchen_panorama.avi + - /tmp/go_to_kitchen_head_camera.mp4 + - /tmp/go_to_kitchen_object_detection.mp4 + - /tmp/go_to_kitchen_panorama.mp4 + - /tmp/go_to_kitchen_rviz.mp4 + - /tmp/go_to_kitchen_smach.mp4 - /tmp/go_to_kitchen_audio.wav - /tmp/go_to_kitchen_rosbag.bag + - /tmp/trashcan_inside.jpg upload_file_titles: - go_to_kitchen_result.yaml - - go_to_kitchen_head_camera.avi - - go_to_kitchen_object_detection.avi - - go_to_kitchen_panorama.avi + - go_to_kitchen_head_camera.mp4 + - go_to_kitchen_object_detection.mp4 + - go_to_kitchen_panorama.mp4 + - go_to_kitchen_rviz.mp4 + - go_to_kitchen_smach.mp4 - go_to_kitchen_audio.wav - go_to_kitchen_rosbag.bag + - trashcan_inside.jpg upload_parents_path: fetch_go_to_kitchen upload_server_name: /gdrive_server + - name: tweet_notifier_plugin + type: app_notifier/tweet_notifier_plugin + plugin_args: + client_name: /tweet_image_server/tweet + image: true + image_topic_name: /edgetpu_object_detector/output/image + warning: false - name: speech_notifier_plugin type: app_notifier/speech_notifier_plugin plugin_args: @@ -113,6 +149,7 @@ plugins: plugin_args: mail_title: Fetch kitchen patrol demo use_timestamp_title: true + use_app_start_time: true plugin_arg_yaml: /var/lib/robot/fetch_mail_notifier_plugin.yaml - name: move_base_cancel_plugin type: app_publisher/rostopic_publisher_plugin @@ -136,13 +173,16 @@ plugin_order: - move_base_cancel_plugin - service_notification_saver_plugin - smach_notification_saver_plugin - - head_camera_video_recorder_plugin - - object_detection_video_recorder_plugin - - panorama_video_recorder_plugin - - respeaker_audio_recorder_plugin - rosbag_recorder_plugin + - head_camera_converter_plugin + - object_detection_converter_plugin + - panorama_converter_plugin + - rviz_converter_plugin + - smach_converter_plugin + - respeaker_audio_converter_plugin - result_recorder_plugin - gdrive_uploader_plugin + - tweet_notifier_plugin - speech_notifier_plugin - mail_notifier_plugin - shutdown_plugin @@ -150,13 +190,16 @@ plugin_order: - move_base_cancel_plugin - service_notification_saver_plugin - smach_notification_saver_plugin - - head_camera_video_recorder_plugin - - object_detection_video_recorder_plugin - - panorama_video_recorder_plugin - - respeaker_audio_recorder_plugin - rosbag_recorder_plugin + - head_camera_converter_plugin + - object_detection_converter_plugin + - panorama_converter_plugin + - rviz_converter_plugin + - smach_converter_plugin + - respeaker_audio_converter_plugin - result_recorder_plugin - gdrive_uploader_plugin + - tweet_notifier_plugin - speech_notifier_plugin - mail_notifier_plugin - shutdown_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 81c75095b2..095dd2a6cb 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -1,6 +1,6 @@ - + @@ -14,4 +14,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + topics: + - /sound_play/goal + - /speech_to_text + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/hello_world/hello_world.app b/jsk_fetch_robot/jsk_fetch_startup/apps/hello_world/hello_world.app index 7b9b90ea81..a2dc73bd13 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/hello_world/hello_world.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/hello_world/hello_world.app @@ -1,5 +1,5 @@ display: Fetch hello world platform: fetch -launch: jsk_fetch_startup/hello_world.xml +run: jsk_robot_startup/boot_sound.py interface: jsk_fetch_startup/hello_world.interface icon: jsk_fetch_startup/hello_world.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/light_off/light_off.app b/jsk_fetch_robot/jsk_fetch_startup/apps/light_off/light_off.app index daf7f86708..f8aeb69c3c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/light_off/light_off.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/light_off/light_off.app @@ -1,6 +1,6 @@ display: Fetch light off platform: fetch -launch: jsk_fetch_startup/light_off.xml +run: jsk_fetch_startup/light-off.l interface: jsk_fetch_startup/light_off.interface icon: jsk_fetch_startup/light_off.png plugins: diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/light_on/light_on.app b/jsk_fetch_robot/jsk_fetch_startup/apps/light_on/light_on.app index ef63123502..eb66297f74 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/light_on/light_on.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/light_on/light_on.app @@ -1,6 +1,6 @@ display: Fetch light on platform: fetch -launch: jsk_fetch_startup/light_on.xml +run: jsk_fetch_startup/light-on.l interface: jsk_fetch_startup/light_on.interface icon: jsk_fetch_startup/light_on.png plugins: diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app new file mode 100644 index 0000000000..10982ad16c --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app @@ -0,0 +1,75 @@ +display: Plug Spot Power Connector +platform: fetch +launch: jsk_fetch_startup/plug_spot_power_connector.xml +interface: jsk_fetch_startup/plug_spot_power_connector.interface +icon: jsk_fetch_startup/plug_spot_power_connector.png +plugins: + - name: service_notification_saver_plugin + type: app_notification_saver/service_notification_saver + - name: head_camera_video_recorder_plugin + type: app_recorder/audio_video_recorder_plugin + launch_args: + video_path: /tmp + video_title: plug_spot_power_connector_head_camera.avi + audio_topic_name: /audio + audio_channels: 1 + audio_sample_rate: 16000 + audio_format: wave + audio_sample_format: S16LE + video_topic_name: /l515_head/color/image_raw + video_height: 1080 + video_width: 1920 + video_framerate: 30 + video_encoding: RGB + - name: panorama_video_recorder_plugin + type: app_recorder/video_recorder_plugin + launch_args: + video_path: /tmp + video_title: plug_spot_power_connector_panorama.avi + video_topic_name: /dual_fisheye_to_panorama/output + video_fps: 1.0 + - name: result_recorder_plugin + type: app_recorder/result_recorder_plugin + plugin_args: + result_path: /tmp + result_title: plug_spot_power_connector_result.yaml + - name: gdrive_uploader_plugin + type: app_uploader/gdrive_uploader_plugin + plugin_args: + upload_file_paths: + - /tmp/plug_spot_power_connector_result.yaml + - /tmp/plug_spot_power_connector_head_camera.avi + - /tmp/plug_spot_power_connector_panorama.avi + upload_file_titles: + - plug_spot_power_connector_result.yaml + - plug_spot_power_connector_head_camera.avi + - plug_spot_power_connector_panorama.avi + upload_parents_path: fetch_plug_spot_power_connector + upload_server_name: /gdrive_server + - name: speech_notifier_plugin + type: app_notifier/speech_notifier_plugin + plugin_args: + client_name: /sound_play + - name: mail_notifier_plugin + type: app_notifier/mail_notifier_plugin + plugin_args: + mail_title: Fetch Plug Spot Power Connector Demo + use_timestamp_title: true + plugin_arg_yaml: /var/lib/robot/fetch_mail_notifier_plugin.yaml +plugin_order: + start_plugin_order: + - service_notification_saver_plugin + - head_camera_video_recorder_plugin + - panorama_video_recorder_plugin + - result_recorder_plugin + - gdrive_uploader_plugin + - speech_notifier_plugin + - mail_notifier_plugin + stop_plugin_order: + - service_notification_saver_plugin + - head_camera_video_recorder_plugin + - panorama_video_recorder_plugin + - result_recorder_plugin + - gdrive_uploader_plugin + - speech_notifier_plugin + - mail_notifier_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.interface b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.interface new file mode 100644 index 0000000000..044105d644 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.png b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.png new file mode 100644 index 0000000000..d1b1329d2f Binary files /dev/null and b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.png differ diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.xml new file mode 100644 index 0000000000..ad05e91977 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.xml @@ -0,0 +1,3 @@ + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/software_runstop/software_runstop.app b/jsk_fetch_robot/jsk_fetch_startup/apps/software_runstop/software_runstop.app index 6c86c77347..ed4a25c745 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/software_runstop/software_runstop.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/software_runstop/software_runstop.app @@ -1,5 +1,6 @@ display: Fetch software runstop platform: fetch -launch: jsk_fetch_startup/software_runstop.xml +run: rostopic/rostopic +run_args: "pub -1 /enable_software_runstop std_msgs/Bool 'data: true'" interface: jsk_fetch_startup/software_runstop.interface icon: jsk_fetch_startup/software_runstop.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app b/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app index 0a48645098..2dc162d470 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app @@ -1,6 +1,6 @@ display: Speak battery platform: fetch -launch: jsk_fetch_startup/speak_battery.xml +run: jsk_fetch_startup/speak-battery.l interface: jsk_fetch_startup/speak_battery.interface icon: jsk_fetch_startup/speak_battery.png plugins: @@ -8,6 +8,7 @@ plugins: type: app_notifier/user_speech_notifier_plugin plugin_args: client_name: /sound_play + warning: true plugin_order: start_plugin_order: - user_speech_notifier_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app index d1c5e17227..e82fe5629f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app @@ -1,10 +1,19 @@ display: Speak time signal platform: fetch -launch: jsk_fetch_startup/time_signal.xml +run: jsk_fetch_startup/time_signal.py +run_name: "time_signal" +# run_name needs https://github.com/PR2/app_manager/pull/64 interface: jsk_fetch_startup/time_signal.interface icon: jsk_fetch_startup/time_signal.png -timeout: 10 +timeout: 120 plugins: + - name: tweet_notifier_plugin + type: app_notifier/tweet_notifier_plugin + plugin_args: + client_name: /tweet_image_server/tweet + image: true + image_topic_name: /edgetpu_object_detector/output/image + warning: false - name: user_speech_notifier_plugin type: app_notifier/user_speech_notifier_plugin plugin_args: @@ -12,6 +21,8 @@ plugins: warning: false plugin_order: start_plugin_order: + - tweet_notifier_plugin - user_speech_notifier_plugin stop_plugin_order: + - tweet_notifier_plugin - user_speech_notifier_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app b/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app index da0197d1b9..28d7cc4bf1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app @@ -1,6 +1,6 @@ display: Fetch tweet platform: fetch -launch: jsk_fetch_startup/tweet.xml +run: jsk_fetch_startup/tweet.l interface: jsk_fetch_startup/tweet.interface icon: jsk_fetch_startup/tweet.png plugins: @@ -8,6 +8,7 @@ plugins: type: app_notifier/user_speech_notifier_plugin plugin_args: client_name: /sound_play + warning: true plugin_order: start_plugin_order: - user_speech_notifier_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/undock/undock.app b/jsk_fetch_robot/jsk_fetch_startup/apps/undock/undock.app index da845f0a25..78a4b30891 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/undock/undock.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/undock/undock.app @@ -1,5 +1,5 @@ display: Fetch undock platform: fetch -launch: jsk_fetch_startup/undock.xml +run: jsk_fetch_startup/undock.l interface: jsk_fetch_startup/undock.interface icon: jsk_fetch_startup/undock.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app new file mode 100644 index 0000000000..680166f454 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app @@ -0,0 +1,75 @@ +display: Unplug Spot Power Connector +platform: fetch +launch: jsk_fetch_startup/unplug_spot_power_connector.xml +interface: jsk_fetch_startup/unplug_spot_power_connector.interface +icon: jsk_fetch_startup/unplug_spot_power_connector.png +plugins: + - name: service_notification_saver_plugin + type: app_notification_saver/service_notification_saver + - name: head_camera_video_recorder_plugin + type: app_recorder/audio_video_recorder_plugin + launch_args: + video_path: /tmp + video_title: unplug_spot_power_connector_head_camera.avi + audio_topic_name: /audio + audio_channels: 1 + audio_sample_rate: 16000 + audio_format: wave + audio_sample_format: S16LE + video_topic_name: /l515_head/color/image_raw + video_height: 1080 + video_width: 1920 + video_framerate: 30 + video_encoding: RGB + - name: panorama_video_recorder_plugin + type: app_recorder/video_recorder_plugin + launch_args: + video_path: /tmp + video_title: unplug_spot_power_connector_panorama.avi + video_topic_name: /dual_fisheye_to_panorama/output + video_fps: 1.0 + - name: result_recorder_plugin + type: app_recorder/result_recorder_plugin + plugin_args: + result_path: /tmp + result_title: unplug_spot_power_connector_result.yaml + - name: gdrive_uploader_plugin + type: app_uploader/gdrive_uploader_plugin + plugin_args: + upload_file_paths: + - /tmp/unplug_spot_power_connector_result.yaml + - /tmp/unplug_spot_power_connector_head_camera.avi + - /tmp/unplug_spot_power_connector_panorama.avi + upload_file_titles: + - unplug_spot_power_connector_result.yaml + - unplug_spot_power_connector_head_camera.avi + - unplug_spot_power_connector_panorama.avi + upload_parents_path: fetch_unplug_spot_power_connector + upload_server_name: /gdrive_server + - name: speech_notifier_plugin + type: app_notifier/speech_notifier_plugin + plugin_args: + client_name: /sound_play + - name: mail_notifier_plugin + type: app_notifier/mail_notifier_plugin + plugin_args: + mail_title: Fetch Unplug Spot Power Connector Demo + use_timestamp_title: true + plugin_arg_yaml: /var/lib/robot/fetch_mail_notifier_plugin.yaml +plugin_order: + start_plugin_order: + - service_notification_saver_plugin + - head_camera_video_recorder_plugin + - panorama_video_recorder_plugin + - result_recorder_plugin + - gdrive_uploader_plugin + - speech_notifier_plugin + - mail_notifier_plugin + stop_plugin_order: + - service_notification_saver_plugin + - head_camera_video_recorder_plugin + - panorama_video_recorder_plugin + - result_recorder_plugin + - gdrive_uploader_plugin + - speech_notifier_plugin + - mail_notifier_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.interface b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.interface new file mode 100644 index 0000000000..044105d644 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.png b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.png new file mode 100644 index 0000000000..3098183bc3 Binary files /dev/null and b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.png differ diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.xml new file mode 100644 index 0000000000..d61fc63f62 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.xml @@ -0,0 +1,3 @@ + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/cfg/TimeSignal.cfg b/jsk_fetch_robot/jsk_fetch_startup/cfg/TimeSignal.cfg new file mode 100644 index 0000000000..e22d48bc1e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/cfg/TimeSignal.cfg @@ -0,0 +1,11 @@ +#! /usr/bin/env python + + +from dynamic_reconfigure.parameter_generator_catkin import * + +PACKAGE = 'jsk_fetch_startup' + +gen = ParameterGenerator() +gen.add("volume", double_t, 0, "Volume of sound.", 1.0, 0.0, 1.0) + +exit(gen.generate(PACKAGE, PACKAGE, "TimeSignal")) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore b/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore new file mode 100644 index 0000000000..dd8bb6cb6a --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore @@ -0,0 +1,2 @@ +fetch*_dialogflow_hotword.yaml +fetch*_email_topic.yaml diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index ea364d3b12..1ce371abbf 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -1,7 +1,52 @@ # This file is bash configuration for robot.conf # This file must be at /var/lib/robot/config.bash -export RS_SERIAL_NO_T265="" -export RS_SERIAL_NO_D435_FRONTRIGHT="" -export RS_SERIAL_NO_D435_FRONTLEFT="" -export RS_SERIAL_NO_L515_HEAD="" +if [ $(hostname) = 'fetch15' ]; then + export DEFAULT_SPEAKER=13; + export DEFAULT_ENGLISH_SPEAKER=cmu_us_bdl.flitevox; + export DEFAULT_WARNING_SPEAKER=cmu_us_fem.flitevox; + + export USE_BASE_CAMERA_MOUNT=true; + export USE_HEAD_BOX=false; + export USE_HEAD_L515=true; + export USE_INSTA360_STAND=true; + + export RS_SERIAL_NO_T265="925122110450"; + export RS_SERIAL_NO_D435_FRONTRIGHT=""; + export RS_SERIAL_NO_D435_FRONTLEFT=""; + # Disable L515 to reduce fetch's CPU usage + # Use L515 after finding a way to reduce L515 CPU usage like ConnectionBasedTransport + # export RS_SERIAL_NO_L515_HEAD="f0211890"; + export RS_SERIAL_NO_L515_HEAD=""; + + export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; + export NETWORK_DEFAULT_ROS_INTERFACE="fetch15"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; + + export AUDIO_DEVICE="alsa_output.usb-1130_USB_AUDIO-00.analog-stereo" +elif [ $(hostname) = 'fetch1075' ]; then + export DEFAULT_SPEAKER=2; + export DEFAULT_ENGLISH_SPEAKER=cmu_us_slt.flitevox; + export DEFAULT_WARNING_SPEAKER=cmu_us_lnh.flitevox; + + export USE_BASE_CAMERA_MOUNT=false; + export USE_HEAD_BOX=false; + export USE_HEAD_L515=true; + export USE_INSTA360_STAND=true; + + export RS_SERIAL_NO_T265=""; + export RS_SERIAL_NO_D435_FRONTRIGHT=""; + export RS_SERIAL_NO_D435_FRONTLEFT=""; + # Disable L515 to reduce fetch's CPU usage + # Use L515 after finding a way to reduce L515 CPU usage like ConnectionBasedTransport + export RS_SERIAL_NO_L515_HEAD="f0232270"; + #export RS_SERIAL_NO_L515_HEAD=""; + + export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; + export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; + + export AUDIO_DEVICE="alsa_output.usb-SEEED_ReSpeaker_4_Mic_Array__UAC1.0_-00.analog-stereo" + + export SMART_DEVICE_PORT=/dev/ttyACM0 +fi diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash new file mode 100644 index 0000000000..007560b460 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash @@ -0,0 +1,12 @@ +# This file is bash configuration for robot.conf +# This file must be at /var/lib/robot/config.bash + +SCRIPT_DIR="$( cd -- "$( dirname -- "${BASH_SOURCE[0]:-$0}"; )" &> /dev/null && pwd 2> /dev/null; )"; +. $SCRIPT_DIR/config.bash + +if [ $(hostname) = 'fetch15' ]; then + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; +elif [ $(hostname) = 'fetch1075' ]; then + export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075.local"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; +fi diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml.in b/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml.in new file mode 100644 index 0000000000..73714a65a9 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml.in @@ -0,0 +1,5 @@ +- ねえねえ +- こんにちわ +- やあ +- @ROBOT_NICKNAME_KANA@ +- @ROBOT_NICKNAME_HIRA@ diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/email_topic.yaml.in b/jsk_fetch_robot/jsk_fetch_startup/config/email_topic.yaml.in new file mode 100644 index 0000000000..a087a38abb --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/email_topic.yaml.in @@ -0,0 +1,2 @@ +sender_address: @EMAIL_SENDER_ADDRESS@ +receiver_address: @EMAIL_RECEIVER_ADDRESS@ diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/fetch1075_app_schedule.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/fetch1075_app_schedule.yaml new file mode 100644 index 0000000000..b15d843c4b --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/fetch1075_app_schedule.yaml @@ -0,0 +1,52 @@ +# 'go to kitchen' launch time is temporary changed to 9:30 AM by yamaguchi, 2022/05/20. +# Recently fetch1075 freezes at 9:00 AM. +# I think the reason may be the simultaneous launch of 'go to kitchen' and 'time signal' +- name: go_to_kitchen_morning + app_name: jsk_fetch_startup/go_to_kitchen + app_schedule: + start: every(1).day.at("09:30") +- name: go_to_kitchen_noon + app_name: jsk_fetch_startup/go_to_kitchen + app_schedule: + start: every(1).day.at("13:30") +- name: go_to_kitchen_evening + app_name: jsk_fetch_startup/go_to_kitchen + app_schedule: + start: every(1).day.at("17:30") +- name: go_to_kitchen_night + app_name: jsk_fetch_startup/go_to_kitchen + app_schedule: + start: every(1).day.at("21:30") +# time singnal +- name: time_signal + app_name: jsk_fetch_startup/time_signal + app_schedule: + start: every(1).hour.at(":00") +# upload notification +- name: upload_notification + app_name: jsk_fetch_startup/upload_notification + app_schedule: + start: every(1).day.at("03:50") +# check use_sim_time +- name: check_use_sim_time + app_name: jsk_robot_startup/check_use_sim_time + app_schedule: + start: every().hour.at(":00") +# volume for monday meeting +- name: volume_zero_monday + app_name: jsk_robot_startup/volume_zero + app_schedule: + start: every().monday.at("12:00") +- name: volume_reset_monday + app_name: jsk_robot_startup/volume_reset + app_schedule: + start: every().monday.at("16:00") +# volume for tuesday meeting +- name: volume_zero_tuesday + app_name: jsk_robot_startup/volume_zero + app_schedule: + start: every().tuesday.at("12:00") +- name: volume_reset_tuesday + app_name: jsk_robot_startup/volume_reset + app_schedule: + start: every().tuesday.at("16:00") diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/fetch15_app_schedule.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/fetch15_app_schedule.yaml new file mode 100644 index 0000000000..6fd9e0c702 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/fetch15_app_schedule.yaml @@ -0,0 +1,33 @@ +# time signal +- name: time_signal + app_name: jsk_fetch_startup/time_signal + app_schedule: + start: every(1).hour.at(":00") +# upload notification +- name: upload_notification + app_name: jsk_fetch_startup/upload_notification + app_schedule: + start: every(1).day.at("03:50") +# check use_sim_time +- name: check_use_sim_time + app_name: jsk_robot_startup/check_use_sim_time + app_schedule: + start: every().hour.at(":00") +# volume for monday meeting +- name: volume_zero_monday + app_name: jsk_robot_startup/volume_zero + app_schedule: + start: every().monday.at("12:00") +- name: volume_reset_monday + app_name: jsk_robot_startup/volume_reset + app_schedule: + start: every().monday.at("16:00") +# volume for tuesday meeting +- name: volume_zero_tuesday + app_name: jsk_robot_startup/volume_zero + app_schedule: + start: every().tuesday.at("12:00") +- name: volume_reset_tuesday + app_name: jsk_robot_startup/volume_reset + app_schedule: + start: every().tuesday.at("16:00") diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/fetch_analyzers.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/fetch_analyzers.yaml index f4847a4cba..d6b18c8111 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/fetch_analyzers.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/config/fetch_analyzers.yaml @@ -102,7 +102,7 @@ analyzers: path: Head Camera timeout: 5.0 startswith: 'head_camera' - num_items: 2 + num_items: 4 imu: type: diagnostic_aggregator/GenericAnalyzer path: IMU @@ -154,18 +154,6 @@ analyzers: contains: '/audio' timeout: 100 discard_stale: true - head_depth_image: - type: diagnostic_aggregator/GenericAnalyzer - path: HeadDepthImage - contains: '/head_camera/depth/image_raw' - timeout: 100 - discard_stale: true - head_rgb_image: - type: diagnostic_aggregator/GenericAnalyzer - path: HeadRGBImage - contains: '/head_camera/rgb/image_raw' - timeout: 100 - discard_stale: true nodes: type: diagnostic_aggregator/AnalyzerGroup path: Nodes diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_cron.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_cron.sh new file mode 100755 index 0000000000..186b8dc4cc --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_cron.sh @@ -0,0 +1,15 @@ +#!/bin/bash + +jsk_fetch_startup=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`"/.. > /dev/null && pwd) + +IFS=':' read -r -a prefix_paths <<< "$CMAKE_PREFIX_PATH" +current_prefix_path="${prefix_paths[0]}" + +set -x + +cd $jsk_fetch_startup/cron_scripts +sudo -u fetch crontab cron_fetch.conf +echo "Set cron jobs for fetch user" +sudo -u root crontab cron_root.conf +echo "Set cron jobs for root user" +set +x diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index d07fbfb529..6a35d559c0 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -8,16 +8,14 @@ current_prefix_path="${prefix_paths[0]}" set -x cd $jsk_fetch_startup/supervisor_scripts -for file in $(ls ./*.conf); do - sudo cp $file /etc/supervisor/conf.d/ - sudo chown root:root /etc/supervisor/conf.d/$file - sudo chmod 644 /etc/supervisor/conf.d/$file - echo "copied $file to /etc/supervisor/conf.d" +for file in $(ls *.conf); do + sudo ln -sf $jsk_fetch_startup/supervisor_scripts/$file /etc/supervisor/conf.d/$file done +sudo supervisorctl reread +# Enable jsk_dstat job to save the csv log under /var/log +sudo ln -sf /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv -# copy config.bash to /var/lib/robo if not exists -if [ ! -e /var/lib/robot/config.bash ]; then - sudo cp $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash -fi +sudo ln -sf $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash +sudo ln -sf $jsk_fetch_startup/config/config_outside.bash /var/lib/robot/config_outside.bash set +x diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh index b079e114a4..5e8e1cec43 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh @@ -1,17 +1,12 @@ #!/bin/bash +# 99-edgetpu-accelerator.rules and 99-realsense-libusb.rules are not tracked in jsk_fetch_startup +# because they are installed by apt + jsk_fetch_startup=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`"/.. > /dev/null && pwd) cd $jsk_fetch_startup/udev_rules for file in $(ls *.rules); do - if [ -e /etc/udev/rules.d/$file ]; then - file_bk=$file.$(date "+%Y%m%d_%H%M%S") - sudo cp /etc/udev/rules.d/$file /etc/udev/rules.d/$file_bk - echo "backup /etc/udev/rules.d/$file to /etc/udev/rules.d/$file_bk" - fi - - sudo cp $file /etc/udev/rules.d/ - sudo chown root:root /etc/udev/rules.d/$file - sudo chmod 644 /etc/udev/rules.d/$file - echo -e "copied jsk_fetch_startup/udev_rules/$file to /etc/udev/rules.d/$file\n" + sudo ln -sf $jsk_fetch_startup/udev_rules/$file /etc/udev/rules.d/$file + echo -e "Create symbolic link from jsk_fetch_startup/udev_rules/$file to /etc/udev/rules.d/$file\n" done diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz index 6cb1fffa48..c8dd4f9418 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz +++ b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz @@ -5,7 +5,7 @@ Panels: Property Tree Widget: Expanded: ~ Splitter Ratio: 0.4187380373477936 - Tree Height: 1319 + Tree Height: 477 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -65,11 +65,6 @@ Visualization Manager: Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order - base_camera_mount: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true base_link: Alpha: 1 Show Axes: false @@ -143,6 +138,10 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + head_l515_virtual_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false head_pan_link: Alpha: 1 Show Axes: false @@ -153,6 +152,10 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + insta360_link: + Alpha: 1 + Show Axes: false + Show Trail: false l515_head_link: Alpha: 1 Show Axes: false @@ -344,12 +347,12 @@ Visualization Manager: Class: rviz/Map Color Scheme: costmap Draw Behind: false - Enabled: false + Enabled: true Name: SafeCostMap Topic: /safe_teleop_base/local_costmap/costmap Unreliable: false Use Timestamp: false - Value: false + Value: true - Alpha: 0.3499999940395355 Class: rviz/Map Color Scheme: costmap @@ -401,9 +404,7 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 Min Color: 0; 0; 0 - Min Intensity: 0 Name: BaseScan Position Transformer: XYZ Queue Size: 10 @@ -431,9 +432,7 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 Min Color: 0; 0; 0 - Min Intensity: 0 Name: XtionPointCloud Position Transformer: XYZ Queue Size: 10 @@ -446,19 +445,6 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: true - - Class: jsk_rviz_plugin/OverlayImage - Enabled: true - Name: XtionRGB - Topic: /head_camera/rgb/quater/image_rect_color - Value: true - alpha: 0.800000011920929 - height: 128 - keep aspect ratio: true - left: 10 - overwrite alpha value: false - top: 10 - transport hint: raw - width: 320 - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: @@ -471,12 +457,10 @@ Visualization Manager: Color: 255; 255; 255 Color Transformer: RGB8 Decay Time: 0 - Enabled: true + Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 Min Color: 0; 0; 0 - Min Intensity: 0 Name: HeadL515PointCloud Position Transformer: XYZ Queue Size: 10 @@ -488,7 +472,93 @@ Visualization Manager: Unreliable: false Use Fixed Frame: true Use rainbow: true - Value: true + Value: false + - Class: rviz/Group + Displays: + - Class: jsk_rviz_plugin/OverlayImage + Enabled: true + Name: XtionRGB + Topic: /head_camera/rgb/quater/image_rect_color + Value: true + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 10 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 320 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: false + Name: XtionRGBHumanPoseEstimator + Topic: /edgetpu_human_pose_estimator/output/image + Value: false + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 10 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 320 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: false + Name: XtionRGBObjectDetector + Topic: /edgetpu_human_pose_estimator/output/image + Value: false + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 10 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 320 + Enabled: true + Name: XtionRGB + - Class: rviz/Group + Displays: + - Class: jsk_rviz_plugin/OverlayImage + Enabled: true + Name: PanoramaImage + Topic: /dual_fisheye_to_panorama/quater/output + Value: true + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 340 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 480 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: false + Name: PanoramaHumanPoseEstimator + Topic: /edgetpu_panorama_human_pose_estimator/output/image + Value: false + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 340 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 480 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: false + Name: PanoramaObjectDetector + Topic: /edgetpu_panorama_object_detector/output/image + Value: false + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 340 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 480 + Enabled: true + Name: PanoramaImage Enabled: true Global Options: Background Color: 48; 48; 48 @@ -519,35 +589,35 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 10.471776962280273 + Distance: 10 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: -0.00829183217138052 - Y: 0.022624600678682327 - Z: -0.003759089857339859 - Focal Shape Fixed Size: true + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: false Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.5747973322868347 + Pitch: 0.7853981852531433 Target Frame: base_link Value: Orbit (rviz) - Yaw: 1.745403528213501 + Yaw: 0.7853981852531433 Saved: ~ Window Geometry: CancelAction: - collapsed: true + collapsed: false Displays: - collapsed: true - Height: 1865 - Hide Left Dock: true + collapsed: false + Height: 1025 + Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd0000000400000000000001f8000006abfc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d000005b2000000c900fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e00000005f5000000f30000007f00ffffff000000010000010f00000463fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000463000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003f50000003efc0100000002fb0000000800540069006d00650100000000000003f5000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000003f5000006ab00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000001f800000361fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e00000269000000ca00fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e01000002ad000000f20000008200ffffff000000010000010f00000463fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000463000000a600fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d00650100000000000007800000026200fffffffb0000000800540069006d00650100000000000004500000000000000000000005820000036100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -556,6 +626,6 @@ Window Geometry: collapsed: false Views: collapsed: true - Width: 1013 - X: 67 + Width: 1920 + X: 0 Y: 27 diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup_record.rviz b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup_record.rviz index 8b162425f0..6ab7883d78 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup_record.rviz +++ b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup_record.rviz @@ -3,9 +3,10 @@ Panels: Help Height: 78 Name: Displays Property Tree Widget: - Expanded: ~ + Expanded: + - /OverlayImage1 Splitter Ratio: 0.4187380373477936 - Tree Height: 624 + Tree Height: 618 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -65,11 +66,6 @@ Visualization Manager: Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order - base_camera_mount: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true base_link: Alpha: 1 Show Axes: false @@ -85,14 +81,6 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true - d435_front_left_link: - Alpha: 1 - Show Axes: false - Show Trail: false - d435_front_right_link: - Alpha: 1 - Show Axes: false - Show Trail: false elbow_flex_link: Alpha: 1 Show Axes: false @@ -113,11 +101,6 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true - head_box_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true head_camera_depth_frame: Alpha: 1 Show Axes: false @@ -138,6 +121,15 @@ Visualization Manager: Alpha: 1 Show Axes: false Show Trail: false + head_l515_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_l515_virtual_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false head_pan_link: Alpha: 1 Show Axes: false @@ -148,6 +140,14 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + insta360_link: + Alpha: 1 + Show Axes: false + Show Trail: false + l515_head_link: + Alpha: 1 + Show Axes: false + Show Trail: false l_gripper_finger_link: Alpha: 1 Show Axes: false @@ -455,6 +455,19 @@ Visualization Manager: Name: RvizScenePublisher Value: true topic_name: /rviz/image + - Class: jsk_rviz_plugin/OverlayImage + Enabled: true + Name: OverlayImage + Topic: /smach_image_publisher/image + Value: true + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 650 + overwrite alpha value: false + top: 10 + transport hint: compressed + width: 300 Enabled: true Global Options: Background Color: 48; 48; 48 @@ -513,7 +526,7 @@ Window Geometry: Height: 1052 Hide Left Dock: true Hide Right Dock: true - QMainWindow State: 000000ff00000000fd0000000400000000000001f800000382fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003b000002f9000000c700fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e000000033a000000830000007900ffffff000000010000010f00000382fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b00000382000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003f50000003efc0100000002fb0000000800540069006d00650100000000000003f50000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000003f50000038200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000001f80000037efc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d000002f5000000c900fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e0000000338000000830000007f00ffffff000000010000010f00000382fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b00000382000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003f50000003efc0100000002fb0000000800540069006d00650100000000000003f5000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000003f50000037e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -524,4 +537,4 @@ Window Geometry: collapsed: true Width: 1013 X: 67 - Y: 180 + Y: 134 diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/sanity_targets.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/sanity_targets.yaml index 6b8ce4ff93..24a3521055 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/sanity_targets.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/config/sanity_targets.yaml @@ -2,8 +2,6 @@ topics: - /audio - /edgetpu_human_pose_estimator/output/image/compressed - /edgetpu_object_detector/output/image/compressed - - /head_camera/depth/image_raw - - /head_camera/rgb/image_raw nodes: - /head_camera/head_camera_nodelet_manager diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/view_model.rviz b/jsk_fetch_robot/jsk_fetch_startup/config/view_model.rviz new file mode 100644 index 0000000000..e8978465a4 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/view_model.rviz @@ -0,0 +1,426 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 728 + - 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 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.5 + 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 + base_camera_mount: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bellows_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bellows_link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + d435_front_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + d435_front_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + estop_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + gripper_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_box_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_camera_depth_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_camera_depth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + head_camera_rgb_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_camera_rgb_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_l515_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_l515_virtual_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + insta360_link: + Alpha: 1 + Show Axes: false + Show Trail: false + l515_head_link: + Alpha: 1 + Show Axes: false + Show Trail: false + l_gripper_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_fixed_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + upperarm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_roll_link: + 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: true + base_camera_mount: + Value: true + base_link: + Value: true + bellows_link: + Value: true + bellows_link2: + Value: true + d435_front_left_link: + Value: true + d435_front_right_link: + Value: true + elbow_flex_link: + Value: true + estop_link: + Value: true + forearm_roll_link: + Value: true + gripper_link: + Value: true + head_box_link: + Value: true + head_camera_depth_frame: + Value: true + head_camera_depth_optical_frame: + Value: true + head_camera_link: + Value: true + head_camera_rgb_frame: + Value: true + head_camera_rgb_optical_frame: + Value: true + head_l515_mount_link: + Value: true + head_l515_virtual_mount_link: + Value: true + head_pan_link: + Value: true + head_tilt_link: + Value: true + insta360_link: + Value: true + l515_head_link: + Value: true + l_gripper_finger_link: + Value: true + l_wheel_link: + Value: true + laser_link: + Value: true + r_gripper_finger_link: + Value: true + r_wheel_link: + Value: true + shoulder_lift_link: + Value: true + shoulder_pan_link: + Value: true + torso_fixed_link: + Value: true + torso_lift_link: + Value: true + upperarm_roll_link: + Value: true + wrist_flex_link: + Value: true + wrist_roll_link: + Value: true + Marker Scale: 0.5 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + base_link: + base_camera_mount: + {} + d435_front_left_link: + {} + d435_front_right_link: + {} + estop_link: + {} + l_wheel_link: + {} + laser_link: + {} + r_wheel_link: + {} + torso_fixed_link: + {} + torso_lift_link: + bellows_link: + {} + bellows_link2: + {} + head_pan_link: + head_box_link: + {} + head_tilt_link: + head_camera_link: + head_camera_depth_frame: + head_camera_depth_optical_frame: + {} + head_camera_rgb_frame: + head_camera_rgb_optical_frame: + {} + head_l515_virtual_mount_link: + head_l515_mount_link: + l515_head_link: + {} + insta360_link: + {} + shoulder_pan_link: + shoulder_lift_link: + upperarm_roll_link: + elbow_flex_link: + forearm_roll_link: + wrist_flex_link: + wrist_roll_link: + gripper_link: + l_gripper_finger_link: + {} + r_gripper_finger_link: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: base_link + 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: 4.618305206298828 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.564796507358551 + Target Frame: + Value: Orbit (rviz) + Yaw: 1.5854246616363525 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1025 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000363fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000363000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000050f0000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1920 + X: 0 + Y: 27 diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml new file mode 100644 index 0000000000..54dc6a28f6 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml @@ -0,0 +1,15 @@ +blacklist: + - name: "/CPU/CPU Usage/my_machine CPU Usage" + - name: "/Other/amcl: Standard deviation" + - name: "/Other/jsk_joy_node: Joystick Driver Status" + - name: "/Other/l515_head .*realsense2_camera_.*: Frequency Status" + - name: "/Other/rosserial_python" + - name: "/Peripherals/PS3 Controller" + - name: "/Sensors/IMU/IMU.*" + - name: "/SoundPlay/sound_play.*" +run_stop_blacklist: + - name: "/Motor Control Boards/.*_(mcb|breaker)" + - name: "/System/Mainboard/Mainboard" + message: "Runstop pressed" + - name: "/Breakers/.*" + message: "Disabled." diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf new file mode 100644 index 0000000000..8c7cc3ea3b --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf @@ -0,0 +1 @@ +0 0 1 Jan,Apr,Jul,Oct * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && systemctl stop haproxy && certbot renew -v --standalone --renew-hook \"$(rospack find jsk_fetch_startup)/scripts/certbot_renewhook.sh\" >> /var/log/certbot_renewal.log" diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf new file mode 100644 index 0000000000..03fadaf878 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf @@ -0,0 +1,2 @@ +0 3 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup update_workspace.sh &> /home/fetch/ros/melodic/update_workspace.log" +0 5 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup storage_warning.sh &> /home/fetch/ros/melodic/storage_warning.log" diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_root.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_root.conf new file mode 100644 index 0000000000..da33972f7e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_root.conf @@ -0,0 +1 @@ +0 4 * * * /sbin/shutdown -r now diff --git a/jsk_fetch_robot/jsk_fetch_startup/data/burnable.png b/jsk_fetch_robot/jsk_fetch_startup/data/burnable.png new file mode 100644 index 0000000000..6b00521962 Binary files /dev/null and b/jsk_fetch_robot/jsk_fetch_startup/data/burnable.png differ diff --git a/jsk_fetch_robot/jsk_fetch_startup/data/icmark.png b/jsk_fetch_robot/jsk_fetch_startup/data/icmark.png new file mode 100644 index 0000000000..125b739436 Binary files /dev/null and b/jsk_fetch_robot/jsk_fetch_startup/data/icmark.png differ diff --git a/jsk_fetch_robot/jsk_fetch_startup/data/plastic.png b/jsk_fetch_robot/jsk_fetch_startup/data/plastic.png new file mode 100644 index 0000000000..e1df1b97aa Binary files /dev/null and b/jsk_fetch_robot/jsk_fetch_startup/data/plastic.png differ diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index d610d09c00..1f53a3d8bb 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -1,8 +1,481 @@ #!/usr/bin/env roseus (require :fetch-interface "package://fetcheus/fetch-interface.l") +(require :state-machine "package://roseus_smach/src/state-machine.l") +(require :state-machine-ros "package://roseus_smach/src/state-machine-ros.l") +(require :state-machine-utils "package://roseus_smach/src/state-machine-utils.l") +(require :base64 "lib/llib/base64.l") + (load "package://jsk_fetch_startup/euslisp/navigation-utils.l") +(ros::advertise "/tweet" std_msgs::String 1) +(ros::advertise "/photo_taken" sensor_msgs::Image 1) +(setq *image* nil) + +(defun image-cb (msg) + (setq *image* msg)) + +(defun go-to-kitchen (&key (tweet t) (n-dock-trial 1) (n-kitchen-trial 1) + (control-switchbot :api)) + ;; go to kitchen + (unless (boundp '*ri*) + (require :fetch-interface "package://fetcheus/fetch-interface.l") + (fetch-init)) + (report-start-go-to-kitchen) + ;; Check if the lights are on in the room + (let ((initial-light-on (get-light-on)) + (success-go-to-kitchen nil) + (success-go-to-trashcan nil) + (success-auto-dock nil) + (success-battery-charging nil)) + (store-params) + ;; turn on light + (if initial-light-on + (report-light-on) + (progn + (report-light-off) + (room-light-on :control-switchbot control-switchbot))) + ;; change the inflation_radius + (inflation-loose) + ;; go to kitchen sink + (setq success-go-to-kitchen (move-to-sink-front :n-trial n-kitchen-trial)) + ;; report result to go to kitchen + (if success-go-to-kitchen + (inspect-kitchen :tweet tweet) + (report-move-to-sink-front-failure)) + ;; go to kitchen trash can + (setq success-go-to-trashcan (move-to-trashcan-front :n-trial n-trashcan-trial)) + ;; report result to go to trash can + (if success-go-to-trashcan + (inspect-trashcan :tweet tweet) + (report-move-to-trashcan-front-failure)) + ;; go back from dock + (report-auto-dock) + (setq success-auto-dock (auto-dock :n-trial n-dock-trial :clear-costmap nil)) + ;; turn off light + (if (and success-auto-dock (not initial-light-on)) + (room-light-off :control-switchbot control-switchbot)) + ;; change the inflation_radius + (restore-params) + (send-kitchen-mail) + (setq success-battery-charging (progn (wait-until-is-charging) + (equal (get-battery-charging-state) :charging))) + (and success-go-to-kitchen success-auto-dock success-battery-charging))) + +(defun go-to-kitchen-state-machine () + (setq *sm* + (make-state-machine + '((:init -> :report-start-go-to-kitchen) + (:report-start-go-to-kitchen -> :get-light-on) + (:get-light-on -> :report-light-on) + (:get-light-on !-> :room-light-on) + (:report-light-on -> :move-to-dock-front) + (:room-light-on -> :move-to-dock-front) + + (:move-to-dock-front -> :inspect-dock-front) + (:move-to-dock-front !-> :report-move-to-dock-front-failure) + (:inspect-dock-front -> :move-to-tv-front) + (:report-move-to-dock-front-failure -> :move-to-tv-front) + + (:move-to-tv-front -> :inspect-tv-front) + (:move-to-tv-front !-> :report-move-to-tv-front-failure) + (:inspect-tv-front -> :move-to-tv-desk) + (:report-move-to-tv-front-failure -> :move-to-tv-desk) + + (:move-to-tv-desk -> :inspect-tv-desk) + (:move-to-tv-desk !-> :report-move-to-tv-desk-failure) + (:inspect-tv-desk -> :move-to-desk-back) + (:report-move-to-tv-desk-failure -> :move-to-desk-back) + + (:move-to-desk-back -> :inspect-desk-back) + (:move-to-desk-back !-> :report-move-to-desk-back-failure) + (:inspect-desk-back -> :move-to-desk-front) + (:report-move-to-desk-back-failure -> :move-to-desk-front) + + (:move-to-desk-front -> :inspect-desk-front) + (:move-to-desk-front !-> :report-move-to-desk-front-failure) + (:inspect-desk-front -> :move-to-kitchen-door-front) + (:report-move-to-desk-front-failure -> :move-to-kitchen-door-front) + + (:move-to-kitchen-door-front -> :inspect-kitchen-door-front) + (:move-to-kitchen-door-front !-> :report-move-to-kitchen-door-front-failure) + (:inspect-kitchen-door-front -> :move-to-sink-front) + (:report-move-to-kitchen-door-front-failure -> :move-to-sink-front) + + (:move-to-sink-front -> :inspect-kitchen) + (:move-to-sink-front !-> :report-move-to-sink-front-failure) + ;;(:inspect-kitchen -> :auto-dock) + (:report-move-to-sink-front-failure -> :auto-dock) + (:inspect-kitchen -> :move-to-trashcan-front) + (:move-to-trashcan-front -> :inspect-trashcan) + (:move-to-trashcan-front !-> :report-move-to-trashcan-front-failure) + (:inspect-trashcan -> :auto-dock) + (:report-move-to-trashcan-front-failure -> :auto-dock) + (:auto-dock -> :room-light-off) + (:auto-dock !-> :auto-dock-failure) + (:auto-dock-failure -> :room-light-off) + (:room-light-off -> :finish) + (:finish -> t) + (:finish !-> nil)) + '((:init + '(lambda (userdata) + (fetch-init) + (if (send *ri* :simulation-modep) + (progn + (load "models/room73b2-scene.l") + (load "package://jsk_maps/src/eng2-scene.l") + (room73b2) + (setq *base-spot* "/eng2/7f/room73B2-base") + (setq *scene* (make-eng2-7f-scene)) + (send *ri* :objects (send *room73b2* :objects)) + (send (send *ri* :robot) + :newcoords (car (get-spot-coords "/eng2/7f/room73B2-center"))) + )) + (undock) + (send *ri* :clear-costmap) + (store-params) + (inflation-loose) + (clear-app-notification) + (ros::subscribe "/head_camera/rgb/image_rect_color/compressed" + sensor_msgs::CompressedImage #'image-cb) + t)) + (:report-start-go-to-kitchen + '(lambda (userdata) + (report-start-go-to-kitchen) + (set-alist 'description "キッチンを見に行くよ" userdata) + (set-alist 'image "" userdata) + t)) + (:get-light-on + '(lambda (userdata) + (let ((light-on (get-light-on))) + (setf (cdr (assoc 'initial-light-on userdata)) light-on) + (ros::spin-once) + (if light-on + (set-alist 'description "電気がついていたよ" userdata) + (set-alist 'description "電気がついていなかったよ" userdata)) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + light-on))) + (:report-light-on + '(lambda (userdata) + (report-light-on) + (set-alist 'description "" userdata) + (set-alist 'image "" userdata) + t)) + (:room-light-on + '(lambda (userdata) + (let ((control-switchbot (cdr (assoc 'control-switchbot userdata))) + (label-names (notify-recognition :location "on the way to kitchen"))) + (report-light-off) + (room-light-on :control-switchbot control-switchbot) + (ros::spin-once) + (set-alist 'description "電気をつけたよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:move-to-dock-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-dock-front-trial userdata))) + (success (move-to-dock-front :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) + (setf (cdr (assoc 'success-go-to-dock-front userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "ドックの前に移動したよ" userdata) + (set-alist 'description "ドックの前に移動しようとしたけど,迷子になっちゃった" userdata)) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + success))) + (:inspect-dock-front + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-dock-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "ドックの前の様子を見たよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:report-move-to-dock-front-failure + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (report-move-to-dock-front-failure) + (ros::spin-once) + (set-alist 'description "ドックの前に移動できなかったよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:move-to-tv-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-tv-front-trial userdata))) + (success (move-to-tv-front :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-tv-front userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "テレビの前に移動したよ" userdata) + (set-alist 'description "テレビの前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image "" userdata) + success))) + (:inspect-tv-front + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-tv-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "テレビの前の様子を見たよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:report-move-to-tv-front-failure + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (report-move-to-tv-front-failure) + (ros::spin-once) + (set-alist 'description "テレビの前に移動できなかったよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:move-to-tv-desk + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-tv-desk-trial userdata))) + (success (move-to-tv-desk :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) + (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "机の前に移動したよ" userdata) + (set-alist 'description "机の前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image "" userdata) + success))) + (:inspect-tv-desk + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-tv-desk :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "机の様子を確認したよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:report-move-to-tv-desk-failure + '(lambda (userdata) + (let* (label-names (notify-recognition :location "on the way to kitchen")) + (report-move-to-tv-desk-failure) + (ros::spin-once) + (set-alist 'description "机の前に移動できなかったよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:move-to-desk-back + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-desk-back-trial userdata))) + (success (move-to-desk-back :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) + (setf (cdr (assoc 'success-go-to-desk-back userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "部屋の後ろに移動したよ" userdata) + (set-alist 'description "部屋の後ろに移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image "" userdata) + success))) + (:inspect-desk-back + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-desk-back :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "部屋の後ろを確認したよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:report-move-to-desk-back-failure + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (report-move-to-desk-back-failure) + (ros::spin-once) + (set-alist 'description "部屋の後ろに移動できなかったよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:move-to-desk-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-desk-front-trial userdata))) + (success (move-to-desk-front :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-desk-front userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "部屋の前に移動したよ" userdata) + (set-alist 'description "部屋の前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image "" userdata) + success))) + (:inspect-desk-front + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-desk-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "部屋の前を確認したよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:report-move-to-desk-front-failure + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (report-move-to-desk-front-failure) + (ros::spin-once) + (set-alist 'description "部屋の前に移動できなかったよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:move-to-kitchen-door-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-kitchen-door-front-trial userdata))) + (success (move-to-kitchen-door-front :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "ドアの前に移動したよ" userdata) + (set-alist 'description "ドアの前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image "" userdata) + success))) + (:inspect-kitchen-door-front + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "kitchen-door-front"))) + (inspect-kitchen-door-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "ドアの前からキッチンの様子を見たよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:report-move-to-kitchen-door-front-failure + '(lambda (userdata) + (report-move-to-kitchen-door-front-failure) + (ros::spin-once) + (set-alist 'description "ドアの前に移動できなかったよ" userdata) + (set-alist 'image "" userdata) + t)) + (:move-to-sink-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-kitchen-trial userdata))) + (success (move-to-sink-front :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) + (setf (cdr (assoc 'success-go-to-kitchen userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "キッチンに移動したよ" userdata) + (set-alist 'description "キッチンに移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image "" userdata) + success))) + (:inspect-kitchen + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "kitchen")) + (notify-text (if label-names (format nil "~Aがあったよ" label-names) ""))) + (inspect-kitchen :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:report-move-to-sink-front-failure + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "on the way to sink-front"))) + (report-move-to-sink-front-failure) + (ros::spin-once) + (set-alist 'description "キッチンに行けなかったよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) + (:move-to-trashcan-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-trashcan-trial userdata))) + (success (move-to-trashcan-front :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) + (setf (cdr (assoc 'success-go-to-trashcan userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "ゴミ箱の前に移動したよ" userdata) + (set-alist 'description "ゴミ箱の前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image "" userdata) + success))) + (:inspect-trashcan + '(lambda (userdata) + (inspect-trashcan :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "ゴミ箱の様子を確認したよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t)) + (:report-move-to-trashcan-front-failure + '(lambda (userdata) + (report-move-to-trashcan-front-failure) + (ros::spin-once) + (set-alist 'description "ゴミ箱の前に行けなかったよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t)) + (:auto-dock + '(lambda (userdata) + (report-auto-dock) + (let* ((n-trial (cdr (assoc 'n-dock-trial userdata))) + (success (auto-dock :n-trial n-trial :clear-costmap nil))) + (setf (cdr (assoc 'success-auto-dock userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "帰ってきたよ" userdata) + (set-alist 'description "帰ってこようとしたけど,迷子になっちゃった" userdata)) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + success))) + (:auto-dock-failure + '(lambda (userdata) + (report-auto-dock-failure) + (ros::spin-once) + (set-alist 'description "帰ってこられなかったよ" userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t)) + (:room-light-off + '(lambda (userdata) + (let ((success-auto-dock (cdr (assoc 'success-auto-dock userdata))) + (initial-light-on (cdr (assoc 'initial-light-on userdata))) + (control-switchbot (cdr (assoc 'control-switchbot userdata)))) + (if (and success-auto-dock (not initial-light-on)) + (progn + (room-light-off :control-switchbot control-switchbot) + (ros::spin-once) + (set-alist 'description "電気を消したよ" userdata) + (set-alist 'image "" userdata)))) + t)) + (:finish + '(lambda (userdata) + (let ((success-battery-charging + (progn (wait-until-is-charging) + (equal (get-battery-charging-state) :charging))) + (success-auto-dock (cdr (assoc 'success-auto-dock userdata))) + (success-go-to-kitchen + (cdr (assoc 'success-go-to-kitchen userdata)))) + (restore-params) + (ros::spin-once) + (set-alist 'description "キッチンデモを終えるよ" userdata) + (set-alist 'image "" userdata) + (and success-go-to-kitchen success-auto-dock success-battery-charging))))) + '(:init) + '(t nil)))) (defun main (&key (tweet t) (n-dock-trial 3) (n-kitchen-trial 3) (n-trashcan-trial 3) (n-dock-front-trial 3) (n-tv-front-trial 3) (n-tv-desk-trial 3) (n-desk-back-trial 3) (n-desk-front-trial 3) (n-kitchen-door-front-trial 3) (control-switchbot :api)) (when (not (boundp '*sm*)) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 13bdcee901..11cf8a9218 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -1,23 +1,21 @@ (load "package://jsk_robot_startup/lifelog/tweet_client.l") (load "package://jsk_fetch_startup/euslisp/notify-app.l") -(load "package://switchbot_ros/scripts/switchbot.l") -(require :state-machine "package://roseus_smach/src/state-machine.l") -(require :state-machine-ros "package://roseus_smach/src/state-machine-ros.l") -(require :state-machine-utils "package://roseus_smach/src/state-machine-utils.l") -(require :base64 "lib/llib/base64.l") +(if (ros::rospack-find "switchbot_ros") + (load "package://switchbot_ros/scripts/switchbot.l")) (ros::load-ros-manifest "fetch_auto_dock_msgs") (ros::load-ros-manifest "jsk_robot_startup") (ros::load-ros-manifest "jsk_recognition_msgs") (ros::load-ros-manifest "power_msgs") +(ros::load-ros-manifest "sensor_msgs") +(if (ros::rospack-find "smart_device_protocol") + (ros::load-ros-manifest "smart_device_protocol")) (defparameter *dock-action* nil) (defparameter *undock-action* nil) (defparameter *spots* nil) (defparameter *tfl* (instance ros::transform-listener :init)) -(ros::advertise "/photo_taken" sensor_msgs::Image 1) - (let ((robot-name (ros::get-param "/robot/name"))) (defparameter *dock-spot* (cond @@ -25,7 +23,7 @@ "/eng2/7f/room73B2-fetch-dock-front") ((equal robot-name "fetch1075") "/eng2/7f/room73B2-fetch-dock2-front") - (t nil)))) + (t "/eng2/7f/room73B2-fetch-dock2-front")))) (defun store-params () @@ -37,14 +35,18 @@ (defun restore-params () - (if (boundp '*global-inflation-radius*) - (ros::set-dynamic-reconfigure-param - "/move_base/global_costmap/inflater" "inflation_radius" - :double *global-inflation-radius*)) - (if (boundp '*local-inflation-radius*) - (ros::set-dynamic-reconfigure-param - "/move_base/local_costmap/inflater" "inflation_radius" - :double *local-inflation-radius*)) + (let ((global-costmap-server "/move_base/global_costmap/inflater") + (local-costmap-server "/move_base/local_costmap/inflater")) + (if (and (boundp '*global-inflation-radius*) + (ros::wait-for-service (format nil "~A/set_parameters" global-costmap-server) 1)) + (ros::set-dynamic-reconfigure-param + "/move_base/global_costmap/inflater" "inflation_radius" + :double *global-inflation-radius*)) + (if (and (boundp '*local-inflation-radius*) + (ros::wait-for-service (format nil "~A/set_parameters" local-costmap-server) 1)) + (ros::set-dynamic-reconfigure-param + "/move_base/local_costmap/inflater" "inflation_radius" + :double *local-inflation-radius*))) t) @@ -62,17 +64,26 @@ (defun get-spot-coords (name) - (unless *spots* - (setq *spots* (one-shot-subscribe "/spots_marker_array" visualization_msgs::MarkerArray))) - (let ((spot-coords nil) (frame-id nil)) - (dolist (x (send *spots* :markers)) - (if (equal (send x :text) name) - (progn - (setq spot-coords (send x :pose)) - (setq frame-id (send (send x :header) :frame_id))))) - (send (send spot-coords :position) :z 0) - (setq spot-coords (ros::tf-pose->coords spot-coords)) - (cons spot-coords frame-id))) + (if (send *ri* :simulation-modep) + (let ((base-coords (send *scene* :spot *base-spot*)) + (spot-coords (send *scene* :spot name)) + (goal-coords nil)) + (if (and base-coords spot-coords) + (setq goal-coords (send base-coords :transformation spot-coords))) + (cons goal-coords nil)) + (progn + (unless *spots* + (setq *spots* (one-shot-subscribe "/spots_marker_array" visualization_msgs::MarkerArray))) + (let ((spot-coords nil) (frame-id nil)) + (dolist (x (send *spots* :markers)) + (if (equal (send x :text) name) + (progn + (setq spot-coords (send x :pose)) + (setq frame-id (send (send x :header) :frame_id))))) + (send (send spot-coords :position) :z 0) + (setq spot-coords (ros::tf-pose->coords spot-coords)) + (cons spot-coords frame-id)) + ))) (defun simple-dock (&key (use-pose t)) @@ -82,7 +93,7 @@ "/dock" fetch_auto_dock_msgs::DockAction))) (unless (send *dock-action* :wait-for-server 5) (ros::ros-error "/dock action server is not started") - (return-from dock nil)) + (return-from simple-dock nil)) (let ((dock-action-goal (instance fetch_auto_dock_msgs::DockActionGoal :init))) (when use-pose (let* ((timestamp (ros::time-now)) @@ -117,7 +128,7 @@ (simple-dock)) -(defun undock () +(defun undock (&key (rotate-in-place nil)) (unless *undock-action* (setq *undock-action* (instance ros::simple-action-client :init @@ -126,14 +137,47 @@ (ros::ros-error "/undock action server is not started") (return-from undock nil)) (send *undock-action* :send-goal - (instance fetch_auto_dock_msgs::UndockActionGoal :init)) + (instance fetch_auto_dock_msgs::UndockActionGoal :init + :goal (instance fetch_auto_dock_msgs::UndockGoal :rotate_in_place rotate-in-place))) (unless (send *undock-action* :wait-for-result :timeout 60) (ros::ros-error "No result returned from /undock action server") (return-from undock nil)) (send (send *undock-action* :get-result) :undocked)) +(defun wait-until-is-charging (&key (timeout 10)) + """ + Wait for updating battery charging state especially when robots dock. + Args: + - key + timeout [sec]: Set waiting time for updating /battery_state topic + + ;; If /battery_state is subscribed before /battery_state becomes true + ;; while dock succeeds, the result will not be correct, + ;; so wait for a certain time when docking. + """ + (if (send *ri* :simulation-modep) (return-from wait-until-is-charging nil)) + (let* ((msg nil) + (is-charging nil) + (duration 0) + (start-time (send (ros::time-now) :sec))) + (while (not is-charging) + (when (> duration timeout) + (ros::ros-warn "Skip waiting for charging state because of timeout") + (return-from wait-until-is-charging :timeout)) + (setq msg (one-shot-subscribe "/battery_state" power_msgs::BatteryState + :timeout 1000)) + (if msg (setq is-charging (send msg :is_charging))) + (setq duration (- (send (ros::time-now) :sec) start-time))) + :charging)) (defun get-battery-charging-state (&key (timeout 1500)) + """ + Get battery charging state + Args: + - key + timeout: Set waiting time for topic. + """ + (if (send *ri* :simulation-modep) (return-from get-battery-charging-state nil)) (let* ((msg (one-shot-subscribe "/battery_state" power_msgs::batterystate :timeout timeout)) (is-charging (if msg (send msg :is_charging)))) ;; You may fail to subscribe /battery_state @@ -141,7 +185,6 @@ (if (not msg) (return-from get-battery-charging-state nil)) (if is-charging :charging :discharging))) - (defun go-to-spot (name &key (relative-pos nil) (relative-rot nil) (undock-rotate nil) (clear-costmap t)) "Move the robot to the spot defined in /spots_marker_array topic. The reason for using relative-pos and relative-rot instead of relative-coords is that it is easier to understand if relative-pos and relative-rot are specified in the different coords (specifically, world (map) and local (spot) coords respectively). For detail, see https://github.com/jsk-ros-pkg/jsk_robot/pull/1458#pullrequestreview-1039654868 Args: @@ -169,10 +212,7 @@ Args: (return-from go-to-spot-undock t)) (if (equal battery-charging-state :charging) (progn - (setq undock-success (auto-undock :n-trial 3)) - ;; rotate after undock - (if (and undock-success undock-rotate) - (send *ri* :go-pos-unsafe 0 0 180))) + (setq undock-success (auto-undock :n-trial 3 :rotate-in-place undock-rotate))) (return-from go-to-spot-undock t)) (if (not undock-success) (progn @@ -187,7 +227,9 @@ Args: (setq goal-pose (send goal-pose :translate relative-pos :world))) (when relative-rot (setq goal-pose (send goal-pose :rotate relative-rot :z :local))) - (send *ri* :move-to goal-pose :frame-id frame-id))) + (if frame-id + (send *ri* :move-to goal-pose :frame-id frame-id) + (send *ri* :move-to goal-pose)))) (defun auto-dock (&key (n-trial 1) (clear-costmap t)) @@ -197,19 +239,19 @@ Args: :relative-pos #f(-800 0 0) :clear-costmap clear-costmap) (ros::ros-info "arrived at the dock.") - (setq success (dock)) + (setq success (if (send *ri* :simulation-modep) t (dock))) (when success (return-from auto-dock success)))) success)) -(defun auto-undock (&key (n-trial 1)) +(defun auto-undock (&key (n-trial 1) (rotate-in-place nil)) (let ((success nil)) (unless (boundp '*ri*) (require :fetch-interface "package://fetcheus/fetch-interface.l") (fetch-init)) (dotimes (i n-trial) (ros::ros-info "trying to do undock.") - (setq success (undock)) + (setq success (undock :rotate-in-place rotate-in-place)) (when success (return-from auto-undock success))) (if (not success) (let ((enable-request (instance power_msgs::BreakerCommandRequest :init :enable t)) @@ -288,7 +330,7 @@ Args: (ros::ros-info "start going back to the dock.") (send *ri* :speak-jp "ドックに戻ります。" :wait t)) -(defun report-move-to-sink-front-success () +(defun report-move-to-sink-front () (ros::ros-info "arrived at the kitchen stove.") (send *ri* :speak-jp "キッチンのコンロの前につきました。" :wait t)) @@ -382,10 +424,17 @@ Args: (defun notify-recognition (&key (location "kitchen")) (let* ((msg (one-shot-subscribe "/edgetpu_object_detector/output/class" - jsk_recognition_msgs::ClassificationResult)) - (label-names (send msg :label_names))) + jsk_recognition_msgs::ClassificationResult + :timeout 3000)) + (label-names (if msg (send msg :label_names)))) (when label-names (ros::ros-info (format nil "Notify app that ~A is found." label-names)) + (write-message-on-message-board + (list 120 33 132 149 126 152) + (format nil "Notify app that ~A is found." label-names) + (ros::time 600) + (ros::get-param "/robot/name" "default_name") + ) (notify-app "object recognition" (send msg :header :stamp) location @@ -403,8 +452,32 @@ Args: location (format nil "CO2 concentration is ~A ppm" (send msg :data)))))) +(defun notify-trashcan-occupancy (&key (location "kitchen")) + (let* ((msg (one-shot-subscribe "/trashbin_occupancy_detector/container/occupancies" + jsk_recognition_msgs::BoundingBoxArray + :timeout 3000)) + (occupancy (if msg (send (elt (send msg :boxes) 0) :value))) + (notify-text (if occupancy (if (> occupancy 1.0) + "Trashcan is full." + "Trashcan is not full.")))) + (when occupancy + (ros::ros-info + (format nil "Notify app that the occupancy of trash can is measured. ~A." occupancy)) + (write-message-on-message-board + (list 120 33 132 149 126 152) + (format nil "~A Trashcan occupancy is ~A" notify-text occupancy) + (ros::time 600) + (ros::get-param "/robot/name" "default_name") + ) + (notify-app "trashcan occupancy" + (ros::time-now) + location + (format nil "~A Trashcan occupancy is ~A" + notify-text + occupancy))))) + (defun inspect-kitchen (&key (tweet t)) - (report-move-to-sink-front-success) + (report-move-to-sink-front) (if tweet (progn ;; stove @@ -417,7 +490,7 @@ Args: ;; sink (tweet-string "I took a photo at 73B2 Kitchen sink." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img)) (take-photo "kitchen_sink.jpg") (notify-recognition :location "kitchen sink")) @@ -433,51 +506,57 @@ Args: (when success-move-to-sink-front (return))) success-move-to-sink-front)) -(defun move-to-dock-front (&key (n-trial 1) (offset #f(400 -500 0))) +(defun move-to-dock-front (&key (n-trial 1) (offset #f(0 0 0))) (let ((success-move-to-dock-front nil)) (dotimes (i n-trial) (setq success-move-to-dock-front - (send *ri* :move-to (make-coords :pos (float-vector 5077.8 6763.237 30000.0) :rpy (float-vector 0.059 0 0)) :relative-pos offset)) + (go-to-spot *dock-spot* + :relative-pos offset :undock-rotate t)) (when success-move-to-dock-front (return))) success-move-to-dock-front)) -(defun move-to-tv-front (&key (n-trial 1) (offset #f(400 -500 0))) +(defun move-to-tv-front (&key (n-trial 1) (offset #f(0 0 0))) (let ((success-move-to-tv-front nil)) (dotimes (i n-trial) (setq success-move-to-tv-front - (send *ri* :move-to (make-coords :pos (float-vector 5082.057 6800.628 30000.0) :rpy (float-vector 3.109 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-tv-front" + :relative-pos offset :undock-rotate t)) (when success-move-to-tv-front (return))) success-move-to-tv-front)) -(defun move-to-tv-desk (&key (n-trial 1) (offset #f(400 -500 0))) +(defun move-to-tv-desk (&key (n-trial 1) (offset #f(0 0 0))) (let ((success-move-to-tv-desk nil)) (dotimes (i n-trial) (setq success-move-to-tv-desk - (send *ri* :move-to (make-coords :pos (float-vector 4035.759 7343.818 30000.0) :rpy (float-vector 1.753 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-tv-desk" + :relative-pos offset :undock-rotate t)) (when success-move-to-tv-desk (return))) success-move-to-tv-desk)) -(defun move-to-desk-back (&key (n-trial 1) (offset #f(400 -500 0))) +(defun move-to-desk-back (&key (n-trial 1) (offset #f(0 0 0))) (let ((success-move-to-desk-back nil)) (dotimes (i n-trial) (setq success-move-to-desk-back - (send *ri* :move-to (make-coords :pos (float-vector 4324.417 6121.184 30000.0) :rpy (float-vector -0.845 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-desk-back" + :relative-pos offset :undock-rotate t)) (when success-move-to-desk-back (return))) success-move-to-desk-back)) -(defun move-to-desk-front (&key (n-trial 1) (offset #f(400 -500 0))) +(defun move-to-desk-front (&key (n-trial 1) (offset #f(0 0 0))) (let ((success-move-to-desk-front nil)) (dotimes (i n-trial) (setq success-move-to-desk-front - (send *ri* :move-to (make-coords :pos (float-vector 4318.808 6108.146 30000.0) :rpy (float-vector -2.231 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-desk-front" + :relative-pos offset :undock-rotate t)) (when success-move-to-desk-front (return))) success-move-to-desk-front)) -(defun move-to-kitchen-door-front (&key (n-trial 1) (offset #f(400 -500 0))) +(defun move-to-kitchen-door-front (&key (n-trial 1) (offset #f(0 0 0))) (let ((success-move-to-kitchen-door-front nil)) (dotimes (i n-trial) (setq success-move-to-kitchen-door-front - (send *ri* :move-to (make-coords :pos (float-vector 1558.69 7230.57 30000.0) :rpy (float-vector 2.296 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-kitchen-door-front" + :relative-pos offset :undock-rotate t)) (when success-move-to-kitchen-door-front (return))) success-move-to-kitchen-door-front)) @@ -490,7 +569,7 @@ Args: (progn (tweet-string "I took a photo in front of the dock." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-tv-front (&key (tweet t)) @@ -502,7 +581,7 @@ Args: (progn (tweet-string "I took a photo in front of the tv." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-tv-desk (&key (tweet t)) @@ -514,7 +593,7 @@ Args: (progn (tweet-string "I took a photo in front of the tv." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-desk-back (&key (tweet t)) @@ -526,7 +605,7 @@ Args: (progn (tweet-string "I took a photo of desks." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-desk-front (&key (tweet t)) @@ -538,7 +617,7 @@ Args: (progn (tweet-string "I took a photo of desks." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-kitchen-door-front (&key (tweet t)) @@ -550,7 +629,7 @@ Args: (progn (tweet-string "I took a photo of kitchen." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-trashcan (&key (tweet t)) @@ -569,10 +648,11 @@ Args: (send *ri* :wait-interpolation) (tweet-string "I took a photo of 73B2 trash can inside." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img)) (take-photo "trashcan_inside.jpg") (notify-recognition :location "trash cans inside") + (notify-trashcan-occupancy :location "trash can") (send *ri* :go-pos-unsafe -0.2 0 0)) (progn (notify-recognition :location "trash cans")))) @@ -588,364 +668,39 @@ Args: (send *ri* :go-pos-unsafe 0 0 -80) ;; face the front against the trash can success-move-to-trashcan-front)) -(defun image-cb (msg) - (setq *image* msg)) +(defun padding-byte-array (byte-array target-length) + (concatenate cons byte-array (make-list (- target-length (length byte-array)) :initial-element 0))) + +(defun write-message-on-message-board (target-addr message timeout-duration source-name) + "Send packet to write message on a message board. + + Args: + target-addr: list of integer to represent mac address of target message board. + message: string + timeout-duration: ros::time to represent message timoeut + source-name: string + " + (let* ((packet-type-array (list 42 0)) + (source-name-array (padding-byte-array (coerce source-name cons) 64)) + (timeout-duration-msec (floor (* 1000 (send timeout-duration :to-sec)))) + (timeout-duration-array + (mapcar + #'(lambda (order) + (/ + (- timeout-duration-msec + (* (round (expt 256 (+ 1 order))) (/ timeout-duration-msec (round (expt 256 (+ 1 order)))))) + (round (expt 256 order)))) + '(0 1 2 3 4 5 6 7) + )) + (message-array (padding-byte-array (coerce message cons) 64)) + (byte-data (concatenate cons packet-type-array source-name-array timeout-duration-array message-array)) + (msg (instance smart_device_protocol::Packet :init + :mac_address (coerce target-addr string) + :data (coerce byte-data string))) + ) + (ros::advertise "/smart_device_protocol/send" smart_device_protocol::Packet 1) + (ros::publish "/smart_device_protocol/send" msg) + (ros::ros-info "Write message ~A to board ~A" message target-addr) + ) + ) -(defun go-to-kitchen (&key (tweet t) (n-dock-trial 1) (n-kitchen-trial 1) - (control-switchbot :api)) - ;; go to kitchen - (unless (boundp '*ri*) - (require :fetch-interface "package://fetcheus/fetch-interface.l") - (fetch-init)) - (report-start-go-to-kitchen) - ;; Check if the lights are on in the room - (let ((initial-light-on (get-light-on)) - (success-go-to-kitchen nil) - (success-go-to-trashcan nil) - (success-auto-dock nil) - (success-battery-charging nil)) - (store-params) - ;; turn on light - (if initial-light-on - (report-light-on) - (progn - (report-light-off) - (room-light-on :control-switchbot control-switchbot))) - ;; change the inflation_radius - (inflation-loose) - ;; go to kitchen sink - (setq success-go-to-kitchen (move-to-sink-front :n-trial n-kitchen-trial)) - ;; report result to go to kitchen - (if success-go-to-kitchen - (inspect-kitchen :tweet tweet) - (report-move-to-sink-front-failure)) - ;; go to kitchen trash can - (setq success-go-to-trashcan (move-to-trashcan-front :n-trial n-trashcan-trial)) - ;; report result to go to trash can - (if success-go-to-trashcan - (inspect-trashcan :tweet tweet) - (report-move-to-trashcan-front-failure)) - ;; go back from dock - (report-auto-dock) - (setq success-auto-dock (auto-dock :n-trial n-dock-trial :clear-costmap nil)) - ;; turn off light - (if (and success-auto-dock (not initial-light-on)) - (room-light-off :control-switchbot control-switchbot)) - ;; change the inflation_radius - (restore-params) - (send-kitchen-mail) - (setq success-battery-charging (equal (get-battery-charging-state) :charging)) - (and success-go-to-kitchen success-auto-dock success-battery-charging))) - - -(defun go-to-kitchen-state-machine () - (setq *sm* - (make-state-machine - '((:init -> :report-start-go-to-kitchen) - (:report-start-go-to-kitchen -> :get-light-on) - (:get-light-on -> :report-light-on) - (:get-light-on !-> :room-light-on) - (:report-light-on -> :move-to-dock-front) - (:room-light-on -> :move-to-dock-front) - - (:move-to-dock-front -> :inspect-dock-front) - (:move-to-dock-front !-> :report-move-to-dock-front-failure) - (:inspect-dock-front -> :move-to-tv-front) - (:report-move-to-dock-front-failure -> :move-to-tv-front) - - (:move-to-tv-front -> :inspect-tv-front) - (:move-to-tv-front !-> :report-move-to-tv-front-failure) - (:inspect-tv-front -> :move-to-tv-desk) - (:report-move-to-tv-front-failure -> :move-to-tv-desk) - - (:move-to-tv-desk -> :inspect-tv-desk) - (:move-to-tv-desk !-> :report-move-to-tv-desk-failure) - (:inspect-tv-desk -> :move-to-desk-back) - (:report-move-to-tv-desk-failure -> :move-to-desk-back) - - (:move-to-desk-back -> :inspect-desk-back) - (:move-to-desk-back !-> :report-move-to-desk-back-failure) - (:inspect-desk-back -> :move-to-desk-front) - (:report-move-to-desk-back-failure -> :move-to-desk-front) - - (:move-to-desk-front -> :inspect-desk-front) - (:move-to-desk-front !-> :report-move-to-desk-front-failure) - (:inspect-desk-front -> :move-to-kitchen-door-front) - (:report-move-to-desk-front-failure -> :move-to-kitchen-door-front) - - (:move-to-kitchen-door-front -> :inspect-kitchen-door-front) - (:move-to-kitchen-door-front !-> :report-move-to-kitchen-door-front-failure) - (:inspect-kitchen-door-front -> :move-to-sink-front) - (:report-move-to-kitchen-door-front-failure -> :move-to-sink-front) - - (:move-to-sink-front -> :inspect-kitchen) - (:move-to-sink-front !-> :report-move-to-sink-front-failure) - ;;(:inspect-kitchen -> :auto-dock) - ;;(:report-move-to-sink-front-failure -> :auto-dock) - (:inspect-kitchen -> :move-to-trashcan-front) - (:move-to-trashcan-front -> :inspect-trashcan) - (:move-to-trashcan-front !-> :report-move-to-trashcan-front-failure) - (:inspect-trashcan -> :auto-dock) - (:report-move-to-trashcan-front-failure -> :auto-dock) - (:auto-dock -> :room-light-off) - (:room-light-off -> :finish) - (:finish -> t) - (:finish !-> nil)) - '((:init - '(lambda (userdata) - (fetch-init) - (undock) - (send *ri* :clear-costmap) - (store-params) - (inflation-loose) - (clear-app-notification) - (ros::subscribe "/edgetpu_object_detector/output/image/compressed" - sensor_msgs::CompressedImage #'image-cb) - t)) - (:report-start-go-to-kitchen - '(lambda (userdata) - (report-start-go-to-kitchen) - (set-alist 'description "キッチンを見に行くよ" userdata) - (set-alist 'image "" userdata) - t)) - (:get-light-on - '(lambda (userdata) - (let ((light-on (get-light-on))) - (setf (cdr (assoc 'initial-light-on userdata)) light-on) - (if light-on - (set-alist 'description "電気がついていたよ" userdata) - (set-alist 'description "電気がついていなかったよ" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - light-on))) - (:report-light-on - '(lambda (userdata) - (report-light-on) - t)) - (:room-light-on - '(lambda (userdata) - (let ((control-switchbot (cdr (assoc 'control-switchbot userdata)))) - (report-light-off) - (room-light-on :control-switchbot control-switchbot) - (set-alist 'description "電気をつけたよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t))) - (:move-to-dock-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-dock-front-trial userdata))) - (success (move-to-dock-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-dock-front userdata)) success) - (if success - (set-alist 'description "ドックの前に移動したよ" userdata) - (set-alist 'description "ドックの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-dock-front - '(lambda (userdata) - (inspect-dock-front :tweet (cdr (assoc 'tweet userdata))) - (set-alist 'description "ドックの前の様子を見たよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-dock-front-failure - '(lambda (userdata) - (report-move-to-dock-front-failure) - (set-alist 'description "ドックの前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-tv-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-tv-front-trial userdata))) - (success (move-to-tv-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-tv-front userdata)) success) - (if success - (set-alist 'description "テレビの前に移動したよ" userdata) - (set-alist 'description "テレビの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-tv-front - '(lambda (userdata) - (inspect-tv-front :tweet (cdr (assoc 'tweet userdata))) - (set-alist 'description "テレビの前の様子を見たよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-tv-front-failure - '(lambda (userdata) - (report-move-to-tv-front-failure) - (set-alist 'description "テレビの前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-tv-desk - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-tv-desk-trial userdata))) - (success (move-to-tv-desk :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) - (if success - (set-alist 'description "机の前に移動したよ" userdata) - (set-alist 'description "机の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-tv-desk - '(lambda (userdata) - (inspect-tv-desk :tweet (cdr (assoc 'tweet userdata))) - (set-alist 'description "机の様子を確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-tv-desk-failure - '(lambda (userdata) - (report-move-to-tv-desk-failure) - (set-alist 'description "机の前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-desk-back - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-desk-back-trial userdata))) - (success (move-to-desk-back :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-desk-back userdata)) success) - (if success - (set-alist 'description "部屋の後ろに移動したよ" userdata) - (set-alist 'description "部屋の後ろに移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-desk-back - '(lambda (userdata) - (inspect-desk-back :tweet (cdr (assoc 'tweet userdata))) - (set-alist 'description "部屋の後ろを確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-desk-back-failure - '(lambda (userdata) - (report-move-to-desk-back-failure) - (set-alist 'description "部屋の後ろに移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-desk-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-desk-front-trial userdata))) - (success (move-to-desk-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-desk-front userdata)) success) - (if success - (set-alist 'description "部屋の前に移動したよ" userdata) - (set-alist 'description "部屋の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-desk-front - '(lambda (userdata) - (inspect-desk-front :tweet (cdr (assoc 'tweet userdata))) - (set-alist 'description "部屋の前を確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-desk-front-failure - '(lambda (userdata) - (report-move-to-desk-front-failure) - (set-alist 'description "部屋の前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-kitchen-door-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-kitchen-door-front-trial userdata))) - (success (move-to-kitchen-door-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) - (if success - (set-alist 'description "ドアの前に移動したよ" userdata) - (set-alist 'description "ドアの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-kitchen-door-front - '(lambda (userdata) - (inspect-kitchen-door-front :tweet (cdr (assoc 'tweet userdata))) - (set-alist 'description "ドアの前からキッチンの様子を見たよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-kitchen-door-front-failure - '(lambda (userdata) - (report-move-to-kitchen-door-front-failure) - (set-alist 'description "ドアの前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-sink-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-kitchen-trial userdata))) - (success (move-to-sink-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-kitchen userdata)) success) - (if success - (set-alist 'description "キッチンに移動したよ" userdata) - (set-alist 'description "キッチンに移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-kitchen - '(lambda (userdata) - (let* ((label-names (notify-recognition :location "kitchen")) - (notify-text (if label-names (format nil "~Aがあったよ" label-names) ""))) - (inspect-kitchen :tweet (cdr (assoc 'tweet userdata))) - (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-sink-front-failure - '(lambda (userdata) - (report-move-to-sink-front-failure) - (set-alist 'description "キッチンに行けなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-trashcan-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-trashcan-trial userdata))) - (success (move-to-trashcan-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-trashcan userdata)) success) - (if success - (set-alist 'description "ゴミ箱の前に移動したよ" userdata) - (set-alist 'description "ゴミ箱の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-trashcan - '(lambda (userdata) - (inspect-trashcan :tweet (cdr (assoc 'tweet userdata))) - (set-alist 'description "ゴミ箱の様子を確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-trashcan-front-failure - '(lambda (userdata) - (report-move-to-trashcan-front-failure) - (set-alist 'description "ゴミ箱の前に行けなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:auto-dock - '(lambda (userdata) - (report-auto-dock) - (let* ((n-trial (cdr (assoc 'n-dock-trial userdata))) - (success (auto-dock :n-trial n-trial :clear-costmap nil))) - (setf (cdr (assoc 'success-auto-dock userdata)) success) - (if success - (set-alist 'description "帰ってきたよ" userdata) - (set-alist 'description "帰ってこようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:auto-dock-failure - '(lambda (userdata) - (report-auto-dock-failure) - (set-alist 'description "帰ってこられなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:room-light-off - '(lambda (userdata) - (let ((success-auto-dock (cdr (assoc 'success-auto-dock userdata))) - (initial-light-on (cdr (assoc 'initial-light-on userdata))) - (control-switchbot (cdr (assoc 'control-switchbot userdata)))) - (if (and success-auto-dock (not initial-light-on)) - (progn - (room-light-off :control-switchbot control-switchbot) - (set-alist 'description "電気を消したよ" userdata) - (set-alist 'image "" userdata)))) - t)) - (:finish - '(lambda (userdata) - (let ((success-battery-charging - (progn (wait-until-is-charging) - (equal (get-battery-charging-state) :charging))) - (success-auto-dock (cdr (assoc 'success-auto-dock userdata))) - (success-go-to-kitchen - (cdr (assoc 'success-go-to-kitchen userdata)))) - (restore-params) - (set-alist 'description "キッチンデモを終えるよ" userdata) - (set-alist 'image "" userdata) - (and success-go-to-kitchen success-auto-dock success-battery-charging))))) - '(:init) - '(t nil)))) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/devices/realsense_nodelet.launch.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/devices/realsense_nodelet.launch.xml index a72dd3f2d1..c5993ed682 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/devices/realsense_nodelet.launch.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/devices/realsense_nodelet.launch.xml @@ -3,6 +3,8 @@ This launch file is copied from realsense2_camera in realsense_ros https://github.com/IntelRealSense/realsense-ros and then modified And it is originally distributed under Apache-2.0 License --> + + @@ -10,6 +12,7 @@ + @@ -101,11 +104,12 @@ + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch index 0bccd16208..f06beff91f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch @@ -2,19 +2,22 @@ - - - - - + + + + + + - + + + @@ -31,7 +34,6 @@ - @@ -39,6 +41,8 @@ + + @@ -107,7 +111,12 @@ false, false, false] odom0_nodelay: true odom0_differential: true + permit_corrected_publication: false + @@ -137,7 +146,7 @@ command="$(find xacro)/xacro $(find jsk_fetch_startup)/robots/jsk_fetch.urdf.xacro ros_distro:=$(env ROS_DISTRO) use_fetch_description:=$(arg use_fetch_description) base_camera_mount:=$(arg use_base_camera_mount) head_box:=$(arg use_head_box) - head_l515:=$(arg use_head_l515)" /> + head_l515:=$(arg use_head_l515) insta360_stand:=$(arg insta360_stand)" /> diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_auto_dock.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_auto_dock.xml new file mode 100644 index 0000000000..be7b25f86c --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_auto_dock.xml @@ -0,0 +1,14 @@ + + + + + duration_timeout_undock: 10.0 + duration_timeout_preorientation: 20.0 + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 996ee01797..539974b2b4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -1,17 +1,69 @@ - + - + + + + + + + + - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - + + @@ -20,25 +72,27 @@ + respawn="true" output="screen" if="$(arg launch_battery_warning)"> duration: 180 - charge_level_threshold: 80.0 + charge_level_threshold: 65.0 shutdown_level_threshold: 60.0 charge_level_step: 10.0 volume: 1.0 - + lang: japanese volume: 0.5 - + - + @@ -51,21 +105,30 @@ - - - - + + + + + + + default_voice: $(arg default_english_speaker) + plugin: sound_play/flite_plugin + + + - - - - - - - - - + + + + + + + + + + + @@ -73,14 +136,17 @@ - + + + name="diag_agg" args="CPP" output="screen" + clear_params="true" > @@ -95,80 +161,138 @@ - + - + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + - + + - + - + interface_name: wlan0 - - - - - - - - - - - - - - - - - - - - - tts_action_names: - - sound_play - - robotsound_jp - + + + + + + + + + + + + + + + + + + + + + + tts_action_names: + - sound_play + - robotsound_jp + + + + + + + + + default_select: speech_to_text_google + patient: 6 + + - - - - - - - default_select: speech_to_text_google - patient: 6 - - @@ -178,14 +302,15 @@ - + vital_rate: 0.1 - + @@ -227,17 +352,22 @@ + output="screen" if="$(arg launch_build_map)" > - + + + luminance_threshold: 70 + - + map_frame: /map base_frame: /base_link @@ -245,30 +375,97 @@ - + - - - - email_info: /var/lib/robot/email_topic.yaml - - + + + + + email_info: /var/lib/robot/email_topic.yaml + + + + + + + + + use_mail: true + use_twitter: $(arg launch_tweet) + use_google_chat: $(arg launch_google_chat) + google_chat_space: spaces/AAAARE9CrfA + + + - - + + - email_info: /var/lib/robot/email_topic.yaml + duration: 0.5 + + + + + - - + + + + + + + + + + + + + + + + + + + + run_stop_topic: robot_state + run_stop_condition: "m.runstopped is True" + seconds_to_start_speaking: 60 + speak_interval: 600 + language: $(arg default_warning_speaker) + ignore_time_after_runstop_is_enabled: 5.0 + ignore_time_after_runstop_is_disabled: 5.0 + + + + + + + + - + duration: 60 diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch new file mode 100644 index 0000000000..237ef48534 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch @@ -0,0 +1,56 @@ + + + + + + + + + + + + edgetpu_human_node_manager: + nodes: + - name: edgetpu_human_pose_estimator + type: human_pose_estimator + - name: edgetpu_panorama_human_pose_estimator + type: panorama_human_pose_estimator + default: edgetpu_human_pose_estimator + edgetpu_human_pose_estimator: + input_topic: $(arg input_image) + image_transport: raw + device_id: 0 + edgetpu_panorama_human_pose_estimator: + input_topic: $(arg input_panorama_image) + image_transport: raw + device_id: 0 + + + + + + + edgetpu_object_node_manager: + nodes: + - name: edgetpu_object_detector + type: object_detector + - name: edgetpu_panorama_object_detector + type: panorama_object_detector + default: edgetpu_object_detector + edgetpu_object_detector: + input_topic: $(arg input_image) + image_transport: raw + device_id: 1 + model_file: /etc/ros/jsk_data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite + label_file: /etc/ros/jsk_data/coral_usb/73b2_kitchen_labels.txt + edgetpu_panorama_object_detector: + input_topic: $(arg input_panorama_image) + image_transport: raw + device_id: 1 + model_file: /etc/ros/jsk_data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite + label_file: /etc/ros/jsk_data/coral_usb/73b2_kitchen_labels.txt + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch new file mode 100644 index 0000000000..a236629a55 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_gazebo_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_gazebo_bringup.launch index 62ec7167f5..0d48cab9e7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_gazebo_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_gazebo_bringup.launch @@ -4,6 +4,9 @@ + + + @@ -31,13 +34,51 @@ + + + + + + + + + + - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_indigo.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_indigo.launch index 5cd5374aa4..2835f972fd 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_indigo.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_indigo.launch @@ -1,6 +1,7 @@ + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch index c94523f778..9958ed71f2 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch @@ -2,14 +2,18 @@ + - - + + + + + @@ -21,8 +25,8 @@ - scale_width: 0.25 - scale_height: 0.25 + scale_width: 0.5 + scale_height: 0.5 diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml index f685bdd841..4c61e45da8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml @@ -2,6 +2,8 @@ + + @@ -11,23 +13,28 @@ + + + + - - + + + @@ -73,4 +80,10 @@ - sound_play/SoundRequestActionGoal - sound_play/SoundRequestActionResult + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch index afbedb15e5..1e0ab40556 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch @@ -1,12 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + @@ -56,13 +78,12 @@ - - + @@ -73,16 +94,17 @@ - - + + + @@ -90,21 +112,90 @@ - - - - - + + + + - /l515_head/motion_module/global_time_enabled: true - /l515_head/l500_depth_sensor/global_time_enabled: true - /l515_head/rgb_camera/global_time_enabled: true + /l515_head/motion_module/global_time_enabled: true + /l515_head/l500_depth_sensor/global_time_enabled: true + /l515_head/rgb_camera/global_time_enabled: true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + step_x: 4 + step_y: 4 + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml index 43d79040b6..7b88454973 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml @@ -16,6 +16,15 @@ + + + + + warning_hz: 5 + + + + + + + + + + + + warning_hz: 5 + + - + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_tweet.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_tweet.launch index d8faf71fb8..198a504b64 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_tweet.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_tweet.launch @@ -1,11 +1,10 @@ - - + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml index b7eabb9a39..d34d1b345a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml @@ -1,10 +1,10 @@ move_base: recovery_behavior_enabled: true recovery_behaviors: - - name: "conservative_reset" - type: "clear_costmap_recovery/ClearCostmapRecovery" - - name: "rotate_recovery0" - type: "rotate_recovery/RotateRecovery" + - name: "complex_conservative_recovery" + type: "complex_recovery/SequentialComplexRecovery" + - name: "complex_rotate0" + type: "complex_recovery/SequentialComplexRecovery" - name: "speak_and_wait0" type: "speak_and_wait_recovery/SpeakAndWaitRecovery" - name: "aggressive_reset" @@ -19,16 +19,64 @@ move_base: type: "rotate_recovery/RotateRecovery" - name: "move_slow_and_clear" type: "move_slow_and_clear/MoveSlowAndClear" + complex_conservative_recovery: + recovery_behaviors: + - name: "update_inflation_layer_local0" + type: "update_move_base_parameter_recovery/UpdateInflationLayerParameterRecovery" + - name: "update_costmap_local0" + type: "update_move_base_parameter_recovery/UpdateCostmapParameterRecovery" + - name: "update_inflation_layer_global0" + type: "update_move_base_parameter_recovery/UpdateInflationLayerParameterRecovery" + - name: "update_costmap_global0" + type: "update_move_base_parameter_recovery/UpdateCostmapParameterRecovery" + - name: "conservative_reset" + type: "clear_costmap_recovery/ClearCostmapRecovery" + update_inflation_layer_local0: + parameter_name: "/move_base/local_costmap/inflater" + inflation_radius: 0.1 + duration_dealline: 15.0 + update_costmap_local0: + parameter_name: "/move_base/local_costmap" + footprint_padding: 0.1 + duration_dealline: 15.0 + update_inflation_layer_global0: + parameter_name: "/move_base/global_costmap/inflater" + inflation_radius: 0.1 + duration_dealline: 15.0 + update_costmap_global0: + parameter_name: "/move_base/global_costmap" + footprint_padding: 0.1 + duration_dealline: 15.0 + conservative_reset: + reset_distance: 3.0 + force_updating: true + complex_rotate0: + recovery_behaviors: + - name: "speak_and_wait" + type: "speak_and_wait_recovery/SpeakAndWaitRecovery" + - name: "rotate_recovery" + type: "rotate_recovery/RotateRecovery" + speak_and_wait: + speak_text: "リカバリのためにまわります。" + duration_wait: 0.0 + duration_timeout: 1.0 + sound_action: /robotsound_jp speak_and_wait0: - speak_text: "とおれません、みちをあけてください" + speak_text: "とおれません、ちょっとみちをあけてください" duration_wait: 5.0 duration_timeout: 1.0 sound_action: /robotsound_jp + aggressive_reset: + reset_distance: 1.0 + force_updating: true speak_and_wait1: speak_text: "とおれません、みちをあけてください" duration_wait: 5.0 duration_timeout: 1.0 sound_action: /robotsound_jp + all_reset: + reset_distance: 0.0 + force_updating: true move_slow_and_clear: planner_namespace: TrajectoryPlannerROS max_trans_param_name: max_vel_x diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml index 9da82ce6e2..0d3130cdcb 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml @@ -1,112 +1,4 @@ move_base: - controller_frequency: 20.0 - global_costmap: - inflater: - inflation_radius: 1.0 # 0.7 - cost_scaling_factor: 10.0 # 10.0 - obstacles: - min_obstacle_height: 0.05 - footprint_padding: 0.05 - publish_frequency: 1.0 - local_costmap: - inflater: - inflation_radius: 1.0 # 0.7 - cost_scaling_factor: 10.0 # 25.0 default 10, increasing factor decrease the cost value - obstacles: - min_obstacle_height: 0.05 - # default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide) - footprint_padding: 0.05 - update_frequency: 5.0 - base_global_planner: global_planner/GlobalPlanner - base_local_planner: teb_local_planner/TebLocalPlannerROS - # base_local_planner: base_local_planner/TrajectoryPlannerROS - GlobalPlanner: - allow_unknown: true - neural_cost: 50 - lethal_cost: 253 - cost_factor: 0.8 - default_tolerance: 0.0 - orientation_mode: 1 - visualize_potential: false - publish_potential: false - TrajectoryPlannerROS: - yaw_goal_tolerance: 0.1 - xy_goal_tolerance: 0.17 - max_vel_x: 0.5 - min_vel_x: 0.1 - min_in_place_vel_theta: 0.5 - escape_vel: 0.0 - sim_time: 1.5 - sim_granularity: 0.025 - angular_sim_granularity: 0.025 - vx_samples: 10 - vth_samples: 40 - meter_scoring: true - pdist_scale: 4.0 - gdist_scale: 2.5 - occdist_scale: 0.00625 - dwa: true - TebLocalPlannerROS: - odom_topic: /odom_combined - map_frame: /odom - # Trajectory - teb_autosize: True - dt_ref: 0.3 - dt_hysteresis: 0.1 - global_plan_overwrite_orientation: True - max_global_plan_lookahead_dist: 3.0 - feasibility_check_no_poses: 5 - # Robot - max_vel_x: 0.5 - max_vel_x_backwards: 0.3 - max_vel_theta: 1.0 - acc_lim_x: 1.0 - acc_lim_theta: 1.0 - min_turning_radius: 0.2 - footprint_model: - type: "circular" - radius: 0.3 - # GoalTolerance - xy_goal_tolerance: 0.2 - yaw_goal_tolerance: 0.1 - free_goal_vel: False - # Obstacles - min_obstacle_dist: 0.1 - include_costmap_obstacles: True - costmap_obstacles_behind_robot_dist: 1.0 - obstacle_poses_afected: 30 - costmap_converter_plugin: "" - costmap_converter_spin_thread: True - costmap_converter_rate: 5 - # Optimization - no_inner_iterations: 5 - no_outer_iterations: 4 - optimization_activate: True - optimization_verbose: False - penalty_epsilon: 0.1 - weight_max_vel_x: 2 - weight_max_vel_theta: 1 - weight_acc_lim_x: 1 - weight_acc_lim_theta: 1 - weight_kinematics_nh: 1000 - weight_kinematics_forward_drive: 1000 - weight_kinematics_turning_radius: 100 - weight_optimaltime: 1 - weight_obstacle: 50 - weight_dynamic_obstacle: 10 # not in use yet - alternative_time_cost: False # not in use yet - # Homotopy Class Planner - enable_homotopy_class_planning: True - enable_multithreading: True - simple_exploration: False - max_number_classes: 4 - roadmap_graph_no_samples: 15 - roadmap_graph_area_width: 5 - h_signature_prescaler: 0.5 - h_signature_threshold: 0.1 - obstacle_keypoint_offset: 0.1 - obstacle_heading_threshold: 0.45 - visualize_hc_graph: False recovery_behavior_enabled: true recovery_behaviors: - name: "conservative_reset" @@ -157,7 +49,7 @@ move_base: limited_trans_speed: 0.3 limited_rot_speed: 0.8 limited_distance: 0.3 - planner_namespace: TebLocalPlannerROS + planner_namespace: TrajectoryPlannerROS max_trans_param_name: max_vel_x max_rot_param_name: max_vel_theta max_planning_retries: 2 diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch index 1fdab69f5f..20abc5d53a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch @@ -12,6 +12,8 @@ + + @@ -104,8 +106,8 @@ + args="$(arg rosbag) $(arg loop_flag) --clock --start $(arg start_time) $(arg duration) -r $(arg rate)" output="screen" /> + args="-d $(arg rviz_config)" /> diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch index 43b5a923ce..12dd846fd3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch @@ -35,6 +35,9 @@ /head_camera/depth_registered/throttled/camera_info /head_camera/rgb/throttled/image_rect_color/compressed /head_camera/depth_registered/throttled/image_rect/compressedDepth + /server_name/smach/container_init + /server_name/smach/container_status + /server_name/smach/container_structure /audio $(arg other_topics) $(arg regex_flag) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch new file mode 100644 index 0000000000..76030da7cd --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -0,0 +1,176 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + use_indices: false + + + + + + + + + + + + + + + + + + + + + + + + + tolerance: 0.02 + min_size: 20 + vital_rate: 0.1 + + + + + + + + align_boxes: true + align_boxes_with_plane: false + target_frame_id: base_link + use_pca: true + force_to_flip_z_axis: false + vital_rate: 0.1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + trashbin_l: 0.3 + trashbin_w: 0.2 + trashbin_h: 0.49 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/view_model.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/view_model.launch new file mode 100644 index 0000000000..4f8ef6e3f9 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/view_model.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/package.xml b/jsk_fetch_robot/jsk_fetch_startup/package.xml index a89d0c4dea..f83da9e637 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/package.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/package.xml @@ -12,7 +12,9 @@ catkin fetch_teleop + dynamic_reconfigure + dynamic_reconfigure image_proc jsk_fetch_accessories jsk_fetch_diagnosis @@ -29,12 +31,15 @@ pr2_computer_monitor robot_pose_publisher rviz + switchbot_ros tf touchegg sound_play switchbot_ros tf2_ros voice_text + tf2 + tf2_geometry_msgs amcl @@ -48,6 +53,7 @@ librealsense2 realsense2_camera realsense2_description + update_move_base_parameter_recovery app_manager @@ -64,9 +70,16 @@ julius_ros respeaker_ros + + dialogflow_task_executive + google_chat_ros + robot_pose_publisher + + jsk_pcl_ros + rostest diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro new file mode 100644 index 0000000000..0e1002ac0e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro @@ -0,0 +1,72 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro index 8361f9dc20..24885a8324 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro @@ -22,16 +22,22 @@ - + + + + + + + - + - + diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/insta360_stand.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/insta360_stand.urdf.xacro new file mode 100644 index 0000000000..690742cfa6 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/insta360_stand.urdf.xacro @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro index 460086a8da..6cbb4f2840 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro @@ -1,10 +1,13 @@ + - + - + + + @@ -21,4 +24,13 @@ + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro new file mode 100644 index 0000000000..f373bc6110 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro @@ -0,0 +1,74 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/certbot_renewhook.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/certbot_renewhook.sh new file mode 100755 index 0000000000..d37fe27421 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/certbot_renewhook.sh @@ -0,0 +1,7 @@ +#!/bin/sh + +SITE=dialogflow.$(hostname).jsk.imi.i.u-tokyo.ac.jp + +cd /etc/letsencrypt/live/$SITE +cat fullchain.pem privkey.pem > /etc/haproxy/certs/$SITE.pem +systemctl restart haproxy diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/dstat.bash b/jsk_fetch_robot/jsk_fetch_startup/scripts/dstat.bash new file mode 100755 index 0000000000..440237145e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/dstat.bash @@ -0,0 +1,14 @@ +#!/usr/bin/env bash + +# Keep only the last 1000 lines of csv log before executing dstat +CSV_FILE=/home/fetch/Documents/jsk_dstat.csv + +if [ -e $CSV_FILE ]; then + cp -f $CSV_FILE $CSV_FILE.bk + tail -n 1000 $CSV_FILE.bk > $CSV_FILE + rm -f $CSV_FILE.bk +else + touch $CSV_FILE +fi + +dstat -tl --cpufreq -c -C all --top-cpu-adv -dgimnprsTy --output $CSV_FILE diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh new file mode 100755 index 0000000000..ec5d8f0b84 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh @@ -0,0 +1,63 @@ +#!/bin/bash + +function usage() { + echo "Usage: $0 " + exit 1 +} + +function start_jobs() { + sudo supervisorctl start roscore + sudo supervisorctl start robot + sudo supervisorctl start jsk-shutdown + sudo supervisorctl start jsk-rfcomm-bind + sudo supervisorctl start jsk-object-detector + sudo supervisorctl start jsk-network-monitor + sudo supervisorctl start jsk-log-wifi + sudo supervisorctl start jsk-human-pose-estimator + sudo supervisorctl start jsk-gdrive + sudo supervisorctl start jsk-fetch-startup + sudo supervisorctl start jsk-dstat + sudo supervisorctl start jsk-dialog + sudo supervisorctl start jsk-app-scheduler +} + +function restart_jobs() { + sudo supervisorctl restart roscore + sudo supervisorctl restart robot + sudo supervisorctl restart jsk-shutdown + sudo supervisorctl restart jsk-rfcomm-bind + sudo supervisorctl restart jsk-object-detector + sudo supervisorctl restart jsk-network-monitor + sudo supervisorctl restart jsk-log-wifi + sudo supervisorctl restart jsk-human-pose-estimator + sudo supervisorctl restart jsk-gdrive + sudo supervisorctl restart jsk-fetch-startup + sudo supervisorctl restart jsk-dstat + sudo supervisorctl restart jsk-dialog + sudo supervisorctl restart jsk-app-scheduler +} + +function stop_jobs() { + sudo supervisorctl stop roscore + sudo supervisorctl stop robot + sudo supervisorctl stop jsk-shutdown + sudo supervisorctl stop jsk-rfcomm-bind + sudo supervisorctl stop jsk-object-detector + sudo supervisorctl stop jsk-network-monitor + sudo supervisorctl stop jsk-log-wifi + sudo supervisorctl stop jsk-human-pose-estimator + sudo supervisorctl stop jsk-gdrive + sudo supervisorctl stop jsk-fetch-startup + sudo supervisorctl stop jsk-dstat + sudo supervisorctl stop jsk-dialog + sudo supervisorctl stop jsk-app-scheduler +} + +command=$1 + +case "$command" in + start) start_jobs;; + restart) restart_jobs;; + stop) stop_jobs;; + *) usage;; +esac diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh index 9de64ee353..3afeeb5c6d 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh @@ -1,25 +1,51 @@ #!/bin/bash IFACE=wlan0 -OUTPATH=/var/log/wifi.log INTERVAL=10 +PING_COUNT=3 +PING_TIMEOUT=1 +PING_TARGET="www.google.com" wifi_status(){ local ssid=$(iw $IFACE link | grep SSID | cut -d: -f2) local freq=$(iw $IFACE link | grep freq | cut -d':' -f2) - local signal=$(cat /proc/net/wireless | grep wlan0 | awk '{print $3}') - local level=$(cat /proc/net/wireless | grep wlan0 | awk '{print $4}') - local noise=$(cat /proc/net/wireless | grep wlan0 | awk '{print $5}') + local signal=$(cat /proc/net/wireless | grep $IFACE | awk '{print $3}') + local level=$(cat /proc/net/wireless | grep $IFACE | awk '{print $4}') + local noise=$(cat /proc/net/wireless | grep $IFACE | awk '{print $5}') local bitrate=$(iw $IFACE link | grep bitrate | cut -d':' -f2) - echo "$(date -Iseconds),$ssid,$freq,$signal,$level,$noise,$bitrate" + local ping_result_raw=$(ping -I $IFACE $PING_TARGET -c $PING_COUNT -W $PING_TIMEOUT 2> /dev/null | tail -n 1) + if [ -z "$ping_result_raw" ]; then + # minus ping indicates ping fails + local ping_result_duration=-1000 + else + local ping_result_duration=$(echo $ping_result_raw | cut -d " " -f 4 | cut -d "/" -f 2) + fi + echo "$(date -Iseconds),$ssid,$freq,$signal,$level,$noise,$bitrate, $ping_result_duration" } -OUTDIR=$(dirname $OUTPATH) -if [ ! -d $OUTDIR ]; then - mkdir -p $OUTDIR -fi +print_help(){ + echo "Usage: log-wifi-link.sh [-h]" + echo " [-i INTERVAL (default: 10)]" + echo " [-I IFACE (default: wlan0)]" + echo " [-c PING_COUNT (default: 3)]" + echo " [-W PING_TIMEOUT (default: 1)]" + echo " [-t PING_TARGET (default: \"www.google.com\")]" + exit 1 +} + +while getopts hi:I:c:W:t: o +do + case "$o" in + i) INTERVAL=$OPTARG;; + I) IFACE="$OPTARG";; + c) PING_COUNT=$OPTARG;; + W) PING_TIMEOUT=$OPTARG;; + t) PING_TARGET="$OPTARG";; + h) print_help;; + esac +done while true; do - wifi_status >> $OUTPATH + wifi_status sleep $INTERVAL done diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/network_monitor.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/network_monitor.py index 1f67266a30..782f5479a5 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/network_monitor.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/network_monitor.py @@ -47,21 +47,21 @@ TOUCH_FILE = "/home/fetch/.Network_Monitor_Restarted_Robot" -def ping(use_arping, hosts): +def ping(use_arping, hosts, network_interface='wlan0'): for host in hosts: for _ in xrange(5): print(datetime.now(),"Sending ping request") if use_arping: - response = os.system("arping -I wlan0 -c 1 " + host) + response = os.system("arping -I {} -c 1 {}".format(network_interface, host)) else: - response = os.system("ping -c 1 -q " + host) + response = os.system("ping -c 1 -q {}".format(host)) if response == 0: return True sleep(5) return False -def get_sanshiro(): - return [['sanshiro', 'sanshiro']] +def get_sanshiro(network_profile_id): + return [[network_profile_id, 'sanshiro']] def get_saved_networks(filepaths=None): # NetworkManager has its own ID for networks, often multiple for the same @@ -90,19 +90,19 @@ def get_saved_networks(filepaths=None): # for reconnecting to 'sanshiro' -def reconnect_to_wlan(): - if call(["nmcli", "d", "disconnect", "iface", "wlan0"]) == 0: +def reconnect_to_wlan(network_interface='wlan0', network_profile_id='sanshiro'): + if call(["nmcli", "d", "disconnect", "iface", network_interface]) == 0: sleep(0.3) - print("disconnect from wlan0") + print("Network disconnected with interface \"{}\"".format(network_interface)) else: - print("'nmcli d disconnect iface wlan0' do not work correctly!") + print("'nmcli d disconnect iface {}' do not work correctly!".format(network_interface)) - if call(["nmcli", "c", "up", "id", "sanshiro"]) == 0: + if call(["nmcli", "c", "up", "id", network_profile_id]) == 0: sleep(0.3) - print("connect to sanshiro") + print("Network connected with profile \"{}\"".format(network_profile_id)) return True else: - print("'nmcli c up id sanshiro' do not work correctly!") + print("'nmcli c up id {}' do not work correctly!".format(network_profile_id)) return False @@ -150,13 +150,13 @@ def connect_by_nmcli_id(nid, ssid="SSID not given"): return False -def attempt_reconnect_to_network(): +def attempt_reconnect_to_network(network_interface, network_profile_id): # First, try to connect to sanshiro - if connect_by_nmcli_id('sanshiro', 'sanshiro'): + if connect_by_nmcli_id(network_profile_id, 'sanshiro'): return True # Get list of stored 'wireless' connections; [id, ssid] - known = get_saved_networks() # alternative : known = get_sanshiro() + known = get_saved_networks() # alternative : known = get_sanshiro(network_profile_id) # Get list of unique available wifi network ssids and their strongest signal avail = get_avail_networks_by_strength() @@ -170,7 +170,7 @@ def attempt_reconnect_to_network(): for ntwk in to_try: if connect_by_nmcli_id(*ntwk): return True - if reconnect_to_wlan(): + if reconnect_to_wlan(network_interface, network_profile_id): return True return False @@ -249,12 +249,12 @@ def main(args): while True: try: # Check if we can ping the access point - if not ping(args.arping, hostnames): + if not ping(args.arping, hostnames, args.interface): print(datetime.now(), "Cannot connect to", ', '.join(hostnames)) sound_goal.goal.sound_request.arg = "ピングが通りません" pub.publish(sound_goal) # Try to connect to any known network - if not attempt_reconnect_to_network(): + if not attempt_reconnect_to_network(args.interface, args.profile): # TODO use check_output instead of Popen and handle truly # bad issues with computer restarts or notification. print(datetime.now(), "Restarting network-manager") @@ -302,6 +302,10 @@ def main(args): help="One or more comma delimited hostname(s) to ping. Hostnames will " "be tried in order supplied until one is successfully contacted. Default: " "Looks for NETWORK_MONITOR_HOSTNAMES in environment.") + parser.add_argument('-I', '--interface', default='wlan0', + help='Network interface to be used.') + parser.add_argument('--profile', default='sanshiro', + help='Network profile to be used.') parser.add_argument("-a", "--arping", action='store_true', help="Use arping instead of ping.") parser.add_argument("--enable-reboot-option", action='store_true', diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh new file mode 100755 index 0000000000..10f059f0b4 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh @@ -0,0 +1,40 @@ +#!/usr/bin/env bash + +# Check storage percentage +STORAGE_PERCENTAGE=`df -h / | awk 'NR==2 {print $5}' | sed -e 's/\%//g'` + +# If storage_percentage greater than 80% +if [ $STORAGE_PERCENTAGE -gt 80 ]; then + SEND_EMAIL=1 + # In root directory + ROOTDIR_STORAGE=`du -h -d 0 /* 2>/dev/null | sort -hr | awk '{print $2 " " $1}'` + # In home directory + HOMEDIR_STORAGE=`du -h -d 0 /home/* 2>/dev/null | sort -hr | awk '{print $2 " " $1}'` +else + echo -e "No problem with the storace capacity. Storage percentage: $STORAGE_PERCENTAGE" +fi + +if [ -n "$SEND_EMAIL" ]; then + rostopic pub -1 /email jsk_robot_startup/Email "header: + seq: 0 + stamp: {secs: 0, nsecs: 0} + frame_id: '' +subject: 'Storage warning' +body: 'Storage usage is ${STORAGE_PERCENTAGE}%. Please remove unnecessary files. + + +In root directory: + +${ROOTDIR_STORAGE} + + +In home directory: + +${HOMEDIR_STORAGE}' +sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' +receiver_address: 'fetch@jsk.imi.i.u-tokyo.ac.jp' +smtp_server: '' +smtp_port: '' +attached_files: []" + echo -e "Storage percentage: $STORAGE_PERCENTAGE\n Root directory: $ROOTDIR_STORAGE\n Home directory: $HOMEDIR_STORAGE\n" +fi diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py index ca5781dc44..083e12c658 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py @@ -8,19 +8,25 @@ import sys import urllib2 +from dynamic_reconfigure.server import Server +from jsk_fetch_startup.cfg import TimeSignalConfig as Config from sound_play.msg import SoundRequestAction from sound_play.msg import SoundRequestGoal class TimeSignal(object): - def __init__(self): + def __init__(self, volume=1.0): self.client_en = actionlib.SimpleActionClient( '/sound_play', SoundRequestAction) self.client_jp = actionlib.SimpleActionClient( '/robotsound_jp', SoundRequestAction) self.now_time = datetime.now() + self.now_date = self.now_time.date() self.now_hour = self.now_time.hour + self.now_minute = self.now_time.minute self.day = self.now_time.strftime('%a') + self.volume = volume + self.srv = Server(Config, self.config_callback) reload(sys) sys.setdefaultencoding('utf-8') api_key_file = rospy.get_param( @@ -33,7 +39,7 @@ def speak(self, client, speech_text, lang=None): sound_goal = SoundRequestGoal() sound_goal.sound_request.sound = -3 sound_goal.sound_request.command = 1 - sound_goal.sound_request.volume = 1.0 + sound_goal.sound_request.volume = self.volume if lang is not None: sound_goal.sound_request.arg2 = lang sound_goal.sound_request.arg = speech_text @@ -43,7 +49,9 @@ def speak(self, client, speech_text, lang=None): def speak_jp(self): # time signal - speech_text = str(self.now_hour) + 'じです。' + speech_text = self._get_time_text( + self.now_date, self.now_hour, self.now_minute, + lang='ja') if self.now_hour == 0: speech_text += '早く帰りましょう。' if self.now_hour == 12: @@ -56,10 +64,8 @@ def speak_jp(self): speech_text += 'そろそろ輪講です。' if self.day == 'Tue' and self.now_hour == 15: speech_text += '掃除の時間です。' - if self.day == 'Fri' and self.now_hour == 14: + if self.day == 'Fri' and self.now_hour == 15: speech_text += '創造輪講の時間です。' - if self.day == 'Fri' and self.now_hour == 16: - speech_text += '掃除の時間です。' # weather forecast if self.now_hour in [0, 7, 12, 19]: @@ -72,7 +78,9 @@ def speak_jp(self): self.speak(self.client_jp, speech_text, lang='jp') def speak_en(self): - speech_text = self._get_text(self.now_hour) + speech_text = self._get_time_text( + self.now_date, self.now_hour, self.now_minute, + lang='en') # time signal if self.now_hour == 0: speech_text += " Let's go home." @@ -80,6 +88,14 @@ def speak_en(self): speech_text += " Let's go to lunch." if self.now_hour == 19: speech_text += " Let's go to dinner." + if self.day == 'Mon' and self.now_hour == 12: + speech_text += ' The lab meeting will start soon.' + if self.day == 'Tue' and self.now_hour == 12: + speech_text += ' The lab meeting will start soon.' + if self.day == 'Tue' and self.now_hour == 15: + speech_text += ' It is cleaning time now.' + if self.day == 'Fri' and self.now_hour == 15: + speech_text += ' Rinko will start soon. ' # weather forecast if self.now_hour in [0, 7, 12, 19]: @@ -91,18 +107,33 @@ def speak_en(self): rospy.logdebug(speech_text) self.speak(self.client_en, speech_text) - def _get_text(self, hour): - if hour == 0: - text = 'midnight' - elif hour == 12: - text = 'noon' + def _get_time_text(self, date, hour, minute, lang='en'): + if lang == 'ja': + if hour == 0 and minute == 0: + time_text = '{}年{}月{}日'.format( + date.year, date.month, date.day) + elif hour == 12 and minute == 0: + time_text = '正午' + else: + time_text = '{}時'.format(hour) + if minute != 0: + time_text += '{}分'.format(minute) + time_text += 'です。' else: - if hour > 12: - text = str(hour % 12) + ' P.M.' + if hour == 0 and minute == 0: + time_text = date.strftime('%Y %B %d') + elif hour == 12 and minute == 0: + time_text = 'noon' else: - text = str(hour % 12) + ' A.M.' - text = "It's " + text + "." - return text + time_text = str(hour % 12) + if minute != 0: + time_text += ' {}'.format(minute) + if hour > 12: + time_text += ' P.M.' + else: + time_text += ' A.M.' + time_text = "It's {}.".format(time_text) + return time_text def _get_weather_forecast(self, lang='en'): url = 'http://api.openweathermap.org/data/2.5/weather?q=tokyo&lang={}&units=metric&appid={}'.format(lang, self.appid) # NOQA @@ -126,6 +157,20 @@ def _get_weather_forecast(self, lang='en'): forecast_text += " The wind speed is {} meter per second.".format(wind_speed) return forecast_text + def _set_volume(self, volume): + ''' + Set speak volume between 0.0 and 1.0 + ''' + volume = min(max(0.0, volume), 1.0) + if self.volume != volume: + self.volume = volume + rospy.loginfo("time_signal's volume was set to {}".format( + self.volume)) + + def config_callback(self, config, level): + self._set_volume(config.volume) + return config + if __name__ == '__main__': rospy.init_node('time_signal') diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index f27e401366..6fd0ba00d2 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -1,43 +1,9 @@ #!/usr/bin/env bash -. $HOME/ros/melodic/devel/setup.bash -# Filename should end with .txt to preview the contents in a web browser -LOGFILE=$HOME/ros/melodic/update_workspace.txt - -{ -set -x -# Update workspace -cd $HOME/ros/melodic/src -ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $HOME/ros/melodic/src/.rosinstall -wstool foreach --git 'git stash' -wstool update --delete-changed-uris -WSTOOL_UPDATE_RESULT=$? -cd $HOME/ros/melodic -catkin clean aques_talk collada_urdf_jsk_patch -y -catkin init -catkin config -DCMAKE_BUILD_TYPE=Release -catkin build -CATKIN_BUILD_RESULT=$? -# Send mail -MAIL_BODY="" -if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then - MAIL_BODY=$MAIL_BODY"Please wstool update workspace manually. " -fi -if [ $CATKIN_BUILD_RESULT -ne 0 ]; then - MAIL_BODY=$MAIL_BODY"Please catkin build workspace manually." -fi -set +x -} > $LOGFILE 2>&1 -if [ -n "$MAIL_BODY" ]; then - rostopic pub -1 /email jsk_robot_startup/Email "header: - seq: 0 - stamp: {secs: 0, nsecs: 0} - frame_id: '' -subject: 'Daily workspace update fails' -body: '$MAIL_BODY' -sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' -receiver_address: 'fetch@jsk.imi.i.u-tokyo.ac.jp' -smtp_server: '' -smtp_port: '' -attached_files: ['$LOGFILE']" -fi +cp $(rospack find jsk_robot_startup)/scripts/update_workspace_main.sh /tmp/update_workspace.sh +# jsk_footstep_planner is not released for melodic +# jsk_footstep_controller is not released for melodic +# librealsense2 should not be installed from ROS repository +# realsense-ros should not be installed from ROS repository +/tmp/update_workspace.sh -r $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO -t fetch -s "jsk_footstep_controller jsk_footstep_planner librealsense2 realsense2_camera realsense2_description" +rm /tmp/update_workspace.sh diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/warning.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/warning.py index decf7e9d1d..029e8b281c 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/warning.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/warning.py @@ -9,7 +9,6 @@ from sound_play.libsoundplay import SoundClient from actionlib_msgs.msg import GoalStatus, GoalStatusArray -from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus from fetch_driver_msgs.msg import RobotState from geometry_msgs.msg import Twist from power_msgs.msg import BatteryState, BreakerState @@ -36,40 +35,6 @@ def terminate_thread(thread): ctypes.pythonapi.PyThreadState_SetAsyncExc(thread.ident, None) raise SystemError("PyThreadState_SetAsyncExc failed") -class DiagnosticsSpeakThread(threading.Thread): - def __init__(self, error_status): - threading.Thread.__init__(self) - self.volume = rospy.get_param("~volume", 1.0) - self.error_status = error_status - self.start() - - def run(self): - global sound - for status in self.error_status: - # ignore error status if the error already occured in the latest 10 minites - if status.message in error_status_in_10_min: - if rospy.Time.now().secs - error_status_in_10_min[status.message] < 600: - continue - else: - error_status_in_10_min[status.message] = rospy.Time.now().secs - else: - error_status_in_10_min[status.message] = rospy.Time.now().secs - # we can ignore "Joystick not open." - if status.message == "Joystick not open." : - continue - if status.name == "supply_breaker" and status.message == "Disabled." : - continue - # - text = "Error on {}, {}".format(status.name, status.message) - rospy.loginfo(text) - text = text.replace('_', ', ') - sound.say(text, 'voice_kal_diphone', volume=self.volume) - time.sleep(5) - - def stop(self): - terminate_thread(self) - self.join() - class Warning: def __init__(self): time.sleep(1) @@ -77,22 +42,13 @@ def __init__(self): self.battery_state_msgs = BatteryState() self.twist_msgs = Twist() # - self.diagnostics_speak_thread = {} self.auto_undocking = False - self.diagnostics_list = [] - if rospy.get_param("~speak_warn", True): - self.diagnostics_list.append(DiagnosticStatus.WARN) - if rospy.get_param("~speak_error", True): - self.diagnostics_list.append(DiagnosticStatus.ERROR) - if rospy.get_param("~speak_stale", True): - self.diagnostics_list.append(DiagnosticStatus.STALE) # self.base_breaker = rospy.ServiceProxy('base_breaker', BreakerCommand) # self.battery_sub = rospy.Subscriber("battery_state", BatteryState, self.battery_callback, queue_size = 1) self.cmd_vel_sub = rospy.Subscriber("base_controller/command_unchecked", Twist, self.cmd_vel_callback, queue_size = 1) self.robot_state_sub = rospy.Subscriber("robot_state", RobotState, self.robot_state_callback, queue_size = 1) - self.diagnostics_status_sub = rospy.Subscriber("diagnostics", DiagnosticArray, self.diagnostics_status_callback, queue_size = 1) self.undock_sub = rospy.Subscriber("/undock/status", GoalStatusArray, self.undock_status_callback) # self.cmd_vel_pub = rospy.Publisher("base_controller/command", Twist, queue_size=1) @@ -140,29 +96,6 @@ def cmd_vel_callback(self, msg): ## self.twist_msgs = msg - def diagnostics_status_callback(self, msg): - ## - self.diagnostic_status_msgs = msg.status - ## - ## check if this comes from /robot_driver - callerid = msg._connection_header['callerid'] - if callerid not in self.diagnostics_speak_thread: - self.diagnostics_speak_thread[callerid] = None - error_status = filter(lambda n: n.level in self.diagnostics_list, msg.status) - # when RunStopped, ignore message from *_mcb and *_breaker - if self.robot_state_msgs.runstopped: - error_status = filter(lambda n: not (re.match("\w*_(mcb|breaker)",n.name) or (n.name == "Mainboard" and n.message == "Runstop pressed")), error_status) - if not error_status : # error_status is not [] - if self.diagnostics_speak_thread[callerid] and self.diagnostics_speak_thread[callerid].is_alive(): - self.diagnostics_speak_thread[callerid].stop() - return - # make sure that diagnostics_speak_thread is None, when the thread is terminated - if self.diagnostics_speak_thread[callerid] and not self.diagnostics_speak_thread[callerid].is_alive(): - self.diagnostics_speak_thread[callerid] = None - # run new thread - if self.diagnostics_speak_thread[callerid] is None: - self.diagnostics_speak_thread[callerid] = DiagnosticsSpeakThread(error_status) - if __name__ == "__main__": global sound # store error status and time of the error in the latest 10 minites diff --git a/jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp b/jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp new file mode 100644 index 0000000000..0adecd9ffb --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp @@ -0,0 +1,82 @@ +#include + +#include +#include +#include +#include +#include +#include +#include + +class TrashbinsPoseEstimator{ +private: + double _trashbinL, _trashbinW, _trashbinH; // trashbin size param + ros::Subscriber _trashbinHandleSub; + ros::Subscriber _pointCloud; + ros::Publisher _virtualTrashbinContainerPub; + jsk_recognition_msgs::BoundingBoxArray _trashbins; // trashbin object + geometry_msgs::Quaternion defaultOrientation; + +public: + // constructor + TrashbinsPoseEstimator(ros::NodeHandle &_nh, ros::NodeHandle &_pnh){ + _pnh.getParam("trashbin_l", this->_trashbinL); + _pnh.getParam("trashbin_w", this->_trashbinW); + _pnh.getParam("trashbin_h", this->_trashbinH); + this->_trashbinHandleSub = _nh.subscribe("input", 10, &TrashbinsPoseEstimator::DrawVirtualTrashbinContainerCB, this); + this->_virtualTrashbinContainerPub = _nh.advertise("output", 10); + // init default orientation const + this->defaultOrientation.w = 1.0; + this->defaultOrientation.x = 0.0; + this->defaultOrientation.y = 0.0; + this->defaultOrientation.z = 0.0; + }; + // destructor + ~TrashbinsPoseEstimator(){ + ROS_INFO("Killing node..."); + }; + + // draw virtual trashbin container and publish for debugging + void DrawVirtualTrashbinContainerCB(const jsk_recognition_msgs::BoundingBoxArray& msg){ + boost::shared_ptr handles(new jsk_recognition_msgs::BoundingBoxArray), trashbins(new jsk_recognition_msgs::BoundingBoxArray); + boost::shared_ptr handle(new jsk_recognition_msgs::BoundingBox), trashbin(new jsk_recognition_msgs::BoundingBox); + boost::shared_ptr handleCenterPosition(new geometry_msgs::Point), trashbinCenterPosition(new geometry_msgs::Point); + + if (msg.boxes.empty()) { + ROS_DEBUG("No handle candidates"); + } else { + ROS_DEBUG_STREAM(msg.boxes.size() << " handle candidates" << std::endl); + *handles = msg; + for (int i = 0; i < handles->boxes.size(); i++) { + *handle = handles->boxes.at(i); + // decide trashbin center position + *handleCenterPosition = handle->pose.position; + trashbinCenterPosition->x = + handleCenterPosition->x + this->_trashbinL / 2.0; + trashbinCenterPosition->y = handleCenterPosition->y; + trashbinCenterPosition->z = + handleCenterPosition->z - this->_trashbinH / 2.0; + // make BoundingBox trashbin + trashbin->header = handle->header; + trashbin->pose.position = *trashbinCenterPosition; + trashbin->pose.orientation = this->defaultOrientation; + trashbin->dimensions.x = this->_trashbinL; + trashbin->dimensions.y = this->_trashbinW; + trashbin->dimensions.z = this->_trashbinH; + trashbin->label = i; + trashbins->boxes.push_back(*trashbin); + } + trashbins->header = handles->header; + this->_virtualTrashbinContainerPub.publish(*trashbins); + this->_trashbins = *trashbins; + } + } +}; + +int main(int argc, char **argv){ + ros::init(argc, argv, "trashbin_pose_estimator"); + ros::NodeHandle nh; + ros::NodeHandle pnh("~"); + TrashbinsPoseEstimator node = TrashbinsPoseEstimator(nh, pnh); + ros::spin(); +} diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf index 57944374f6..23dcfcb3be 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf @@ -1,8 +1,9 @@ [program:jsk-app-scheduler] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-app-scheduler.log stderr_logfile=/var/log/ros/jsk-app-scheduler.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-coral.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-coral.conf deleted file mode 100644 index d7cf1778cf..0000000000 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-coral.conf +++ /dev/null @@ -1,11 +0,0 @@ -[program:jsk-coral] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt --screen --wait" -stopsignal=TERM -directory=/home/fetch/ros/coral_ws -autostart=true -autorestart=false -stdout_logfile=/var/log/ros/jsk-coral.log -stderr_logfile=/var/log/ros/jsk-coral.log -user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 -priority=200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index 581d4d8f87..50db8b9ed5 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -1,11 +1,12 @@ [program:jsk-dialog] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch dialogflow_task_executive dialogflow_task_executive.launch run_app_manager:=false --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " stopsignal=TERM directory=/home/fetch/ros/melodic -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-dialog.log stderr_logfile=/var/log/ros/jsk-dialog.log user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",GOOGLE_APPLICATION_CREDENTIALS=/var/lib/robot/dialogflow/JSK-Fetch-a384d3498680.json,DIALOGFLOW_PROJECT_ID=fetch-kiedno,PYTHONUNBUFFERED=1 +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",GOOGLE_APPLICATION_CREDENTIALS=/var/lib/robot/dialogflow/fetch-credential.json,DIALOGFLOW_PROJECT_ID=fetch-kiedno,PYTHONUNBUFFERED=1 priority=200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf new file mode 100644 index 0000000000..4fcf56a3e3 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf @@ -0,0 +1,11 @@ +; Install dstat +; sudo apt install dstat +[program:jsk-dstat] +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup dstat.bash" +stopsignal=TERM +autostart=true +autorestart=false +stdout_logfile=/var/log/ros/jsk-dstat.log +stderr_logfile=/var/log/ros/jsk-dstat.log +user=root +priority=1 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf new file mode 100644 index 0000000000..463ddf138e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf @@ -0,0 +1,11 @@ +[program:jsk-fetch-startup-outside] +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" +stopsignal=TERM +directory=/home/fetch/ros/melodic +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-fetch-startup.log +stderr_logfile=/var/log/ros/jsk-fetch-startup.log +user=fetch +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",AUDIO_DEVICE="alsa_output.usb-1130_USB_AUDIO-00.analog-stereo",PYTHONUNBUFFERED=1 +priority=100 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 5292717154..5efe6fb1be 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true use_voice_text:=false --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true @@ -7,5 +7,5 @@ autorestart=false stdout_logfile=/var/log/ros/jsk-fetch-startup.log stderr_logfile=/var/log/ros/jsk-fetch-startup.log user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",AUDIO_DEVICE="alsa_output.usb-1130_USB_AUDIO-00.analog-stereo",PYTHONUNBUFFERED=1 +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 priority=100 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf index a79cc1deb3..dd8e281cda 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf @@ -1,8 +1,9 @@ [program:jsk-gdrive] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch gdrive_ros gdrive_server.launch --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" stopsignal=TERM directory=/home/fetch/ros/melodic -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-gdrive.log stderr_logfile=/var/log/ros/jsk-gdrive.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf index cdb54b8638..a9723545b8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf @@ -1,5 +1,5 @@ [program:jsk-log-wifi] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup log-wifi-link.sh" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rosrun jsk_fetch_startup log-wifi-link.sh -I $NETWORK_DEFAULT_WIFI_INTERFACE" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf new file mode 100644 index 0000000000..2dbd597ae2 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf @@ -0,0 +1,10 @@ +[program:jsk-network-monitor-outside] +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" +stopsignal=TERM +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-network-monitor.log +stderr_logfile=/var/log/ros/jsk-network-monitor.log +user=root +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",NETWORK_MONITOR_HOSTNAMES="google.com",PYTHONUNBUFFERED=1 +priority=200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf index bf05c87a6b..30e1578f91 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf @@ -1,5 +1,5 @@ [program:jsk-network-monitor] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup network_monitor.py" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf index 16f10c4710..b80954f2ab 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf @@ -1,5 +1,5 @@ [program:jsk-rfcomm-bind] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch jsk_robot_startup rfcomm_bind.launch --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch jsk_robot_startup rfcomm_bind.launch --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf index bdc0bd78eb..37feca3d06 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf @@ -1,5 +1,5 @@ [program:jsk-shutdown] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_robot_startup shutdown.py --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_robot_startup shutdown.py ~input:=/battery_state _input_condition:='m.is_charging is False' --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-73b2.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-73b2.conf new file mode 100644 index 0000000000..52656f1761 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-73b2.conf @@ -0,0 +1,8 @@ +[program:jsk-switch-wifi-73b2] +command=nmcli c up sanshiro-73B2 +stopsignal=TERM +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-switch-wifi.log +stderr_logfile=/var/log/ros/jsk-switch-wifi.log +user=root diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-outside.conf new file mode 100644 index 0000000000..d892d5be10 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-outside.conf @@ -0,0 +1,8 @@ +[program:jsk-switch-wifi-outside] +command=nmcli c up sanshiro-outside +stopsignal=TERM +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-switch-wifi.log +stderr_logfile=/var/log/ros/jsk-switch-wifi.log +user=root diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf new file mode 100644 index 0000000000..90f32f5811 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf @@ -0,0 +1,11 @@ +[program:robot-outside] +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" +stopsignal=TERM +directory=/home/fetch/ros/melodic +autostart=false +autorestart=unexpected +stdout_logfile=/var/log/ros/robot.log +stderr_logfile=/var/log/ros/robot.log +user=ros +environment=ROS_LOG_DIR=/var/log/ros,ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",FETCH_CALIBRATED_URDF=/etc/ros/melodic/calibrated_2020_12_04_02_08_34.urdf,FETCH_CALIBRATED_RGB=/etc/ros/melodic/rgb_2020_12_04_02_08_34.yaml,FETCH_CALIBRATED_DEPTH=/etc/ros/melodic/depth_2020_12_04_02_08_34.yaml,PYTHONUNBUFFERED=1 +priority=10 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf index 0862a3af71..0b33af1409 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf @@ -1,5 +1,5 @@ [program:robot] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml index 5f2e1d51bf..85062f575d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml +++ b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml @@ -36,9 +36,14 @@ windows: - jsk-fetch-startup: tail -f -n 1000 /var/log/ros/jsk-fetch-startup.log - jsk-network-monitor: tail -f -n 1000 /var/log/ros/jsk-network-monitor.log - jsk-log-wifi: tail -f -n 1000 /var/log/ros/jsk-log-wifi.log - - jsk-app-scheduler: tail -f -n 1000 /var/log/ros/jsk-app-scheduler.log - - jsk-coral: tail -f -n 1000 /var/log/ros/jsk-coral.log - - jsk-dialog: tail -f -n 1000 /var/log/ros/jsk-dialog.log - - jsk-gdrive: tail -f -n 1000 /var/log/ros/jsk-gdrive.log - - jsk-shutdown: tail -f -n 1000 /var/log/ros/jsk-shutdown.log - - jsk-rfcomm-bind: tail -f -n 1000 /var/log/ros/jsk-rfcomm-bind.log + - jsk-dstat: tail -f -n 1000 /var/log/ros/jsk-dstat.log + # - jsk-app-scheduler: tail -f -n 1000 /var/log/ros/jsk-app-scheduler.log + # - jsk-coral: tail -f -n 1000 /var/log/ros/jsk-coral.log + # - jsk-object-detector: tail -f -n 1000 /var/log/ros/jsk-object-detector.log + # - jsk-panorama-object-detector: tail -f -n 1000 /var/log/ros/jsk-panorama-object-detector.log + # - jsk-human-pose-estimator: tail -f -n 1000 /var/log/ros/jsk-human-pose-estimator.log + # - jsk-panorama-human-pose-estimator: tail -f -n 1000 /var/log/ros/jsk-panorama-human-pose-estimator.log + # - jsk-dialog: tail -f -n 1000 /var/log/ros/jsk-dialog.log + # - jsk-gdrive: tail -f -n 1000 /var/log/ros/jsk-gdrive.log + # - jsk-shutdown: tail -f -n 1000 /var/log/ros/jsk-shutdown.log + # - jsk-rfcomm-bind: tail -f -n 1000 /var/log/ros/jsk-rfcomm-bind.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules index 4606864732..f80fad6045 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules +++ b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules @@ -1,3 +1,10 @@ # You can access arduino attached to fetch via /dev/arduino # https://github.com/start-jsk/jsk_apc/blob/16c004c511e864478aa6581a04c5a023e5fde391/jsk_arc2017_baxter/udev/90-rosserial.rules SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001", SYMLINK+="arduino", MODE="0666" + +# The following device is for arduino nano every in nakane hand version 1 +# Please update idVendor and idProduct if you use a different microcontroller +SUBSYSTEM=="tty", ATTRS{idVendor}=="2341", ATTRS{idProduct}=="0058", SYMLINK+="nakane_hand", MODE="0666" + +# The following device is for M5Atom S3 for smart device protocol interface by k-shinjo 2024/1/9 +SUBSYSTEM=="tty", ATTRS{idVendor}=="303A", ATTRS{idProduct}=="1001", SYMLINK+="smart_device_protocol_interface", MODE="0666" diff --git a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/99-jsk-ps3joy.rules b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/99-jsk-ps3joy.rules index 113b5af453..05f7eb15b3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/99-jsk-ps3joy.rules +++ b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/99-jsk-ps3joy.rules @@ -3,3 +3,4 @@ # https://github.com/fetchrobotics/fetch_robots/blob/8e144f9a193129a0de5254075bbe5eb8245e1603/fetch_system_config/root/lib/udev/rules.d/99-ps3joy.rules # Current 99-ps3joy.rules in fetchrobotics/fetch_robots is for PS4 controller, but we still use PS3 controller. KERNEL=="js?", SUBSYSTEM=="input", ATTRS{name}=="Sony PLAYSTATION(R)3 Controller", SYMLINK+="ps3joy" +KERNEL=="js?", SUBSYSTEM=="input", ATTRS{name}=="PLAYSTATION(R)3 Controller", SYMLINK+="ps3joy" diff --git a/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh b/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh new file mode 100755 index 0000000000..3dbf85dd09 --- /dev/null +++ b/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh @@ -0,0 +1,5 @@ +#!/usr/bin/env bash + +cp $(rospack find jsk_robot_startup)/scripts/update_workspace_main.sh /tmp/update_workspace.sh +/tmp/update_workspace.sh -w $HOME/ros/indigo -r $(rospack find jsk_pr2_startup)/jsk_pr2.rosinstall -t pr2 -u +rm /tmp/update_workspace.sh diff --git a/jsk_robot_common/complex_recovery/CMakeLists.txt b/jsk_robot_common/complex_recovery/CMakeLists.txt new file mode 100644 index 0000000000..7dd42684f9 --- /dev/null +++ b/jsk_robot_common/complex_recovery/CMakeLists.txt @@ -0,0 +1,89 @@ +cmake_minimum_required(VERSION 2.8.3) +project(complex_recovery) + +add_compile_options(-std=c++11) + +find_package(catkin REQUIRED + COMPONENTS + costmap_2d + nav_core + pluginlib + roscpp + tf2 + tf2_ros +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES complex_recovery + CATKIN_DEPENDS + costmap_2d + nav_core + pluginlib + roscpp + tf2 + tf2_ros +) + +# Abort if indigo or kinetic +if ( $ENV{ROS_DISTRO} STREQUAL "indigo" OR $ENV{ROS_DISTRO} STREQUAL "kinetic" ) + return() +endif() + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_library(complex_recovery + src/sequential_complex_recovery.cpp + src/parallel_complex_recovery.cpp + src/utils.cpp +) +add_dependencies(complex_recovery + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(complex_recovery + ${catkin_LIBRARIES} +) + +install(TARGETS complex_recovery + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) + +install(FILES complex_recovery_plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +# +# Testing +# +if (CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + + catkin_add_executable_with_gtest(sequential_complex_recovery_test_node + tests/sequential_complex_recovery_test_node.cpp + ) + target_link_libraries(sequential_complex_recovery_test_node + ${catkin_LIBRARIES} + ${PROJECT_NAME} + ) + add_rostest(tests/sequential_complex_recovery.test) + + catkin_add_executable_with_gtest(parallel_complex_recovery_test_node + tests/parallel_complex_recovery_test_node.cpp + ) + target_link_libraries(parallel_complex_recovery_test_node + ${catkin_LIBRARIES} + ${PROJECT_NAME} + ) + add_rostest(tests/parallel_complex_recovery.test) +endif() diff --git a/jsk_robot_common/complex_recovery/README.md b/jsk_robot_common/complex_recovery/README.md new file mode 100644 index 0000000000..fc65f10920 --- /dev/null +++ b/jsk_robot_common/complex_recovery/README.md @@ -0,0 +1,67 @@ +# complex_recovery + +This package provides recovery behavior plugins which combines multi recoveries to one recovery behavior. +This is useful for assuring a set of recovery behavior to run at one time. + +There are two types of recoveries. One is to run multi recoveries sequentially and another is to run them in parallel. + +![complex_recovery_diagrams](https://user-images.githubusercontent.com/9410362/189815175-a3265d23-01d4-4ae9-831c-b01aacad2872.png) + +## complex_recovery/SequentialComplexRecovery + +* `~recovery_behaviors` (list of dictionaries which has `name` and `type` entries, default: None) + +Example configuration of `move_base` is like + +```yaml +recovery_behavior_enabled: true +recovery_behaviors: + - name: "speak_then_clear_costmap0" + type: "complex_recovery/SequentialComplexRecovery" +speak_then_clear_costmap0: + recovery_behaviors: + - name: "speak_and_wait0" + type: "speak_and_wait_recovery/SpeakAndWaitRecovery" + - name: "clear_costmap0" + type: "clear_costmap_recovery/ClearCostmapRecovery" + speak_and_wait0: + speak_text: "I'm clearing costmap." + duration_wait: 5.0 + duration_timeout: 1.0 + sound_action: /sound_play + clear_costmap0: + reset_distance: 1.0 +``` + +In this case, `speak_and_clear_costmap0` recovery runs `speak_and_wait0` recovery first, then runs `clear_costmap0`. +So a robot speaks first and then clear its costmap. + +## complex_recovery/ParallelComplexRecovery + +* `~recovery_behaviors` (list of dictionaries which has `name` and `type` entries, default: None) + +Example configuration of `move_base` is like + +```yaml +recovery_behavior_enabled: true +recovery_behaviors: + - name: "speak_and_rotate_costmap0" + type: "complex_recovery/SequentialComplexRecovery" +speak_and_rotate_costmap0: + recovery_behaviors: + - name: "speak_and_wait0" + type: "speak_and_wait_recovery/SpeakAndWaitRecovery" + - name: "rotate0" + type: "rotate_recovery/RotateRecovery" + speak_and_wait0: + speak_text: "I'm rotating." + duration_wait: 5.0 + duration_timeout: 1.0 + sound_action: /sound_play + rotate0: + sim_granularity: 0.017 + frequency: 20.0 +``` + +In this case, `speak_and_rotate_costmap0` recovery runs `speak_and_wait0` and `rotate0` simultaneously. +So a robot speaks during its rotation. diff --git a/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml b/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml new file mode 100644 index 0000000000..52d7a4b4d5 --- /dev/null +++ b/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml @@ -0,0 +1,18 @@ + + + + A recovery behavior that runs other recovery behaviors sequentially. + + + + + A recovery behavior that runs other recovery behaviors in parallel. + + + diff --git a/jsk_robot_common/complex_recovery/include/complex_recovery/parallel_complex_recovery.h b/jsk_robot_common/complex_recovery/include/complex_recovery/parallel_complex_recovery.h new file mode 100644 index 0000000000..fc56d9c217 --- /dev/null +++ b/jsk_robot_common/complex_recovery/include/complex_recovery/parallel_complex_recovery.h @@ -0,0 +1,32 @@ +#ifndef COMPLEX_RECOVERY_H +#define COMPLEX_RECOVERY_H + +#include +#include +#include +#include + +namespace complex_recovery +{ + +class ParallelComplexRecovery : public nav_core::RecoveryBehavior +{ +public: + ParallelComplexRecovery(); + void initialize( + std::string name, + tf2_ros::Buffer* tf_buffer, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap); + void runBehavior(); + ~ParallelComplexRecovery(); + +private: + bool initialized_; + std::vector > recovery_behaviors_; + std::vector recovery_behavior_names_; + pluginlib::ClassLoader recovery_loader_; +}; +}; + +#endif diff --git a/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h b/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h new file mode 100644 index 0000000000..507e0ea0ab --- /dev/null +++ b/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h @@ -0,0 +1,32 @@ +#ifndef COMPLEX_RECOVERY_H +#define COMPLEX_RECOVERY_H + +#include +#include +#include +#include + +namespace complex_recovery +{ + +class SequentialComplexRecovery : public nav_core::RecoveryBehavior +{ +public: + SequentialComplexRecovery(); + void initialize( + std::string name, + tf2_ros::Buffer*, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap); + void runBehavior(); + ~SequentialComplexRecovery(); + +private: + bool initialized_; + std::vector > recovery_behaviors_; + std::vector recovery_behavior_names_; + pluginlib::ClassLoader recovery_loader_; +}; +}; + +#endif diff --git a/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h b/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h new file mode 100644 index 0000000000..a02ee51eec --- /dev/null +++ b/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h @@ -0,0 +1,21 @@ +#include +#include +#include +#include +#include + +namespace complex_recovery +{ + + +bool loadRecoveryBehaviors( + std::string parent_name, + ros::NodeHandle& node, + pluginlib::ClassLoader& recovery_loader, + std::vector >& recovery_behaviors, + std::vector& recovery_behavior_names, + tf2_ros::Buffer* ptr_tf_buffer, + costmap_2d::Costmap2DROS* ptr_global_costmap, + costmap_2d::Costmap2DROS* ptr_local_costmap + ); +}; diff --git a/jsk_robot_common/complex_recovery/package.xml b/jsk_robot_common/complex_recovery/package.xml new file mode 100644 index 0000000000..1892a9fc61 --- /dev/null +++ b/jsk_robot_common/complex_recovery/package.xml @@ -0,0 +1,30 @@ + + + complex_recovery + 1.1.0 + The complex_recovery package + + Koki Shinjo + Kei Okada + Koki Shinjo + + BSD + + + catkin + + costmap_2d + nav_core + pluginlib + roscpp + tf2 + tf2_ros + + rostest + speak_and_wait_recovery + sound_play + + + + + diff --git a/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp new file mode 100644 index 0000000000..80425e0f1b --- /dev/null +++ b/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp @@ -0,0 +1,84 @@ +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(complex_recovery::ParallelComplexRecovery, nav_core::RecoveryBehavior) + +namespace complex_recovery +{ + +ParallelComplexRecovery::ParallelComplexRecovery(): + initialized_(false), + recovery_loader_("nav_core", "nav_core::RecoveryBehavior") +{ +} + +void ParallelComplexRecovery::initialize( + std::string name, + tf2_ros::Buffer* tf_buffer, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap) +{ + if (not initialized_) { + ros::NodeHandle private_nh("~/" + name); + bool success = loadRecoveryBehaviors( + name, + private_nh, + recovery_loader_, + recovery_behaviors_, + recovery_behavior_names_, + tf_buffer, + global_costmap, + local_costmap + ); + if ( not success ) { + ROS_ERROR("Failed to load behaviors."); + } else { + ROS_INFO("Behaviors are loaded."); + for (auto behavior_name = recovery_behavior_names_.begin(); behavior_name != recovery_behavior_names_.end(); behavior_name++) { + ROS_INFO("behavior: %s", behavior_name->c_str()); + } + } + + initialized_ = true; + } else { + ROS_ERROR("You should not call initialize twice on this object, doing nothing"); + } +} + +ParallelComplexRecovery::~ParallelComplexRecovery() +{ + recovery_behaviors_.clear(); +} + +void ParallelComplexRecovery::runBehavior() +{ + if (not initialized_) + { + ROS_ERROR("This object must be initialized before runBehavior is called"); + return; + } + + std::vector> threads; + + ROS_INFO("Start executing behaviors in parallel."); + for (auto index = 0; index < recovery_behaviors_.size(); index++) { + ROS_INFO("start executing behavior %s", recovery_behavior_names_[index].c_str()); + threads.push_back( + std::shared_ptr( + new std::thread( + &nav_core::RecoveryBehavior::runBehavior, + recovery_behaviors_[index] + ))); + } + + ROS_INFO("Waiting for behaviors to finish."); + for (auto thread = threads.begin(); thread != threads.end(); thread++) { + (*thread)->join(); + } + + ROS_INFO("All behaviors have finished."); +} + +}; diff --git a/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp new file mode 100644 index 0000000000..4a71196ea1 --- /dev/null +++ b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp @@ -0,0 +1,71 @@ +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(complex_recovery::SequentialComplexRecovery, nav_core::RecoveryBehavior) + +namespace complex_recovery +{ + +SequentialComplexRecovery::SequentialComplexRecovery(): + initialized_(false), + recovery_loader_("nav_core", "nav_core::RecoveryBehavior") +{ +} + +void SequentialComplexRecovery::initialize( + std::string name, + tf2_ros::Buffer* tf_buffer, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap) +{ + if (not initialized_) { + ros::NodeHandle private_nh("~/" + name); + bool success = loadRecoveryBehaviors( + name, + private_nh, + recovery_loader_, + recovery_behaviors_, + recovery_behavior_names_, + tf_buffer, + global_costmap, + local_costmap + ); + if ( not success ) { + ROS_ERROR("Failed to load behaviors."); + } else { + ROS_INFO("Behaviors are loaded."); + for (auto behavior_name = recovery_behavior_names_.begin(); behavior_name != recovery_behavior_names_.end(); behavior_name++) { + ROS_INFO("behavior: %s", behavior_name->c_str()); + } + } + + initialized_ = true; + } else { + ROS_ERROR("You should not call initialize twice on this object, doing nothing"); + } +} + +SequentialComplexRecovery::~SequentialComplexRecovery() +{ + recovery_behaviors_.clear(); +} + +void SequentialComplexRecovery::runBehavior() +{ + if (not initialized_) + { + ROS_ERROR("This object must be initialized before runBehavior is called"); + return; + } + + ROS_INFO("Start executing behaviors sequentially."); + for (auto index = 0; index < recovery_behaviors_.size(); index++) { + ROS_INFO("executing behavior %s", recovery_behavior_names_[index].c_str()); + recovery_behaviors_[index]->runBehavior(); + } + + ROS_INFO("All behaviors have finished."); +} + +}; diff --git a/jsk_robot_common/complex_recovery/src/utils.cpp b/jsk_robot_common/complex_recovery/src/utils.cpp new file mode 100644 index 0000000000..660d91007f --- /dev/null +++ b/jsk_robot_common/complex_recovery/src/utils.cpp @@ -0,0 +1,108 @@ +#include + +namespace complex_recovery +{ + +/** + * + * Almost copied from https://github.com/ros-planning/navigation/blob/47c9c629fc93e6c6bbcd3109eb2d5b55efce400d/move_base/src/move_base.cpp#L1019-L1102 + */ +bool loadRecoveryBehaviors( + std::string parent_name, + ros::NodeHandle& node, + pluginlib::ClassLoader& recovery_loader, + std::vector >& recovery_behaviors, + std::vector& recovery_behavior_names, + tf2_ros::Buffer* ptr_tf_buffer, + costmap_2d::Costmap2DROS* ptr_global_costmap, + costmap_2d::Costmap2DROS* ptr_local_costmap + ) +{ + XmlRpc::XmlRpcValue behavior_list; + if(node.getParam("recovery_behaviors", behavior_list)){ + if(behavior_list.getType() == XmlRpc::XmlRpcValue::TypeArray){ + for(int i = 0; i < behavior_list.size(); ++i){ + if(behavior_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct){ + if(behavior_list[i].hasMember("name") && behavior_list[i].hasMember("type")){ + //check for recovery behaviors with the same name + for(int j = i + 1; j < behavior_list.size(); j++){ + if(behavior_list[j].getType() == XmlRpc::XmlRpcValue::TypeStruct){ + if(behavior_list[j].hasMember("name") && behavior_list[j].hasMember("type")){ + std::string name_i = behavior_list[i]["name"]; + std::string name_j = behavior_list[j]["name"]; + if(name_i == name_j){ + ROS_ERROR("A recovery behavior with the name %s already exists, this is not allowed. Using the default recovery behaviors instead.", + name_i.c_str()); + return false; + } + } + } + } + } + else{ + ROS_ERROR("Recovery behaviors must have a name and a type and this does not. Using the default recovery behaviors instead."); + return false; + } + } + else{ + ROS_ERROR("Recovery behaviors must be specified as maps, but they are XmlRpcType %d. We'll use the default recovery behaviors instead.", + behavior_list[i].getType()); + return false; + } + } + + //if we've made it to this point, we know that the list is legal so we'll create all the recovery behaviors + for(int i = 0; i < behavior_list.size(); ++i){ + try{ + //check if a non fully qualified name has potentially been passed in + if(!recovery_loader.isClassAvailable(behavior_list[i]["type"])){ + std::vector classes = recovery_loader.getDeclaredClasses(); + for(unsigned int i = 0; i < classes.size(); ++i){ + if(behavior_list[i]["type"] == recovery_loader.getName(classes[i])){ + //if we've found a match... we'll get the fully qualified name and break out of the loop + ROS_WARN("Recovery behavior specifications should now include the package name. You are using a deprecated API. Please switch from %s to %s in your yaml file.", + std::string(behavior_list[i]["type"]).c_str(), classes[i].c_str()); + behavior_list[i]["type"] = classes[i]; + break; + } + } + } + + boost::shared_ptr behavior(recovery_loader.createInstance(behavior_list[i]["type"])); + + //shouldn't be possible, but it won't hurt to check + if(behavior.get() == NULL){ + ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. This should not happen"); + return false; + } + + //initialize the recovery behavior with its name + std::string base_name = behavior_list[i]["name"]; + behavior->initialize( + parent_name + "/" + base_name, + ptr_tf_buffer, ptr_global_costmap, ptr_local_costmap); + recovery_behavior_names.push_back(behavior_list[i]["name"]); + recovery_behaviors.push_back(behavior); + } + catch(pluginlib::PluginlibException& ex){ + ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what()); + return false; + } + } + } + else{ + ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. We'll use the default recovery behaviors instead.", + behavior_list.getType()); + return false; + } + } + else{ + //if no recovery_behaviors are specified, we'll just load the defaults + return false; + } + + //if we've made it here... we've constructed a recovery behavior list successfully + return true; +} + +}; diff --git a/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test new file mode 100644 index 0000000000..17dc02c20c --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test @@ -0,0 +1,56 @@ + + + + recovery: + recovery_behaviors: + - name: 'wait_and_speak_complex0' + type: 'complex_recovery/SequentialComplexRecovery' + - name: 'wait_and_speak_complex1' + type: 'complex_recovery/SequentialComplexRecovery' + wait_and_speak_complex0: + recovery_behaviors: + - name: 'wait_3_secs' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + - name: 'speak_and_wait0' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + wait_3_secs: + speak_text: '' + duration_wait: 3.0 + duration_timeout: 2.0 + result_timeout: 1.0 + speak_and_wait0: + speak_text: 'test0' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 + wait_and_speak_complex1: + recovery_behaviors: + - name: 'wait_5_secs' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + - name: 'speak_and_wait1' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + wait_5_secs: + speak_text: '' + duration_wait: 5.0 + duration_timeout: 2.0 + result_timeout: 1.0 + speak_and_wait1: + speak_text: 'test1' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 + + + + + diff --git a/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery_test_node.cpp b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery_test_node.cpp new file mode 100644 index 0000000000..3d54f9cad7 --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery_test_node.cpp @@ -0,0 +1,21 @@ +#include +#include "complex_recovery/parallel_complex_recovery.h" + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "complex_recovery_simple_node"); + ros::NodeHandle nh; + + complex_recovery::ParallelComplexRecovery recovery; + recovery.initialize(std::string("recovery"),NULL,NULL,NULL); + + ros::Rate rate(10); + while (ros::ok()) { + ROS_WARN("Spoken a test"); + recovery.runBehavior(); + ros::spinOnce(); + rate.sleep(); + } + + return 0; +} diff --git a/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery.test b/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery.test new file mode 100644 index 0000000000..78bfd748f2 --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery.test @@ -0,0 +1,34 @@ + + + + recovery: + recovery_behaviors: + - name: 'speak_and_wait0' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + - name: 'speak_and_wait1' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + speak_and_wait0: + speak_text: 'test0' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 + speak_and_wait1: + speak_text: 'test1' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 + + + + + diff --git a/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery_test_node.cpp b/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery_test_node.cpp new file mode 100644 index 0000000000..618ff5656c --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery_test_node.cpp @@ -0,0 +1,21 @@ +#include +#include "complex_recovery/sequential_complex_recovery.h" + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "complex_recovery_simple_node"); + ros::NodeHandle nh; + + complex_recovery::SequentialComplexRecovery recovery; + recovery.initialize(std::string("recovery"),NULL,NULL,NULL); + + ros::Rate rate(10); + while (ros::ok()) { + ROS_WARN("Spoken a test"); + recovery.runBehavior(); + ros::spinOnce(); + rate.sleep(); + } + + return 0; +} diff --git a/jsk_robot_common/complex_recovery/tests/test_parallel_complex_recovery.py b/jsk_robot_common/complex_recovery/tests/test_parallel_complex_recovery.py new file mode 100755 index 0000000000..8d7fea0de8 --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/test_parallel_complex_recovery.py @@ -0,0 +1,55 @@ +#!/usr/bin/env python + +from sound_play.msg import SoundRequestResult +from sound_play.msg import SoundRequestAction +import rospy +import actionlib +import threading +import sys +import unittest +import rostest + +PKG = 'complex_recovery' +NAME = 'parallel_complex_recovery_test' + + +class TestParallelComplexRecovery(unittest.TestCase): + + def __init__(self, *args): + super(self.__class__, self).__init__(*args) + rospy.init_node(NAME) + + self.lock_for_msg = threading.Lock() + self.speech_text_list = [] + + self.action_server = \ + actionlib.SimpleActionServer( + '/sound_play', SoundRequestAction, execute_cb=self.handler, auto_start=False) + self.action_server.start() + + def handler(self, goal): + + with self.lock_for_msg: + self.speech_text_list.append(goal.sound_request.arg) + rospy.logwarn('Receive a message') + self.action_server.set_succeeded( + SoundRequestResult(playing=True, stamp=rospy.Time.now())) + + def test_parallel_complex_recovery(self): + + rate = rospy.Rate(1) + while not rospy.is_shutdown(): + with self.lock_for_msg: + if 'test0' in self.speech_text_list and 'test1' in self.speech_text_list: + break + else: + rospy.logwarn('waiting') + rate.sleep() + + with self.lock_for_msg: + rospy.logwarn('speech_text_list: {}'.format(self.speech_text_list)) + self.assertTrue('test0' in self.speech_text_list and 'test1' in self.speech_text_list) + + +if __name__ == '__main__': + rostest.rosrun(PKG, NAME, TestParallelComplexRecovery, sys.argv) diff --git a/jsk_robot_common/complex_recovery/tests/test_sequential_complex_recovery.py b/jsk_robot_common/complex_recovery/tests/test_sequential_complex_recovery.py new file mode 100755 index 0000000000..4dce3752b1 --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/test_sequential_complex_recovery.py @@ -0,0 +1,55 @@ +#!/usr/bin/env python + +from sound_play.msg import SoundRequestResult +from sound_play.msg import SoundRequestAction +import rospy +import actionlib +import threading +import sys +import unittest +import rostest + +PKG = 'complex_recovery' +NAME = 'sequential_complex_recovery_test' + + +class TestSequentialComplexRecovery(unittest.TestCase): + + def __init__(self, *args): + super(self.__class__, self).__init__(*args) + rospy.init_node(NAME) + + self.lock_for_msg = threading.Lock() + self.speech_text_list = [] + + self.action_server = \ + actionlib.SimpleActionServer( + '/sound_play', SoundRequestAction, execute_cb=self.handler, auto_start=False) + self.action_server.start() + + def handler(self, goal): + + with self.lock_for_msg: + self.speech_text_list.append(goal.sound_request.arg) + rospy.logwarn('Receive a message') + self.action_server.set_succeeded( + SoundRequestResult(playing=True, stamp=rospy.Time.now())) + + def test_sequential_complex_recovery(self): + + rate = rospy.Rate(1) + while not rospy.is_shutdown(): + with self.lock_for_msg: + if 'test0' in self.speech_text_list and 'test1' in self.speech_text_list: + break + else: + rospy.logwarn('waiting') + rate.sleep() + + with self.lock_for_msg: + rospy.logwarn('speech_text_list: {}'.format(self.speech_text_list)) + self.assertTrue('test0' in self.speech_text_list and 'test1' in self.speech_text_list) + + +if __name__ == '__main__': + rostest.rosrun(PKG, NAME, TestSequentialComplexRecovery, sys.argv) diff --git a/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed b/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed index e142d9282c..1350da5b19 100644 --- a/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed +++ b/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed @@ -1,5 +1,15 @@ apps: - app: jsk_robot_startup/personal_use - display: Personal use + display: Personal use - app: jsk_robot_startup/check_use_sim_time display: Check /use_sim_time param + - app: jsk_robot_startup/roseus_resume_interrupt + display: Interrupt + - app: jsk_robot_startup/roseus_resume_resume + display: Resume + - app: jsk_robot_startup/volume_lower + display: Volume lower + - app: jsk_robot_startup/volume_reset + display: Volume reset + - app: jsk_robot_startup/volume_zero + display: Volume zero diff --git a/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.app b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.app new file mode 100644 index 0000000000..d6ea2dad0f --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.app @@ -0,0 +1,6 @@ +display: Interrupt +platform: all +run: rostopic/rostopic +run_args: "pub -1 /roseus_resume/interrupt std_msgs/Empty" +interface: jsk_robot_startup/roseus_resume_interrupt.interface +icon: jsk_robot_startup/roseus_resume_interrupt.png diff --git a/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.interface b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.interface new file mode 100644 index 0000000000..044105d644 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} diff --git a/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.png b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.png new file mode 100644 index 0000000000..352d08ee47 Binary files /dev/null and b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.png differ diff --git a/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.app b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.app new file mode 100644 index 0000000000..c21b0d3a49 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.app @@ -0,0 +1,6 @@ +display: Resume +platform: all +run: rostopic/rostopic +run_args: "pub -1 /roseus_resume/resume std_msgs/Empty" +interface: jsk_robot_startup/roseus_resume_resume.interface +icon: jsk_robot_startup/roseus_resume_resume.png diff --git a/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.interface b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.interface new file mode 100644 index 0000000000..044105d644 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} diff --git a/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.png b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.png new file mode 100644 index 0000000000..235869778e Binary files /dev/null and b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.png differ diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.app b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.app new file mode 100644 index 0000000000..e9648c034f --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.app @@ -0,0 +1,6 @@ +display: Volume Lower +description: robot speaks lower volume +platform: all +run: jsk_robot_startup/auto_speak_volume_lower.l +interface: jsk_robot_startup/volume_lower.interface +icon: jsk_robot_startup/volume_lower.png \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.interface b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.interface new file mode 100644 index 0000000000..5cb4ae9816 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.png b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.png new file mode 100644 index 0000000000..d79825e859 Binary files /dev/null and b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.png differ diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.app b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.app new file mode 100644 index 0000000000..9b71b6cfb6 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.app @@ -0,0 +1,6 @@ +display: Volume Reset +description: robot speaks reset volume +platform: all +run: jsk_robot_startup/auto_speak_volume_reset.l +interface: jsk_robot_startup/volume_reset.interface +icon: jsk_robot_startup/volume_reset.png \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.interface b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.interface new file mode 100644 index 0000000000..5cb4ae9816 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.png b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.png new file mode 100644 index 0000000000..d9dbfbc14f Binary files /dev/null and b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.png differ diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.app b/jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.app new file mode 100644 index 0000000000..99cc7aecb2 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.app @@ -0,0 +1,6 @@ +display: Volume Zero +description: robot speaks zero volume +platform: all +run: jsk_robot_startup/auto_speak_volume_zero.l +interface: jsk_robot_startup/volume_zero.interface +icon: jsk_robot_startup/volume_zero.png \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.interface b/jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.interface new file mode 100644 index 0000000000..5cb4ae9816 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.png b/jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.png new file mode 100644 index 0000000000..cb736a528e Binary files /dev/null and b/jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.png differ diff --git a/jsk_robot_common/jsk_robot_startup/launch/interaction.launch b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch new file mode 100644 index 0000000000..0b3487d7c2 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch new file mode 100644 index 0000000000..ee310515ba --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch @@ -0,0 +1,147 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + approximate_sync: true + topics: + - /publish_trigger_mongodb_event + - $(arg image)/compressed + + + + + + + + + + + + + + + + + + + diff --git a/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch b/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch new file mode 100644 index 0000000000..6313364c0d --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch b/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch index f1f90dc1e3..1e7a5be105 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch @@ -2,6 +2,8 @@ + + @@ -44,6 +46,7 @@ delay_between_messages: 0 max_message_size: None fragment_timeout: 600 + unregister_timeout: 100000000 + + diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l new file mode 100755 index 0000000000..6696fe3f16 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l @@ -0,0 +1,15 @@ +#!/usr/bin/env roseus + +(ros::roseus "speak_volume_lower") +(ros::set-dynamic-reconfigure-param "/audible_warning" "enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/audible_warning" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/time_signal" "volume" :double 0.2) +(exit) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l new file mode 100755 index 0000000000..315e9151af --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l @@ -0,0 +1,15 @@ +#!/usr/bin/env roseus + +(ros::roseus "speak_volume_reset") +(ros::set-dynamic-reconfigure-param "/audible_warning" "enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/audible_warning" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/time_signal" "volume" :double 1.0) +(exit) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l new file mode 100755 index 0000000000..39c58b530e --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l @@ -0,0 +1,15 @@ +#!/usr/bin/env roseus + +(ros::roseus "speak_volume_zero") +(ros::set-dynamic-reconfigure-param "/audible_warning" "enable" :bool nil) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "speak_enable" :bool nil) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "speak_enable" :bool nil) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "speak_enable" :bool nil) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "speak_enable" :bool nil) +(ros::set-dynamic-reconfigure-param "/audible_warning" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/time_signal" "volume" :double 0.0) +(exit) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index b99511f06d..9af0e43968 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -1,4 +1,8 @@ + + + + @@ -11,6 +15,8 @@ + + @@ -36,8 +42,9 @@ + - + @@ -56,7 +63,7 @@ pkg="nodelet" type="nodelet" args="manager" machine="$(arg machine)" output="screen" respawn="$(arg respawn)" launch-prefix="$(arg launch-prefix)"/> - + @@ -135,10 +142,14 @@ respawn="$(arg respawn)"> + database: $(arg database) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg rgb_ns)/$(arg rgb_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + + database: $(arg database) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg rgb_ns)/$(arg rgb_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + @@ -161,10 +176,14 @@ respawn="$(arg respawn)"> + database: $(arg database) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg depth_ns)/$(arg depth_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + + database: $(arg database) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg depth_ns)/$(arg depth_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + @@ -187,8 +210,12 @@ respawn="$(arg respawn)" if="$(arg save_tf)"> + database: $(arg database) update_rate: $(arg log_rate) + + collection: $(arg collection) + @@ -199,8 +226,12 @@ respawn="$(arg respawn)"> + database: $(arg database) periodic_rate: $(arg log_rate) + + collection: $(arg collection) + + database: $(arg database) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg joint_states_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + @@ -221,11 +256,15 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) topics: - /server_name/smach/container_init - /server_name/smach/container_status - /server_name/smach/container_structure + + collection: $(arg collection) + + database: $(arg database) topics: - /Tablet/voice + + collection: $(arg collection) + @@ -246,10 +289,14 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) topics: - /aws_auto_checkin_app/class - /aws_detect_faces/attributes + + collection: $(arg collection) + @@ -259,10 +306,14 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) topics: - /dialogflow_client/text_action/goal - /dialogflow_client/text_action/result + + collection: $(arg collection) + @@ -288,21 +339,64 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) update_rate: $(arg log_rate) map_frame: $(arg map_frame_id) robot_frame: $(arg base_frame_id) + + collection: $(arg collection) + - + + + database: $(arg database) + topics: + - /edgetpu_object_detector/output/class + - /edgetpu_object_detector/output/rects + + + collection: $(arg collection) + + + + + database: $(arg database) + map_frame: $(arg map_frame_id) + robot_frame: $(arg base_frame_id) + + + collection: $(arg collection) + + + + + + - map_frame: $(arg map_frame_id) - robot_frame: $(arg base_frame_id) + database: $(arg database) + topics: + - /edgetpu_human_pose_estimator/output/class + - /edgetpu_human_pose_estimator/output/poses + - /edgetpu_human_pose_estimator/output/rects + + + collection: $(arg collection) @@ -311,7 +405,14 @@ name="action_logger" pkg="jsk_robot_startup" type="action_logger.py" machine="$(arg machine)" - respawn="$(arg respawn)" /> + respawn="$(arg respawn)"> + + database: $(arg database) + + + collection: $(arg collection) + + + database: $(arg database) subst_param: true topics: - /${param /robot/name}/app_list + + collection: $(arg collection) + diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/lifelog_rgb_image.launch b/jsk_robot_common/jsk_robot_startup/lifelog/lifelog_rgb_image.launch new file mode 100644 index 0000000000..6f0f1e4a28 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/lifelog/lifelog_rgb_image.launch @@ -0,0 +1,19 @@ + + + + + + + + + + + + enable_monitor: false + vital_check: false + + + diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch index 13c62d42f4..2a60fe5e16 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch @@ -10,17 +10,25 @@ + + + + + output="screen" machine="$(arg machine)"> + + extra_collections: $(arg extra_collections) + + @@ -34,6 +42,7 @@ + diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet.launch b/jsk_robot_common/jsk_robot_startup/lifelog/tweet.launch index b22b0d066c..827bef6832 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet.launch @@ -27,12 +27,21 @@ output="$(arg output)" respawn="true" > + + + account_info: $(arg account_info) + + + + + waking-time *waking-target-second*) - (incf *waking-target-second* *waking-tweet-second*) - ;; tweet source of robot-interface - (unless *src-lines* - (let* ((dirname (ros::rospack-find "pr2eus")) - (fname (format nil "~A/robot-interface.l" dirname)) - str) - (with-open-file (f fname) - (while (setq str (read-line f nil nil)) - (push str *src-lines*))) - (setq *src-lines* (nreverse *src-lines*)) - )) + (if *enable* + (progn + (setq *user-name* (ros::get-param "/active_user/launch_user_name") + *elapsed-time* (ros::get-param "/active_user/elapsed_time")) + ;; tweet depend on up time + (let ((st (ros::get-param "/active_user/start_time"))) + (when st + (let ((waking-time (- (send (ros::time-now) :to-sec) st))) + (ros::ros-debug "~A waking ~A sec (~A)" *robot-name* waking-time *waking-target-second*) + (when (> waking-time *waking-target-second*) + (incf *waking-target-second* (+ *waking-tweet-second* (random *tweet-random-range*))) + ;; tweet source of robot-interface + (unless *src-lines* + (let* ((dirname (ros::rospack-find "pr2eus")) + (fname (format nil "~A/robot-interface.l" dirname)) + str) + (with-open-file (f fname) + (while (setq str (read-line f nil nil)) + (push str *src-lines*))) + (setq *src-lines* (nreverse *src-lines*)) + )) - (let* ((len (length *src-lines*)) - (start-n (floor (random (float len) *random-state*))) - (spos 0) (str-len 0) lines) - (push (format nil "I am running ~A min." (round (/ waking-time 60.0))) - lines) - (incf str-len (length (car lines))) - (while (< (+ start-n spos) len) - (let ((str (elt *src-lines* (+ start-n spos)))) - (incf str-len (length str)) - (if (> str-len 140) (return)) - (push str lines)) - (incf spos)) - (let* ((ln (apply #'+ (length lines) - (mapcar #'(lambda (x) (length x)) lines))) - (dt (make-string (1- ln))) - (pos 0)) - (dolist (s (nreverse lines)) - (replace dt s :start1 pos) - (incf pos (length s)) - (if (< pos (- ln 2)) (setf (elt dt pos) 10)) - (incf pos)) - (tweet-string dt :warning-time 1 :with-image t) - )) - )))) + (let* ((len (length *src-lines*)) + (start-n (floor (random (float len) *random-state*))) + (spos 0) (str-len 0) lines) + (push (format nil "I am running ~A min." (round (/ waking-time 60.0))) + lines) + (incf str-len (length (car lines))) + (while (< (+ start-n spos) len) + (let ((str (elt *src-lines* (+ start-n spos)))) + (incf str-len (length str)) + (if (> str-len 140) (return)) + (push str lines)) + (incf spos)) + (let* ((ln (apply #'+ (length lines) + (mapcar #'(lambda (x) (length x)) lines))) + (dt (make-string (1- ln))) + (pos 0)) + (dolist (s (nreverse lines)) + (replace dt s :start1 pos) + (incf pos (length s)) + (if (< pos (- ln 2)) (setf (elt dt pos) 10)) + (incf pos)) + (tweet-string dt :warning-time 1 :with-image t + :speak *speak-enable* + :volume *volume*) + )))))))) + (ros::spin-once) (ros::sleep) ) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l index 7ec7e3dceb..0f0c1d1b03 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l @@ -2,41 +2,67 @@ (ros::roseus "twitter_client_warning") +(load "package://roseus/euslisp/dynamic-reconfigure-server.l") (load "package://jsk_robot_startup/lifelog/tweet_client.l") (ros::load-ros-manifest "diagnostic_msgs") +(setq *volume* (ros::get-param "~volume" 1.0)) +(setq *speak-enable* (ros::get-param "~speak_enable" t)) +(setq *enable* (ros::get-param "~enable" t)) +(setq *reconfigure-server* + (def-dynamic-reconfigure-server + ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0) + ("speak_enable" bool_t 0 "tweet speak enable" t) + ("enable" bool_t 0 "tweet enable" t)) + ;; use lamda-closure to avoid memory error + '(lambda-closure nil 0 0 (cfg level) + (let ((prev-volume *volume*) + (prev-speak-enable *speak-enable*) + (prev-enable *enable*)) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (setq *speak-enable* (cdr (assoc "speak_enable" cfg :test #'equal))) + (setq *enable* (cdr (assoc "enable" cfg :test #'equal))) + (if (null (equal *volume* prev-volume)) + (ros::ros-warn "Volume changed to: ~A" *volume*)) + (if (null (equal *enable* prev-enable)) + (ros::ros-warn "Enable changed to: ~A" *enable*)) + (if (null (equal *speak-enable* prev-speak-enable)) + (ros::ros-warn "Speak enable changed to: ~A" *speak-enable*))) + cfg))) + (defun diagnostics-cb (msg) - (let ((diagnostics (make-hash-table :test #'equal)) - (tm (ros::time-now)) - status id) - (ros::ros-debug (format nil "~0,3f diagnostics_msgs~%" (send tm :to-sec))) - (dolist (status (send msg :status)) - ;; diagnostic_msgs::DiagnosticStatus::*WARN* - (when (>= (send status :level) diagnostic_msgs::DiagnosticStatus::*WARN*) ;; diagnostic_msgs::DiagnosticStatus::*ERROR*) - (cond ((substringp "/Motors" (send status :name)) - t) ;; skip motors - ((substringp "/Other/Accelerometer" (send status :name)) t) - ((substringp "/Other/Pressure" (send status :name)) t) - ((and (string= "/Computers/Network/Wifi Status (ddwrt)" (send status :name)) - (string= "Updates Stale" (send status :message))) t) - ((and (string= "/Computers/Network" (send status :name)) - (string= "Error" (send status :message))) t) - ((substringp "/Peripherals/PS3 Controller" (send status :name)) t) ;; fetch joystick warning - ((position #\/ (send status :name) :count 2) ;; check depth of name - (setq key (subseq (send status :name) 0 (position #\/ (send status :name) :count 2))) - (when (> (length (send status :name)) (length (gethash key diagnostics))) - (setf (gethash key diagnostics) (cons (send status :name) (send status :message))) - ) ;; when - )) - )) ;; when / dolist - (maphash #'(lambda (k v) (ros::ros-debug (format nil "Warnings ~A ~A~%" (length status) v)) (push v status)) diagnostics) - (when status - (setq id (random (length status))) - (when (= (mod (round (send tm :sec)) 1000) 0) - (tweet-string (format nil "Warning!! ~A is ~A at ~0,3f" (car (elt status id)) (cdr (elt status id)) (send tm :to-sec)) - :warning-time 1 :with-image t) - )) ;; when - )) ;; let + (if *enable* + (let ((diagnostics (make-hash-table :test #'equal)) + (tm (ros::time-now)) + status id) + (ros::ros-debug (format nil "~0,3f diagnostics_msgs~%" (send tm :to-sec))) + (dolist (status (send msg :status)) + ;; diagnostic_msgs::DiagnosticStatus::*WARN* + (when (>= (send status :level) diagnostic_msgs::DiagnosticStatus::*WARN*) ;; diagnostic_msgs::DiagnosticStatus::*ERROR*) + (cond ((substringp "/Motors" (send status :name)) + t) ;; skip motors + ((substringp "/Other/Accelerometer" (send status :name)) t) + ((substringp "/Other/Pressure" (send status :name)) t) + ((and (string= "/Computers/Network/Wifi Status (ddwrt)" (send status :name)) + (string= "Updates Stale" (send status :message))) t) + ((and (string= "/Computers/Network" (send status :name)) + (string= "Error" (send status :message))) t) + ((substringp "/Peripherals/PS3 Controller" (send status :name)) t) ;; fetch joystick warning + ((position #\/ (send status :name) :count 2) ;; check depth of name + (setq key (subseq (send status :name) 0 (position #\/ (send status :name) :count 2))) + (when (> (length (send status :name)) (length (gethash key diagnostics))) + (setf (gethash key diagnostics) (cons (send status :name) (send status :message))) + ) ;; when + )) + )) ;; when / dolist + (maphash #'(lambda (k v) (ros::ros-debug (format nil "Warnings ~A ~A~%" (length status) v)) (push v status)) diagnostics) + (when status + (setq id (random (length status))) + (when (= (mod (round (send tm :sec)) 1000) 0) + (tweet-string (format nil "Warning!! ~A is ~A at ~0,3f" (car (elt status id)) (cdr (elt status id)) (send tm :to-sec)) + :warning-time 1 :with-image t :volume *volume* :speak *speak-enable*))) + ))) (ros::advertise "/tweet" std_msgs::String 1) (ros::subscribe "/diagnostics_agg" diagnostic_msgs::DiagnosticArray #'diagnostics-cb) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l index dac8769842..52baa59aaf 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l @@ -2,6 +2,7 @@ (ros::roseus "twitter_client_worktime") +(load "package://roseus/euslisp/dynamic-reconfigure-server.l") (load "package://jsk_robot_startup/lifelog/tweet_client.l") (defvar *robot-name* "robot") @@ -34,49 +35,78 @@ (t (setq *waking-target-second* *waking-tweet-second*))) +(setq *volume* (ros::get-param "~volume" 1.0)) +(setq *speak-enable* (ros::get-param "~speak_enable" t)) +(setq *enable* (ros::get-param "~enable" t)) +(setq *reconfigure-server* + (def-dynamic-reconfigure-server + ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0) + ("speak_enable" bool_t 0 "tweet speak enable" t) + ("enable" bool_t 0 "tweet enable" t)) + ;; use lamda-closure to avoid memory error + '(lambda-closure nil 0 0 (cfg level) + (let ((prev-volume *volume*) + (prev-speak-enable *speak-enable*) + (prev-enable *enable*)) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (setq *speak-enable* (cdr (assoc "speak_enable" cfg :test #'equal))) + (setq *enable* (cdr (assoc "enable" cfg :test #'equal))) + (if (null (equal *volume* prev-volume)) + (ros::ros-warn "Volume changed to: ~A" *volume*)) + (if (null (equal *enable* prev-enable)) + (ros::ros-warn "Enable changed to: ~A" *enable*)) + (if (null (equal *speak-enable* prev-speak-enable)) + (ros::ros-warn "Speak enable changed to: ~A" *speak-enable*))) + cfg))) + (ros::advertise "/tweet" std_msgs::String 1) (ros::rate 0.1) (do-until-key - (setq *user-name* (ros::get-param "/active_user/launch_user_name") - *elapsed-time* (ros::get-param "/active_user/elapsed_time")) - (ros::ros-debug "user -> ~A, time -> ~A (~A) " - *user-name* *elapsed-time* *target-second*) - ;; tweet depend on working time - (when (> *elapsed-time* *target-second*) - (incf *target-second* *tweet-second* ) - (ros::ros-info "tweet ~A ~A" *user-name* *elapsed-time*) - (let ((mainstr (format nil "~A has used ~A for ~d minutes" - ;; why delete *user-name* after space ? - ;;(subseq *user-name* 0 - ;;(or (position #\space *user-name*) - ;;(length *user-name*))) - *user-name* - *robot-name* - (round (/ *elapsed-time* 60)))) - presubstr postsubstr) - (cond - ((< *elapsed-time* 600) ;; 5 min - (setq presubstr "Congratulations! " - postsubstr ", Let's get started!")) - ((< *elapsed-time* 910) ;; 15 min - (setq presubstr "Gooood! " - postsubstr ", Go ahead!")) - ((< *elapsed-time* 1820) ;; 30 min - (setq presubstr "So Nice! " - postsubstr ", Go ahead!")) - ((< *elapsed-time* 2730) ;; 45 min - (setq presubstr "Fantastic! " - postsubstr ", Keep going!")) - ((< *elapsed-time* 3640) ;; 60 min - (setq presubstr "Amazing! " - postsubstr ", I'm not tired!")) - (t - (setq presubstr "Awesome! " - postsubstr ", Got some rest?"))) - - (tweet-string (format nil "~A~A~A" presubstr mainstr postsubstr) - :warning-time 1 :with-image t) + (if *enable* + (progn + (setq *user-name* (ros::get-param "/active_user/launch_user_name") + *elapsed-time* (ros::get-param "/active_user/elapsed_time")) + (ros::ros-debug "user -> ~A, time -> ~A (~A) " + *user-name* *elapsed-time* *target-second*) + ;; tweet depend on working time + (when (> *elapsed-time* *target-second*) + (incf *target-second* *tweet-second* ) + (ros::ros-info "tweet ~A ~A" *user-name* *elapsed-time*) + (let ((mainstr (format nil "~A has used ~A for ~d minutes" + ;; why delete *user-name* after space ? + ;;(subseq *user-name* 0 + ;;(or (position #\space *user-name*) + ;;(length *user-name*))) + *user-name* + *robot-name* + (round (/ *elapsed-time* 60)))) + presubstr postsubstr) + (cond + ((< *elapsed-time* 600) ;; 5 min + (setq presubstr "Congratulations! " + postsubstr ", Let's get started!")) + ((< *elapsed-time* 910) ;; 15 min + (setq presubstr "Gooood! " + postsubstr ", Go ahead!")) + ((< *elapsed-time* 1820) ;; 30 min + (setq presubstr "So Nice! " + postsubstr ", Go ahead!")) + ((< *elapsed-time* 2730) ;; 45 min + (setq presubstr "Fantastic! " + postsubstr ", Keep going!")) + ((< *elapsed-time* 3640) ;; 60 min + (setq presubstr "Amazing! " + postsubstr ", I'm not tired!")) + (t + (setq presubstr "Awesome! " + postsubstr ", Got some rest?"))) - )) + (tweet-string (format nil "~A~A~A" presubstr mainstr postsubstr) + :warning-time 1 :with-image t + :speak *speak-enable* + :volume *volume*) + )))) + (ros::spin-once) (ros::sleep) ) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/shutdown.py b/jsk_robot_common/jsk_robot_startup/scripts/shutdown.py index ff05431dbc..97bab6c60f 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/shutdown.py +++ b/jsk_robot_common/jsk_robot_startup/scripts/shutdown.py @@ -1,9 +1,11 @@ #!/usr/bin/env python +# -*- coding: utf-8 -*- import os from importlib import import_module import rospy +from sound_play.libsoundplay import SoundClient from std_msgs.msg import Empty @@ -32,7 +34,7 @@ class Shutdown(object): def __init__(self): rospy.loginfo('Start shutdown node.') - + self.client_jp = SoundClient(sound_action='/robotsound_jp', blocking=True) self.condition = rospy.get_param( '~input_condition', None) if self.condition is not None: @@ -51,6 +53,11 @@ def __init__(self): '~shutdown_command', '/sbin/shutdown -h now') self.reboot_command = rospy.get_param( '~reboot_command', '/sbin/shutdown -r now') + self.volume = rospy.get_param('~volume', 1.0) + + def speak(self, client, speech_text, lang='jp'): + client.say(speech_text, voice=lang, volume=self.volume, replace=False) + return client.actionclient.get_result() def callback(self, msg): if isinstance(msg, rospy.msg.AnyMsg): @@ -81,6 +88,7 @@ def shutdown(self, msg): return rospy.loginfo('Shut down robot.') + self.speak(self.client_jp, 'シャットダウンします。') ret = os.system(self.shutdown_command) if ret != 0: rospy.logerr("Failed to call '$ {}'. Check authentication.".format( @@ -88,6 +96,7 @@ def shutdown(self, msg): def reboot(self, msg): rospy.loginfo('Reboot robot.') + self.speak(self.client_jp, '再起動します。') ret = os.system(self.reboot_command) if ret != 0: rospy.logerr("Failed to call '$ {}'. Check authentication.".format( diff --git a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py index ac911446b0..8f804b3380 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py +++ b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py @@ -257,6 +257,8 @@ def _send_mail(self, subject, state_list): if subject: email_msg.subject = subject + elif rospy.has_param("/email_topic/mail_title"): + email_msg.subject = rospy.get_param("/email_topic/mail_title") else: email_msg.subject = 'Message from {}'.format(rospy.get_param('/robot/name', 'robot')) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh new file mode 100755 index 0000000000..bb8fbba094 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -0,0 +1,157 @@ +#!/usr/bin/env bash + +function usage() +{ + echo "Usage: $0 [-w workspace_directory] [-r rosinstall_path] [-t robot_type] [-s skip keys] [-h] [-u] [-l] [-n] + +optional arguments: + -h show this help + -w WORKSPACE_PATH specify target workspace + -r ROSINTALL_PATH rosinstall path + -t ROBOT robot type + -s SKIP_KEYS rosdep install skip keys + -u do not run apt-get upgrade and rosdep install + -l do not send a mail + -n do not update workspace, only show wstool status +" +} + +function get_full_path() +{ + echo "$(cd $(dirname $1) && pwd)/$(basename $1)" +} + +ROSDEP_INSTALL=true +SEND_MAIL=true +UPDATE_WORKSPACE=true +WORKSPACE=$(get_full_path $HOME/ros/$ROS_DISTRO) + +while getopts w:r:t:s:ulnh OPT +do + case $OPT in + w) + WORKSPACE=$(get_full_path $OPTARG) + ;; + r) + ROSINSTALL=$(get_full_path $OPTARG) + ;; + t) + ROBOT_TYPE=$OPTARG + ;; + s) + SKIP_KEYS=$OPTARG + ;; + u) + ROSDEP_INSTALL=false + ;; + l) + SEND_MAIL=false + ;; + n) + UPDATE_WORKSPACE=false + ;; + h) + usage + exit 1 + ;; + *) + usage + exit 1 + ;; + esac +done + +if [ "$WORKSPACE" = "" ]; then + echo "Please set valid workspace -w $WORKSPACE
" + exit 1 +fi +if [ "$ROSINSTALL" = "" ]; then + echo "Please set valid rosinstall -r $ROSINSTALL
" + exit 1 +fi +if [ "$ROBOT_TYPE" = "" ]; then + echo "Please set valid robot type -t $ROBOT_TYPE
" + exit 1 +fi + + +. $WORKSPACE/devel/setup.bash +# Filename should end with .txt to preview the contents in a web browser +LOGFILE=$WORKSPACE/update_workspace.txt + +TMP_MAIL_BODY_FILE=/tmp/update_workspace_mailbody.txt + +{ +set -x +# Update workspace +echo "" > $TMP_MAIL_BODY_FILE +wstool foreach -t $WORKSPACE/src --git 'git fetch origin --prune' +WSTOOL_STATUS=$(wstool status -t $WORKSPACE/src) +if [ -n "$WSTOOL_STATUS" ]; then + echo -e "Please commit robot internal change and send pull request.

" >> $TMP_MAIL_BODY_FILE + echo -e $WSTOOL_STATUS >> $TMP_MAIL_BODY_FILE + # escape " ' , -- and add change line code to end of line + wstool diff -t $WORKSPACE/src | sed -e "s/'/ /g" -e "s/^--/ /g" -e 's/"/ /g' -e "s/
/\\\n/" -e 's/$/
/g' -e "s/,/ /g" | tee -a $TMP_MAIL_BODY_FILE +fi +if [ "${UPDATE_WORKSPACE}" == "true" ]; then + wstool foreach -t $WORKSPACE/src --git 'git stash' + wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot --delete-changed-uris + ln -sf $ROSINSTALL $WORKSPACE/src/.rosinstall + wstool update -t $WORKSPACE/src --delete-changed-uris + # Forcefully checkout specified branch + wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); if [ $branchname != "HEAD" ]; then git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout -b $branchname --track origin/$branchname; fi' + wstool update -t $WORKSPACE/src + WSTOOL_UPDATE_RESULT=$? +else + WSTOOL_UPDATE_RESULT=0 +fi +# Rosdep Install +if [ "${ROSDEP_INSTALL}" == "true" ]; then + sudo apt-get update -y; + rosdep update; + rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys "$SKIP_KEYS"; + ROSDEP_INSTALL_RESULT=$?; +else + ROSDEP_INSTALL_RESULT=0; +fi +# Build workspace +cd $WORKSPACE +catkin clean aques_talk collada_urdf_jsk_patch libcmt -y +catkin init +catkin config -DCMAKE_BUILD_TYPE=Release +catkin build --continue-on-failure +CATKIN_BUILD_RESULT=$? +# Send mail +if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then + echo "Please wstool update workspace manually.
" >> $TMP_MAIL_BODY_FILE +fi +if [ $ROSDEP_INSTALL_RESULT -ne 0 ]; then + echo "Please install dependencies manually.
" >> $TMP_MAIL_BODY_FILE +fi +if [ $CATKIN_BUILD_RESULT -ne 0 ]; then + echo "Please catkin build workspace manually.
" >> $TMP_MAIL_BODY_FILE +fi +set +x +} 2>&1 | tee $LOGFILE + +# MAIL_BODY variable cannot be set directly in a subshell. So it is set from temporary mail body text file. +# The mail body text is put as $TMP_MAIL_BODY_FILE. +# See https://github.com/jsk-ros-pkg/jsk_robot/issues/1569 +MAIL_BODY=$(cat $TMP_MAIL_BODY_FILE) +echo "MAIL_BODY: $MAIL_BODY" + +if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" == "true" ]; then + echo "Sent a mail" + rostopic pub -1 /email jsk_robot_startup/Email "header: + seq: 0 + stamp: {secs: 0, nsecs: 0} + frame_id: '' +subject: 'Daily workspace update fails' +body: +- {type: 'html', message: '${MAIL_BODY}', file_path: '', img_data: '', img_size: 0} +sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' +receiver_address: '$ROBOT_TYPE@jsk.imi.i.u-tokyo.ac.jp' +smtp_server: '' +smtp_port: '' +attached_files: ['$LOGFILE']" +fi diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/action_logger.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/action_logger.py index d42e5d89f4..8fe84131a3 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/action_logger.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/action_logger.py @@ -22,7 +22,10 @@ class ActionLogger(LoggerBase): subscribers = {} # topicname:subscriber def __init__(self): - LoggerBase.__init__(self) + db_name = rospy.get_param('~database', 'jsk_robot_lifelog') + col_name = rospy.get_param('~collection', None) + + super(ActionLogger, self).__init__(db_name=db_name, col_name=col_name) self.queue_size = rospy.get_param("~queue_size", 30) self.action_regex = re.compile(".*Action(Result|Goal|Feedback)$") diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/base_trajectory_logger.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/base_trajectory_logger.py index 664f8fac94..c870cab227 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/base_trajectory_logger.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/base_trajectory_logger.py @@ -31,7 +31,11 @@ def diff_pose(p1, p2): class BaseTrajectoryLogger(LoggerBase): def __init__(self): - LoggerBase.__init__(self) + db_name = rospy.get_param('~database', 'jsk_robot_lifelog') + col_name = rospy.get_param('~collection', None) + + super(BaseTrajectoryLogger, self).__init__(db_name=db_name, col_name=col_name) + self.update_rate = rospy.get_param("~update_rate", 1.0) self.use_amcl = rospy.get_param("~use_amcl", True) self.persistent = rospy.get_param("~persistent", True) diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/mongo_record.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/mongo_record.py index 71803288c1..eed8897950 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/mongo_record.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/mongo_record.py @@ -20,6 +20,7 @@ def __init__(self, argv=None): self.queue_size = rospy.get_param("~queue_size", 1) self.update_rate = rospy.get_param("~update_rate", 1.0) subst_param = rospy.get_param("~subst_param", False) + database = rospy.get_param("~database", 'jsk_robot_lifelog') collection = rospy.get_param("~collection", None) else: args = self.parse_args(argv) @@ -28,6 +29,7 @@ def __init__(self, argv=None): self.queue_size = args.queue_size self.update_rate = args.update_rate subst_param = args.subst_param + database = args.database collection = args.collection self.subscribers = {} @@ -42,7 +44,7 @@ def __init__(self, argv=None): topics.append(str().join(splitted)) self.topics = topics - LoggerBase.__init__(self, col_name=collection) + LoggerBase.__init__(self, db_name=database, col_name=collection) def parse_args(self, argv): p = argparse.ArgumentParser() @@ -57,6 +59,8 @@ def parse_args(self, argv): help="Enable substring param (e,g, '$(param robot/name)/list')") p.add_argument("-r", "--update-rate", type=float, default=1.0, help="Update rate for checking topics") + p.add_argument("-d", "--database", type=str, default=None, + help="Database name to record data") p.add_argument("-c", "--collection", type=str, default=None, help="Collection name to record data") return p.parse_args(argv) diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/object_detection_logger.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/object_detection_logger.py index 4b607dade1..f8623ba2cd 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/object_detection_logger.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/object_detection_logger.py @@ -16,7 +16,11 @@ class ObjectDetectionLogger(LoggerBase): def __init__(self): - LoggerBase.__init__(self) + db_name = rospy.get_param('~database', 'jsk_robot_lifelog') + col_name = rospy.get_param('~collection', None) + + super(ObjectDetectionLogger, self).__init__(db_name=db_name, col_name=col_name) + self.update_rate = rospy.get_param("~update_rate", 1.0) self.map_frame = rospy.get_param('~map_frame', 'map') self.robot_frame = rospy.get_param('~robot_frame', 'base_footprint') diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/tf_logger.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/tf_logger.py index 38192b7737..42f0fdbe5e 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/tf_logger.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/tf_logger.py @@ -13,7 +13,10 @@ class TFLogger(LoggerBase): def __init__(self): - LoggerBase.__init__(self) + db_name = rospy.get_param('~database', 'jsk_robot_lifelog') + col_name = rospy.get_param('~collection', None) + + super(TFLogger, self).__init__(db_name=db_name, col_name=col_name) self.tf_buffer = tf2_ros.Buffer() self.tf_listener = tf2_ros.TransformListener(self.tf_buffer) diff --git a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp index c357e44273..e16b176b6c 100644 --- a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp +++ b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp @@ -49,8 +49,23 @@ namespace jsk_robot_startup jsk_topic_tools::StealthRelay::onInit(); // settings for database - nh_->param("/robot/database", db_name_, "jsk_robot_lifelog"); - nh_->param("/robot/name", col_name_, std::string()); + if (ros::param::has(pnh_->resolveName("database"))) + { + pnh_->param("database", db_name_, "jsk_robot_lifelog"); + } + else + { + pnh_->param("/robot/database", db_name_, "jsk_robot_lifelog"); + } + if (ros::param::has(pnh_->resolveName("collection"))) + { + pnh_->param("collection", col_name_, std::string()); + } + else + { + pnh_->param("/robot/name", col_name_, std::string()); + } + if (col_name_.empty()) { NODELET_FATAL_STREAM("Please specify param 'robot/name' (e.g. pr1012, olive)"); @@ -123,7 +138,7 @@ namespace jsk_robot_startup // The message store object is initialized here, since the object waits for connection // until the connection to the server is established. - msg_store_.reset(new mongodb_store::MessageStoreProxy(*nh_, col_name_, db_name_)); + msg_store_.reset(new mongodb_store::MessageStoreProxy(*pnh_, col_name_, db_name_)); initialized_ = true; // After message store object is initialized, this thread is re-used for @@ -183,7 +198,9 @@ namespace jsk_robot_startup const boost::shared_ptr& msg = event.getConstMessage(); jsk_topic_tools::StealthRelay::inputCallback(msg); - vital_checker_->poke(); + if (vital_checker_ != nullptr) { + vital_checker_->poke(); + } bool on_the_fly = initialized_ && buffer_.empty(); if (!wait_for_insert_ && msg_store_->getNumInsertSubscribers() == 0) { @@ -231,7 +248,7 @@ namespace jsk_robot_startup } else if (!initialized_) { stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, getName() + " is taking too long to be initialized"); - } else if (vital_check_ && !vital_checker_->isAlive()) { + } else if (vital_checker_ != nullptr && vital_check_ && !vital_checker_->isAlive()) { jsk_topic_tools::addDiagnosticErrorSummary(getName(), vital_checker_, stat); } else if (insert_error_count_ != prev_insert_error_count_) { stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, @@ -244,7 +261,9 @@ namespace jsk_robot_startup stat.add("Inserted", inserted_count_); stat.add("Insert Failure", insert_error_count_); - vital_checker_->registerStatInfo(stat, "Last Insert"); + if (vital_checker_ != nullptr) { + vital_checker_->registerStatInfo(stat, "Last Insert"); + } } } // lifelog } // jsk_robot_startup