Skip to content

Commit

Permalink
Track day 18/10 - tuning parameters
Browse files Browse the repository at this point in the history
  • Loading branch information
qev3-d authored and b1n-ch1kn committed Oct 19, 2024
1 parent c79a2a8 commit 02caff4
Show file tree
Hide file tree
Showing 11 changed files with 119 additions and 37 deletions.
47 changes: 47 additions & 0 deletions src/machines/roscube_machine/launch/foxglove.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@

from launch import LaunchDescription
from launch_ros.actions import Node


def generate_launch_description():
return LaunchDescription(
[
Node(
package="foxglove_bridge",
executable="foxglove_bridge",
output="screen",
parameters=[
{"port": 8765},
{"address": "0.0.0.0"},
{"tls": False},
{"certfile": ""},
{"keyfile": ""},
{"topic_whitelist": [".*"]},
{"param_whitelist": [".*"]},
{"service_whitelist": [".*"]},
{"client_topic_whitelist": [".*"]},
{"min_qos_depth": 1},
{"max_qos_depth": 10},
{"num_threads": 0},
{"send_buffer_limit": 10000000},
{"use_sim_time": False},
{
"capabilities": [
"clientPublish",
"parameters",
"parametersSubscribe",
"services",
"connectionGraph",
"assets",
]
},
{"include_hidden": False},
{
"asset_uri_allowlist": [
"^package://(?:\\w+/)*\\w+\\.(?:dae|fbx|glb|gltf|jpeg|jpg|mtl|obj|png|stl|tif|tiff|urdf|webp|xacro)$"
]
},
],
)
]
)
41 changes: 37 additions & 4 deletions src/machines/roscube_machine/launch/machine.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,43 @@ def generate_launch_description():
package="rosboard",
executable="rosboard_node",
),
Node(
package="foxglove_bridge",
executable="foxglove_bridge",
),
# Node(
# package="foxglove_bridge",
# executable="foxglove_bridge",
# output="screen",
# parameters=[
# {"port": 8765},
# {"address": "0.0.0.0"},
# {"tls": False},
# {"certfile": ""},
# {"keyfile": ""},
# {"topic_whitelist": [".*"]},
# {"param_whitelist": [".*"]},
# {"service_whitelist": [".*"]},
# {"client_topic_whitelist": [".*"]},
# {"min_qos_depth": 1},
# {"max_qos_depth": 10},
# {"num_threads": 0},
# {"send_buffer_limit": 1000000000},
# {"use_sim_time": False},
# {
# "capabilities": [
# "clientPublish",
# "parameters",
# "parametersSubscribe",
# "services",
# "connectionGraph",
# "assets",
# ]
# },
# {"include_hidden": False},
# {
# "asset_uri_allowlist": [
# "^package://(?:\\w+/)*\\w+\\.(?:dae|fbx|glb|gltf|jpeg|jpg|mtl|obj|png|stl|tif|tiff|urdf|webp|xacro)$"
# ]
# },
# ],
# ),
Node(
package="driverless_common",
executable="display",
Expand Down
1 change: 1 addition & 0 deletions src/machines/roscube_machine/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
<depend>mission_controller</depend>
<depend>odom_transformer</depend>
<depend>sbg_driver</depend>
<depend>map_creation</depend>

<exec_depend>ros2launch</exec_depend>

Expand Down
12 changes: 6 additions & 6 deletions src/navigation/nav_bringup/config/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -231,9 +231,9 @@ controller_server:
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
desired_linear_vel: 4.5 # The desired maximum linear velocity to use.
lookahead_dist: 6.0 # The lookahead distance to use to find the lookahead point.
min_lookahead_dist: 5.0 # The minimum lookahead distance threshold when using velocity scaled lookahead distances.
max_lookahead_dist: 7.0 # The maximum lookahead distance threshold when using velocity scaled lookahead distances.
lookahead_time: 2.0 # The time to project the velocity by to find the velocity scaled lookahead distance. Also known as the lookahead gain.
min_lookahead_dist: 4.0 # The minimum lookahead distance threshold when using velocity scaled lookahead distances.
max_lookahead_dist: 8.0 # The maximum lookahead distance threshold when using velocity scaled lookahead distances.
lookahead_time: 2.5 # The time to project the velocity by to find the velocity scaled lookahead distance. Also known as the lookahead gain.
# rotate_to_heading_angular_vel: 1.8 # If rotate to heading is used, this is the angular velocity to use.
transform_tolerance: 0.3 # The TF transform tolerance.
use_velocity_scaled_lookahead_dist: true # Whether to use the velocity scaled lookahead distances or constant lookahead_distance.
Expand All @@ -248,9 +248,9 @@ controller_server:
# inflation_cost_scaling_factor: 0.5 # The value of cost_scaling_factor set for the inflation layer in the local costmap.
# The value should be exactly the same for accurately computing distance from obstacles using the inflated cell values
regulated_linear_scaling_min_radius: 7.0 # The turning radius for which the regulation features are triggered.
regulated_linear_scaling_min_speed: 3.0 # The minimum speed for which the regulated features can send, to ensure process is still achievable even in high cost spaces with high curvature.
regulated_linear_scaling_min_speed: 3.5 # The minimum speed for which the regulated features can send, to ensure process is still achievable even in high cost spaces with high curvature.
use_fixed_curvature_lookahead: true # Enable fixed lookahead for curvature detection. Useful for systems with long lookahead.
curvature_lookahead_dist: 2.0 # Distance to lookahead to determine curvature for velocity regulation purposes if use_fixed_curvature_lookahead is enabled.
curvature_lookahead_dist: 5.0 # Distance to lookahead to determine curvature for velocity regulation purposes if use_fixed_curvature_lookahead is enabled.
use_rotate_to_heading: false # Whether to enable rotating to rough heading and goal orientation when using holonomic planners.
# rotate_to_heading_min_angle: 0.785 # The difference in the path orientation and the starting robot orientation to trigger a rotate in place, if use_rotate_to_heading is enabled.
# max_angular_accel: 6.0 # Maximum allowable angular acceleration while rotating to heading, if enabled.
Expand All @@ -259,7 +259,7 @@ controller_server:

EBSTestRPP:
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
desired_linear_vel: 12.0 # The desired maximum linear velocity to use.
desired_linear_vel: 10.0 # The desired maximum linear velocity to use.
lookahead_dist: 6.0 # The lookahead distance to use to find the lookahead point.
# min_lookahead_dist: 3.0 # The minimum lookahead distance threshold when using velocity scaled lookahead distances.
# max_lookahead_dist: 5.0 # The maximum lookahead distance threshold when using velocity scaled lookahead distances.
Expand Down
2 changes: 1 addition & 1 deletion src/navigation/nav_bringup/config/slam_toolbox_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ slam_toolbox_node:
minimum_travel_distance: 0.1 # Minimum distance of travel before processing a new scan
minimum_travel_heading: 0.05 # Minimum changing in heading to justify an update

scan_buffer_size: 1000 # The number of scans to buffer into a chain, also used as the number of scans in the circular buffer of localization mode
scan_buffer_size: 500 # The number of scans to buffer into a chain, also used as the number of scans in the circular buffer of localization mode
# Approx 500 in pit track, 800 in skidpad track
scan_buffer_maximum_scan_distance: 100.0 # Maximum distance of a scan from the pose before removing the scan from the buffer
# Skidpad track approx 50m diam
Expand Down
2 changes: 1 addition & 1 deletion src/navigation/planners/config/ft_planner.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ ft_planner_node:
mpc_path_length: 20
mpc_prediction_horizon: 40

min_track_width: 3.3
min_track_width: 2.9
max_search_range: 5
max_search_angle: 45
matches_should_be_monotonic: True
14 changes: 7 additions & 7 deletions src/operations/mission_controller/launch/ebs_test.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,13 @@ def generate_launch_description():
)
),
# mapping/planning
# Node(
# package="map_creation",
# executable="cone_placement_node",
# parameters=[
# get_package_share_path("map_creation") / "config" / "cone_placement.yaml",
# ],
# ),
Node(
package="map_creation",
executable="cone_placement_node",
parameters=[
get_package_share_path("map_creation") / "config" / "cone_placement.yaml",
],
),
Node(
package="slam_gridmap",
executable="gridmap_to_cone_detection_node",
Expand Down
16 changes: 8 additions & 8 deletions src/operations/mission_controller/launch/trackdrive.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,13 @@ def generate_launch_description():
)
),
# mapping/planning
# Node(
# package="map_creation",
# executable="cone_placement_node",
# parameters=[
# get_package_share_path("map_creation") / "config" / "cone_placement.yaml",
# ],
# ),
Node(
package="map_creation",
executable="cone_placement_node",
parameters=[
get_package_share_path("map_creation") / "config" / "cone_placement.yaml",
],
),
Node(
package="slam_gridmap",
executable="gridmap_to_cone_detection_node",
Expand All @@ -41,7 +41,7 @@ def generate_launch_description():
],
ros_arguments=[
"-p",
"topic_name:=slam/cone_detection",
"topic_name:=slam/global_map",
"-p",
"target_frame:=track",
],
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ def timer_callback(self):
self.controller_id = "TrackdriveRPPFast"

# we have finished lap "10"
if self.laps == 10:
if self.laps == 11:
self.get_logger().info("Trackdrive mission complete")
# currently only works when vehicle supervisor node is running on-car
# TODO: sort out vehicle states for eventual environment agnostic operation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ def generate_launch_description():
pointcloud_to_laserscan_node = Node(
package="pointcloud_to_laserscan",
executable="pointcloud_to_laserscan_node",
name="pointcloud_to_laserscan_node",
output="screen",
parameters=[
os.path.join(pkg_share, "config", "laserscan_params.yaml"),
Expand Down
18 changes: 9 additions & 9 deletions tools/play_bag.sh
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ source install/setup.bash
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_07_25-03_24_19/ --clock -p" # lidar on roll hoop test
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_07_25-05_04_46/ --clock -p" # half lap
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_07_25-05_18_42/ --clock -p" # other half of lap
BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_09_04-05_14_43/ --clock -p" # 2.5 laps
BAG_CMD="ros2 bag play -s mcap src/rosbag2_2024_10_17-01_36_17 -p" # 2.5 laps
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_09_24-06_08_59/ --clock -p" # 1 lap, loop close crashing
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_09_24-02_16_55/ --clock -p" # ebs test run

Expand All @@ -21,14 +21,14 @@ REMAPPINGS=(
)

TOPICS=(
/imu/odometry # needed for RL
/vehicle/wheel_twist # needed for RL
# /lidar/objects
/lidar/converted_2D_scan
/lidar/cone_detection
# /debug_markers/lidar_markers
/system/as_status # needed for lap = 0 in mapping
# /imu/nav_sat_fix # for visual
# /imu/odometry # needed for RL
# /vehicle/wheel_twist # needed for RL
# # /lidar/objects
# /lidar/converted_2D_scan
# /lidar/cone_detection
# # /debug_markers/lidar_markers
# /system/as_status # needed for lap = 0 in mapping
# # /imu/nav_sat_fix # for visual
)

# remap these topics if you are running programs which output to the same topic names
Expand Down

0 comments on commit 02caff4

Please sign in to comment.