Skip to content

Commit

Permalink
PR review changes
Browse files Browse the repository at this point in the history
  • Loading branch information
b1n-ch1kn committed Sep 17, 2024
1 parent 5694283 commit 266d8aa
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 8 deletions.
2 changes: 1 addition & 1 deletion src/hardware/steering_actuator/config/steering.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ steering_actuator_node:
centre_range: 2.0
centre_angle: -8.0
settling_iter: 50
max_position: 2000
max_position: 8500
Kp: 10.0
Ki: 0.0
Kd: 0.0
8 changes: 4 additions & 4 deletions src/machines/roscube_machine/launch/machine.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,10 +76,10 @@ def generate_launch_description():
)
),
),
# Node(
# package="mission_controller",
# executable="mission_launcher_node",
# ),
Node(
package="mission_controller",
executable="mission_launcher_node",
),
IncludeLaunchDescription(
launch_description_source=PythonLaunchDescriptionSource(
launch_file_path=str(get_package_share_path("sensors") / "launch" / "vlp32.launch.py")
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 @@ -20,7 +20,7 @@ slam_toolbox_node:
scan_queue_size: 1 # The number of scan messages to queue up before throwing away old ones. Should always be set to 1 in async mode
use_map_saver: false # Instantiate the map saver service and self-subscribe to the map topic
# map_start_pose: [0.0, 0.0, 0.0] # Pose to start pose-graph mapping/localization in, if available
debug_logging: true # Change logger to debug
debug_logging: false # Change logger to debug
throttle_scans: 1 # Number of scans to throttle in synchronous mode
transform_publish_period: 0.05 # 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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,10 +62,28 @@ def __init__(self):
]
self.get_logger().info(f"Running Command: {' '.join(command)}")
cmd = Popen(command)
command = ["stdbuf", "-o", "L", "ros2", "param", "set", "steering_actuator_node", "max_position", "2000"]
command = [
"stdbuf",
"-o",
"L",
"ros2",
"param",
"set",
"steering_actuator_node",
"max_position",
"2000",
]
self.get_logger().info(f"Running Command: {' '.join(command)}")
cmd = Popen(command)
command = ["stdbuf", "-o", "L", "ros2", "launch", "mission_controller", "ebs_test.launch.py"]
command = [
"stdbuf",
"-o",
"L",
"ros2",
"launch",
"mission_controller",
"ebs_test.launch.py",
]
self.get_logger().info(f"Running Command: {' '.join(command)}")
self.process = Popen(command)
self.get_logger().info("EBS mission started")
Expand Down

0 comments on commit 266d8aa

Please sign in to comment.