Skip to content

Commit

Permalink
track configurations
Browse files Browse the repository at this point in the history
  • Loading branch information
qev3-d committed May 15, 2024
1 parent 9e9c2d7 commit 8e4e37b
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 7 deletions.
4 changes: 2 additions & 2 deletions src/navigation/nav_bringup/config/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -198,11 +198,11 @@ controller_server:
# Controller parameters
RegulatedPurePursuit:
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
desired_linear_vel: 4.0 # The desired maximum linear velocity to use.
desired_linear_vel: 3.0 # The desired maximum linear velocity to use.
lookahead_dist: 4.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.
lookahead_time: 1.5 # The time to project the velocity by to find the velocity scaled lookahead distance. Also known as the lookahead gain.
lookahead_time: 2.0 # 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: false # Whether to use the velocity scaled lookahead distances or constant lookahead_distance.
Expand Down
10 changes: 5 additions & 5 deletions src/navigation/nav_bringup/config/slam_toolbox_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,13 @@ slam_toolbox_node:
# map_start_pose: [0.0, 0.0, 0.0] # Pose to start pose-graph mapping/localization in, if available
debug_logging: false # Change logger to debug
throttle_scans: 1 # Number of scans to throttle in synchronous mode
transform_publish_period: 0.02 # The map to odom transform publish period. 0 will not publish transforms
map_update_interval: 2.0 # Interval to update the 2D occupancy map for other applications / visualization
transform_publish_period: 0.01 # The map to odom transform publish period. 0 will not publish transforms
map_update_interval: 3.0 # Interval to update the 2D occupancy map for other applications / visualization
enable_interactive_mode: false # Interactive mode will retain a cache of laser scans mapped to their ID for visualization in interactive mode
position_covariance_scale: 1.0 # This can be used to tune the influence of the pose position in a downstream localization filter
position_covariance_scale: 1.5 # This can be used to tune the influence of the pose position in a downstream localization filter
yaw_covariance_scale: 1.0 # Pose yaw
resolution: 0.1 # Resolution of the 2D occupancy map to generate
max_laser_range: 50.0 # Maximum laser range to use for 2D occupancy map rastering
resolution: 0.15 # Resolution of the 2D occupancy map to generate
max_laser_range: 35.0 # Maximum laser range to use for 2D occupancy map rastering
minimum_time_interval: 0.5 # The minimum duration of time between scans to be processed in synchronous mode
transform_timeout: 0.5 # TF timeout for looking up transforms
tf_buffer_duration: 0.1 # Duration to store TF messages for lookup. Set high if running offline at multiple times speed in synchronous mode
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
from std_srvs.srv import Trigger

from driverless_common.shutdown_node import ShutdownNode
from rclpy.node import Node


class TrackdriveHandler(ShutdownNode):
Expand Down

0 comments on commit 8e4e37b

Please sign in to comment.