Skip to content

Commit

Permalink
code cleanup
Browse files Browse the repository at this point in the history
Signed-off-by: stevedan <[email protected]>
  • Loading branch information
stevedanomodolor committed Oct 10, 2024
1 parent 5ce2c7e commit fe5dc61
Show file tree
Hide file tree
Showing 6 changed files with 4 additions and 66 deletions.
62 changes: 1 addition & 61 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,6 @@ bt_navigator:
controller_server:
ros__parameters:
controller_frequency: 20.0
costmap_update_timeout: 0.30
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
Expand Down Expand Up @@ -99,10 +98,6 @@ controller_server:
time_steps: 56
model_dt: 0.05
batch_size: 2000
ax_max: 3.0
ax_min: -3.0
ay_max: 3.0
az_max: 3.5
vx_std: 0.2
vy_std: 0.2
wz_std: 0.4
Expand Down Expand Up @@ -277,7 +272,6 @@ planner_server:
ros__parameters:
expected_planner_frequency: 20.0
planner_plugins: ["GridBased"]
costmap_update_timeout: 1.0
GridBased:
plugin: "nav2_navfn_planner::NavfnPlanner"
tolerance: 0.5
Expand Down Expand Up @@ -374,58 +368,4 @@ collision_monitor:
topic: "scan"
min_height: 0.15
max_height: 2.0
enabled: True

docking_server:
ros__parameters:
controller_frequency: 50.0
initial_perception_timeout: 5.0
wait_charge_timeout: 5.0
dock_approach_timeout: 30.0
undock_linear_tolerance: 0.05
undock_angular_tolerance: 0.1
max_retries: 3
base_frame: "base_link"
fixed_frame: "odom"
dock_backwards: false
dock_prestaging_tolerance: 0.5

# Types of docks
dock_plugins: ['simple_charging_dock']
simple_charging_dock:
plugin: 'opennav_docking::SimpleChargingDock'
docking_threshold: 0.05
staging_x_offset: -0.7
use_external_detection_pose: true
use_battery_status: false # true
use_stall_detection: false # true

external_detection_timeout: 1.0
external_detection_translation_x: -0.18
external_detection_translation_y: 0.0
external_detection_rotation_roll: -1.57
external_detection_rotation_pitch: -1.57
external_detection_rotation_yaw: 0.0
filter_coef: 0.1

# Dock instances
# The following example illustrates configuring dock instances.
# docks: ['home_dock'] # Input your docks here
# home_dock:
# type: 'simple_charging_dock'
# frame: map
# pose: [0.0, 0.0, 0.0]

controller:
k_phi: 3.0
k_delta: 2.0
v_linear_min: 0.15
v_linear_max: 0.15

loopback_simulator:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
map_frame_id: "map"
scan_frame_id: "base_scan" # tb4_loopback_simulator.launch.py remaps to 'rplidar_link'
update_duration: 0.02
enabled: True
4 changes: 2 additions & 2 deletions nav2_bringup/rviz/nav2_default_view.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@ Panels:
Name: Navigation 2
- Class: nav2_rviz_plugins/Selector
Name: Selector
# - Class: nav2_rviz_plugins/Docking
# Name: Docking
- Class: nav2_rviz_plugins/Docking
Name: Docking
Visualization Manager:
Class: ""
Displays:
Expand Down
1 change: 0 additions & 1 deletion nav2_rviz_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ find_package(tf2_geometry_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
find_package(yaml-cpp REQUIRED)
find_package(backward_ros REQUIRED)

nav2_package()

Expand Down
1 change: 0 additions & 1 deletion nav2_rviz_plugins/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
<depend>tf2_geometry_msgs</depend>
<depend>visualization_msgs</depend>
<depend>yaml_cpp_vendor</depend>
<depend>backward_ros</depend>

<exec_depend>libqt5-core</exec_depend>
<exec_depend>libqt5-gui</exec_depend>
Expand Down
2 changes: 1 addition & 1 deletion tools/planner_benchmarking/metrics.py
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ def main():
costmap = np.asarray(costmap_msg.data)
costmap.resize(costmap_msg.metadata.size_y, costmap_msg.metadata.size_x)

planners = ["DEFAULT_Smac2d", "BIDIRECTIONAL_Smac2d", "ALL_DIRECTION_Smac2d", "DEFAULT_SmacHybrid", "BIDIRECTIONAL_SmacHybrid", "ALL_DIRECTION_SmacHybrid", "DEFAULT_SmacLattice", "BIDIRECTIONAL_SmacLattice", "ALL_DIRECTION_SmacLattice"]
planners = ['Navfn', 'ThetaStar', 'SmacHybrid', 'Smac2d', 'SmacLattice']
max_cost = 210
side_buffer = 100
time_stamp = navigator.get_clock().now().to_msg()
Expand Down
Binary file removed tools/planner_benchmarking/planners.pickle
Binary file not shown.

0 comments on commit fe5dc61

Please sign in to comment.