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 7b4a532e61..42c0249b11 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 @@ -71,12 +71,9 @@ plugins: - /odom - /odom_combined - /cmd_vel - - /move_base/NavFnROS/plan - - /move_base/TrajectoryPlannerROS/global_plan - - /move_base/TrajectoryPlannerROS/local_plan - - /move_base/GlobalPlanner/plan - - /move_base/TebLocalPlannerROS/global_plan - - /move_base/TebLocalPlannerROS/local_plan + - /move_base/navigation_plan_viz + - /move_base/global_plan_viz + - /move_base/local_plan_viz - /move_base/global_costmap/footprint - /spots_marker_array - /spots_pictogram 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 31e9f88dd3..09718f32a3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz +++ b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz @@ -240,7 +240,7 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /move_base/NavfnROS/plan + Topic: /move_base/navigation_plan_viz Unreliable: false Value: true - Alpha: 1 @@ -263,7 +263,7 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /move_base/TebLocalPlannerROS/global_plan + Topic: /move_base/global_plan_viz Unreliable: false Value: true - Alpha: 1 @@ -286,7 +286,7 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /move_base/TebLocalPlannerROS/local_plan + Topic: /move_base/local_plan_viz Unreliable: false Value: true - Alpha: 1 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 eeca426e6d..8b162425f0 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 @@ -258,7 +258,7 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /move_base/NavfnROS/plan + Topic: /move_base/navigation_plan_viz Unreliable: false Value: true - Alpha: 1 @@ -281,7 +281,7 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /move_base/TebLocalPlannerROS/global_plan + Topic: /move_base/global_plan_viz Unreliable: false Value: true - Alpha: 1 @@ -304,7 +304,7 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /move_base/TebLocalPlannerROS/local_plan + Topic: /move_base/local_plan_viz Unreliable: false Value: true - Alpha: 1 diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/lightweight_navigation.rviz b/jsk_fetch_robot/jsk_fetch_startup/config/lightweight_navigation.rviz index b20c38ab8f..c582d3e44b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/lightweight_navigation.rviz +++ b/jsk_fetch_robot/jsk_fetch_startup/config/lightweight_navigation.rviz @@ -235,7 +235,7 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /move_base/NavfnROS/plan + Topic: /move_base/navigation_plan_viz Unreliable: false Value: true - Alpha: 1 @@ -258,7 +258,7 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /move_base/TrajectoryPlannerROS/global_plan + Topic: /move_base/global_plan_viz Unreliable: false Value: true - Alpha: 1 @@ -281,7 +281,7 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /move_base/TrajectoryPlannerROS/local_plan + Topic: /move_base/local_plan_viz Unreliable: false Value: true - Alpha: 1 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 477d911beb..1698a0fc4a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -137,11 +137,13 @@ (if is-charging :charging :discharging))) -(defun go-to-spot (name &optional (relative-coords (make-coords)) &key (undock-rotate nil)) +(defun go-to-spot (name &optional (relative-coords (make-coords)) + &key (undock-rotate nil) (clear-costmap t)) ;; undock if fetch is docking (unless (boundp '*ri*) (require :fetch-interface "package://fetcheus/fetch-interface.l") (fetch-init)) + (if clear-costmap (send *ri* :clear-costmap)) (let ((undock-success nil)) (block go-to-spot-undock (dotimes (i 3) @@ -170,14 +172,14 @@ (frame-id (cdr ret))) (when relative-coords (setq goal-pose (send goal-pose :transform relative-coords :world))) - (send *ri* :clear-costmap) (send *ri* :move-to goal-pose :frame-id frame-id))) -(defun auto-dock (&key (n-trial 1)) +(defun auto-dock (&key (n-trial 1) (clear-costmap t)) (let ((success nil)) (dotimes (i n-trial) - (when (go-to-spot *dock-spot* (make-coords :pos #f(-800 0 0))) + (when (go-to-spot *dock-spot* (make-coords :pos #f(-800 0 0)) + :clear-costmap clear-costmap) (ros::ros-info "arrived at the dock.") (setq success (dock)) (when success (return-from auto-dock success)))) @@ -349,7 +351,7 @@ (report-move-to-sink-front-failure)) ;; go back from dock (report-auto-dock) - (setq success-auto-dock (auto-dock :n-trial n-dock-trial)) + (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)) @@ -420,7 +422,7 @@ '(lambda (userdata) (report-auto-dock) (let* ((n-trial (cdr (assoc 'n-dock-trial userdata))) - (success (auto-dock :n-trial n-trial))) + (success (auto-dock :n-trial n-trial :clear-costmap nil))) (setf (cdr (assoc 'success-auto-dock userdata)) success) success))) (:room-light-off 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 362ac7d279..14adf7fc14 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -1,4 +1,5 @@ + @@ -207,17 +208,36 @@ + + + + + + + + file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_amcl_common_params.yaml" /> + file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_amcl_$(env ROS_DISTRO)_params.yaml" /> + file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_move_base_common_params.yaml" /> + file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_move_base_$(env ROS_DISTRO)_params.yaml" /> diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_amcl_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_amcl_common_params.yaml similarity index 100% rename from jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_amcl_common_params.yaml rename to jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_amcl_common_params.yaml diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_amcl_indigo_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_amcl_indigo_params.yaml similarity index 100% rename from jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_amcl_indigo_params.yaml rename to jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_amcl_indigo_params.yaml diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_amcl_melodic_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_amcl_melodic_params.yaml similarity index 100% rename from jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_amcl_melodic_params.yaml rename to jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_amcl_melodic_params.yaml 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 new file mode 100644 index 0000000000..e69de29bb2 diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_move_base_indigo_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_indigo_params.yaml similarity index 100% rename from jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_move_base_indigo_params.yaml rename to jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_indigo_params.yaml diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_melodic_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_melodic_params.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_amcl_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_amcl_common_params.yaml new file mode 100644 index 0000000000..0d91503d3e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_amcl_common_params.yaml @@ -0,0 +1,7 @@ +amcl: + update_min_a: 0.05 # update filter every 0.05 [rad] rotation + update_min_d: 0.1 # update filter every 0.1 [m] translation + odom_alpha1: 0.1 # rotation noise per rotation + odom_alpha2: 0.05 # rotation noise per translation + odom_alpha3: 0.05 # translation noise per translation + odom_alpha4: 0.1 # translation noise per rotation diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_amcl_indigo_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_amcl_indigo_params.yaml new file mode 100644 index 0000000000..415958d1d2 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_amcl_indigo_params.yaml @@ -0,0 +1,8 @@ +amcl: + kld_err: 0.1 + kld_z: 0.5 + laser_z_hit: 0.9 + laser_z_rand: 0.5 + laser_sigma_hit: 0.1 + laser_likelihood_max_dist: 4.0 + resample_interval: 1 diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_amcl_melodic_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_amcl_melodic_params.yaml new file mode 100644 index 0000000000..e9afd45afc --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_amcl_melodic_params.yaml @@ -0,0 +1,7 @@ +amcl: + update_min_a: 0.05 # update filter every 0.05 [rad] rotation + update_min_d: 0.1 # update filter every 0.1 [m] translation + odom_alpha1: 0.01 # rotation noise per rotation + odom_alpha2: 0.01 # rotation noise per translation + odom_alpha3: 0.01 # translation noise per translation + odom_alpha4: 0.01 # translation noise per rotation diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_move_base_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml similarity index 88% rename from jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_move_base_common_params.yaml rename to jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml index 30e9553358..9da82ce6e2 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_move_base_common_params.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml @@ -2,27 +2,21 @@ move_base: controller_frequency: 20.0 global_costmap: inflater: - inflation_radius: 0.7 # 0.7 + inflation_radius: 1.0 # 0.7 cost_scaling_factor: 10.0 # 10.0 obstacles: min_obstacle_height: 0.05 footprint_padding: 0.05 - # By reducing update/publish_frequency, move_base control loop rate will be improved - # https://moriokalab.com/news/84 - update_frequency: 1.0 - publish_frequency: 0.5 + publish_frequency: 1.0 local_costmap: inflater: - inflation_radius: 0.35 # 0.7 + 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 - # By reducing update/publish_frequency, move_base control loop rate will be improved - # https://moriokalab.com/news/84 - update_frequency: 1.0 - publish_frequency: 0.5 + update_frequency: 5.0 base_global_planner: global_planner/GlobalPlanner base_local_planner: teb_local_planner/TebLocalPlannerROS # base_local_planner: base_local_planner/TrajectoryPlannerROS @@ -59,8 +53,6 @@ move_base: teb_autosize: True dt_ref: 0.3 dt_hysteresis: 0.1 - # By reducing max_samples, move_base control loop rate will be improved - max_samples: 50 # default 500 global_plan_overwrite_orientation: True max_global_plan_lookahead_dist: 3.0 feasibility_check_no_poses: 5 @@ -79,7 +71,7 @@ move_base: yaw_goal_tolerance: 0.1 free_goal_vel: False # Obstacles - min_obstacle_dist: 0.4 # Enough value not to go too close to obstacle + min_obstacle_dist: 0.1 include_costmap_obstacles: True costmap_obstacles_behind_robot_dist: 1.0 obstacle_poses_afected: 30 diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_indigo_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_indigo_params.yaml new file mode 100644 index 0000000000..3858131bf6 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_indigo_params.yaml @@ -0,0 +1,3 @@ +move_base: + global_costmap: + update_frequency: 2.0 diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_move_base_melodic_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_melodic_params.yaml similarity index 100% rename from jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch_move_base_melodic_params.yaml rename to jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_melodic_params.yaml 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 c9dd328809..b396753ac6 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch @@ -16,9 +16,9 @@ /odom /odom_combined /cmd_vel - /move_base/NavFnROS/plan - /move_base/TrajectoryPlannerROS/global_plan - /move_base/TrajectoryPlannerROS/local_plan + /move_base/navigation_plan_viz + /move_base/global_plan_viz + /move_base/local_plan_viz /move_base/global_costmap/footprint /spots_marker_array /spots_pictogram 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 b0553995f0..8d5fe6f077 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 && if [ -d /usr/vt ]; then VOICE_TEXT=true; else VOICE_TEXT=false; fi && roslaunch jsk_fetch_startup fetch_bringup.launch boot_sound:=true use_voice_text:=$VOICE_TEXT --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && if [ -d /usr/vt ]; then VOICE_TEXT=true; else VOICE_TEXT=false; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true use_voice_text:=$VOICE_TEXT --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true