Skip to content

Commit b9288ee

Browse files
committed
fix param for real robot
1 parent 8860979 commit b9288ee

File tree

4 files changed

+6
-7
lines changed

4 files changed

+6
-7
lines changed

jsk_hrp2jsknts_robot/jsk_hrp2jsknts_startup/jsk_hrp2jsknts_move_base/global_costmap_params.yaml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,9 +7,9 @@ global_costmap:
77
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
88
global_frame: map ## The global frame for the costmap to operate in.
99
robot_base_frame: base_footprint ## The name of the frame for the base link of the robot.
10-
transform_tolerance: 2.0 ## Specifies the delay in transform (tf) data that is tolerable in seconds.
11-
update_frequency: 1.0 ## The frequency in Hz for the map to be updated.
12-
publish_frequency: 1.0 ## The frequency in Hz for the map to be publish display information.
10+
transform_tolerance: 3.0 ## Specifies the delay in transform (tf) data that is tolerable in seconds. # rtabmapの更新速度が遅いので3.0にする
11+
update_frequency: 0.5 ## The frequency in Hz for the map to be updated. # rtabmapの更新速度が遅いので0.5hzにする
12+
publish_frequency: 0.5 ## The frequency in Hz for the map to be publish display information. # rtabmapの更新速度が遅いので0.5hzにする
1313
rolling_window: false ## Whether or not to use a rolling window version of the costmap. If the static_map parameter is set to true, this parameter must be set to false.
1414
always_send_full_costmap: false ## If true the full costmap is published to "~<name>/costmap" every update. If false only the part of the costmap that has changed is published on the "~<name>/costmap_updates" topic.
1515

jsk_hrp2jsknts_robot/jsk_hrp2jsknts_startup/jsk_hrp2jsknts_move_base/global_map.launch

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,8 +23,7 @@
2323
odom_frame_id: odom #最初のodomの原点がmapの原点になる。2次元地図を使用する場合は、mapのXY平面に対して射影が行われるが、このとき、Z成分が負の点やGrid/MaxObstacleHeightより大きい点はobstacleとしては無視される。そのため、最初のodomの原点のZ高さに注意を払う必要がある。
2424

2525
map_always_update: true ## 立ち止まった時にもアップデート
26-
# wait_for_transform: true
27-
# wait_for_transform_duration: 0.5
26+
wait_for_transform_duration: 0.5 ## 通信遅延に対応するため
2827

2928
Grid/RayTracing: true ## octomap_occupied_space にray tracingが適用される
3029
Grid/CellSize: 0.02

jsk_hrp2jsknts_robot/jsk_hrp2jsknts_startup/jsk_hrp2jsknts_move_base/local_costmap_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@ local_costmap:
55
- {name: static_layer, type: "costmap_2d::StaticLayer"}
66
robot_base_frame: base_footprint ## The name of the frame for the base link of the robot.
77
global_frame: odom ## The global frame for the costmap to operate in.
8-
transform_tolerance: 2.0 ## Specifies the delay in transform (tf) data that is tolerable in seconds.
8+
transform_tolerance: 3.0 ## Specifies the delay in transform (tf) data that is tolerable in seconds. # 通信遅延に対応
99
update_frequency: 2.0 ## The frequency in Hz for the map to be updated.
1010
publish_frequency: 2.0 ## The frequency in Hz for the map to be publish display information.
1111
rolling_window: false ## Whether or not to use a rolling window version of the costmap. If the static_map parameter is set to true, this parameter must be set to false.

jsk_hrp2jsknts_robot/jsk_hrp2jsknts_startup/jsk_hrp2jsknts_move_base/teb_local_planner_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ TebLocalPlannerROS:
3030
exact_arc_length: false ## If true, the planner uses the exact arc length in velocity, acceleration and turning rate computations (-> increased cpu time), otherwise the Euclidean approximation is used. ## hrpsysの中のgo-velocityはexectではない(false).
3131
shrink_horizon_min_duration: 3.0 ## Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected (refer to parameter shrink_horizon_backup in order to activate the reduced horizon mode).
3232

33-
min_obstacle_dist: 0.25 ## Minimum desired separation from obstacles in meters ## mapのfootprintは使われず、footprint_modelが参照されることに注意. obstacle_association_cutoff_factor や obstacle_association_force_inclusion_factor に影響する
33+
min_obstacle_dist: 0.30 ## Minimum desired separation from obstacles in meters ## mapのfootprintは使われず、footprint_modelが参照されることに注意. obstacle_association_cutoff_factor や obstacle_association_force_inclusion_factor に影響する
3434
include_costmap_obstacles: True ## Specify if obstacles of the local costmap should be taken into account. Each cell that is marked as obstacle is considered as a point-obstacle. Therefore do not choose a very small resolution of the costmap since it increases computation time. In future releases this circumstance is going to be addressed as well as providing an additional api for dynamic obstacles.
3535
costmap_obstacles_behind_robot_dist: 2.0 ## Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters).
3636
obstacle_poses_affected: 10 ## Each obstacle position is attached to the closest pose on the trajectory in order to keep a distance. Additional neighbors can be taken into account as well. Note, this parameter might be removed in future versions, since the the obstacle association strategy has been modified in kinetic+. Refer to the parameter description of legacy_obstacle_association.

0 commit comments

Comments
 (0)