Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[WIP] Fast go to kitchen #126

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
6 changes: 3 additions & 3 deletions jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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
Expand Down
14 changes: 8 additions & 6 deletions jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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))))
Expand Down Expand Up @@ -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))
Expand Down Expand Up @@ -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
Expand Down
28 changes: 24 additions & 4 deletions jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
<launch>
<arg name="hostname" default="fetch15" />
<arg name="launch_moveit" default="true" />
<arg name="launch_teleop" default="true" />
<arg name="launch_move_base" default="true" />
Expand Down Expand Up @@ -207,17 +208,36 @@
<arg name="launch_map_server" value="false" />
<arg name="odom_topic" value="/odom_combined" />
</include>
<!-- relay plan path topic for visualization -->
<node name="relay_navfn_planner_plan"
pkg="topic_tools" type="relay"
args="/move_base/NavfnROS/plan /move_base/navigation_plan_viz" />
<node name="relay_global_planner_plan"
pkg="topic_tools" type="relay"
args="/move_base/GlobalPlanner/plan /move_base/navigation_plan_viz" />
<node name="relay_trajectory_planner_global_plan"
pkg="topic_tools" type="relay"
args="/move_base/TrajectoryPlannerROS/global_plan /move_base/global_plan_viz" />
<node name="relay_trajectory_planner_local_plan"
pkg="topic_tools" type="relay"
args="/move_base/TrajectoryPlannerROS/local_plan /move_base/local_plan_viz" />
<node name="relay_teb_planner_global_plan"
pkg="topic_tools" type="relay"
args="/move_base/TebLocalPlannerROS/global_plan /move_base/global_plan_viz" />
<node name="relay_teb_planner_local_plan"
pkg="topic_tools" type="relay"
args="/move_base/TebLocalPlannerROS/local_plan /move_base/local_plan_viz" />

<!-- load amcl params -->
<rosparam command="load"
file="$(find jsk_fetch_startup)/launch/navigation/fetch_amcl_common_params.yaml" />
file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_amcl_common_params.yaml" />
<rosparam command="load"
file="$(find jsk_fetch_startup)/launch/navigation/fetch_amcl_$(env ROS_DISTRO)_params.yaml" />
file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_amcl_$(env ROS_DISTRO)_params.yaml" />
<!-- load move_base params -->
<rosparam command="load"
file="$(find jsk_fetch_startup)/launch/navigation/fetch_move_base_common_params.yaml" />
file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_move_base_common_params.yaml" />
<rosparam command="load"
file="$(find jsk_fetch_startup)/launch/navigation/fetch_move_base_$(env ROS_DISTRO)_params.yaml" />
file="$(find jsk_fetch_startup)/launch/navigation/$(arg hostname)/fetch_move_base_$(env ROS_DISTRO)_params.yaml" />
</group>

<!-- slam for build a map -->
Expand Down
Original file line number Diff line number Diff line change
@@ -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
Original file line number Diff line number Diff line change
@@ -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
Original file line number Diff line number Diff line change
@@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
move_base:
global_costmap:
update_frequency: 2.0
6 changes: 3 additions & 3 deletions jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
@@ -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
Expand Down