-
Notifications
You must be signed in to change notification settings - Fork 13
add mission launch files #116
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Merged
Merged
Changes from all commits
Commits
Show all changes
3 commits
Select commit
Hold shift + click to select a range
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,156 @@ | ||
| # bringup | ||
|
|
||
| Mission-level launch files for Athena. Each file composes subsystem launches for a specific competition mission. | ||
|
|
||
| ## Modes | ||
|
|
||
| | Mode | What runs | | ||
| |---|---| | ||
| | `jetson` | Hardware and compute nodes — run on the rover | | ||
| | `base_station` | Operator teleop nodes — run on the laptop | | ||
| | `standalone` | Everything on one machine (default, for development) | | ||
|
|
||
| --- | ||
|
|
||
| ## Delivery | ||
|
|
||
| Drive + Arm + GPS + Heading | ||
|
|
||
| ```bash | ||
| # Rover | ||
| ros2 launch bringup delivery.launch.py mode:=jetson | ||
|
|
||
| # Operator laptop | ||
| ros2 launch bringup delivery.launch.py mode:=base_station | ||
|
|
||
| # Single machine | ||
| ros2 launch bringup delivery.launch.py | ||
|
|
||
| # Mock hardware (no physical rover) | ||
| ros2 launch bringup delivery.launch.py use_mock_hardware:=true use_sim:=true | ||
|
|
||
| # 3 DOF wrist | ||
| ros2 launch bringup delivery.launch.py use_3dof:=true | ||
| ``` | ||
|
|
||
| ### Parameters | ||
|
|
||
| | Parameter | Default | Choices | Description | | ||
| |---|---|---|---| | ||
| | `mode` | `standalone` | `standalone` `jetson` `base_station` | Deployment target | | ||
| | `use_sim` | `false` | `true` `false` | Launch RViz2 | | ||
| | `use_mock_hardware` | `false` | `true` `false` | Mock hardware for drive and arm | | ||
| | `mock_sensor_commands` | `false` | `true` `false` | Mock sensor command interfaces (requires `use_mock_hardware`) | | ||
| | `robot_controller` | `rear_ackermann_controller` | `rear_ackermann_controller` `front_ackermann_controller` `ackermann_steering_controller` | Drive controller to start | | ||
| | `use_3dof` | `false` | `true` `false` | Enable 3 DOF wrist joints on arm | | ||
| | `deactivate_talon` | `false` | `true` `false` | Deactivate talon joints in URDF (use with `use_mock_hardware` to prevent CAN traffic) | | ||
|
|
||
| --- | ||
|
|
||
| ## Autonomous Navigation | ||
|
|
||
| Drive + Nav2 + ZED + GPS + Localizer + Heading | ||
|
|
||
| ```bash | ||
| # Rover | ||
| ros2 launch bringup autonav.launch.py mode:=jetson | ||
|
|
||
| # Operator laptop | ||
| ros2 launch bringup autonav.launch.py mode:=base_station | ||
|
|
||
| # Single machine | ||
| ros2 launch bringup autonav.launch.py | ||
|
|
||
| # Use EKF localizer instead of ZED spatial localization | ||
| ros2 launch bringup autonav.launch.py use_zed_localizer:=false | ||
|
|
||
| # Disable GNSS fusion in ZED | ||
| ros2 launch bringup autonav.launch.py enable_gnss:=false | ||
|
|
||
| # Custom Nav2 params | ||
| ros2 launch bringup autonav.launch.py params_file:=/path/to/params.yaml | ||
|
|
||
| # Debug nav2 verbosity | ||
| ros2 launch bringup autonav.launch.py log_level:=debug | ||
| ``` | ||
|
|
||
| ### Parameters | ||
|
|
||
| | Parameter | Default | Choices | Description | | ||
| |---|---|---|---| | ||
| | `mode` | `standalone` | `standalone` `jetson` `base_station` | Deployment target | | ||
| | `use_sim` | `false` | `true` `false` | Enable sim time and RViz2 | | ||
| | `use_mock_hardware` | `false` | `true` `false` | Mock hardware for drive | | ||
| | `mock_sensor_commands` | `false` | `true` `false` | Mock sensor command interfaces (requires `use_mock_hardware`) | | ||
| | `robot_controller` | `rear_ackermann_controller` | `rear_ackermann_controller` `front_ackermann_controller` `ackermann_steering_controller` | Drive controller to start | | ||
| | `use_zed_localizer` | `true` | `true` `false` | Use ZED spatial localization instead of EKF localizer | | ||
| | `enable_gnss` | `true` | `true` `false` | Enable GNSS fusion inside the ZED camera | | ||
| | `use_minimal` | `false` | `true` `false` | Use minimal Nav2 config (empty costmaps, basic BT) for ackermann testing | | ||
| | `params_file` | `nav2_params.yaml` (or `nav2_params_minimal.yaml` when `use_minimal:=true`) | — | Full path to Nav2 params YAML; overrides `use_minimal` if set explicitly | | ||
| | `use_dem` | `false` | `true` `false` | Enable DEM costmap layer | | ||
| | `use_respawn` | `false` | `true` `false` | Respawn nav2 nodes on crash | | ||
| | `log_level` | `info` | — | Log level for nav2 nodes | | ||
| | `use_config` | `false` | `true` `false` | Launch the Nav2 config GUI | | ||
|
|
||
| --- | ||
|
|
||
| ## Equipment Servicing | ||
|
|
||
| Drive + Arm + GPS + Heading | ||
|
|
||
| ```bash | ||
| # Rover | ||
| ros2 launch bringup equipment_servicing.launch.py mode:=jetson | ||
|
|
||
| # Operator laptop | ||
| ros2 launch bringup equipment_servicing.launch.py mode:=base_station | ||
|
|
||
| # Single machine | ||
| ros2 launch bringup equipment_servicing.launch.py | ||
|
|
||
| # Mock hardware (no physical rover) | ||
| ros2 launch bringup equipment_servicing.launch.py use_mock_hardware:=true use_sim:=true | ||
|
|
||
| # 3 DOF wrist | ||
| ros2 launch bringup equipment_servicing.launch.py use_3dof:=true | ||
| ``` | ||
|
|
||
| ### Parameters | ||
|
|
||
| | Parameter | Default | Choices | Description | | ||
| |---|---|---|---| | ||
| | `mode` | `standalone` | `standalone` `jetson` `base_station` | Deployment target | | ||
| | `use_sim` | `false` | `true` `false` | Launch RViz2 | | ||
| | `use_mock_hardware` | `false` | `true` `false` | Mock hardware for drive and arm | | ||
| | `mock_sensor_commands` | `false` | `true` `false` | Mock sensor command interfaces (requires `use_mock_hardware`) | | ||
| | `robot_controller` | `rear_ackermann_controller` | `rear_ackermann_controller` `front_ackermann_controller` `ackermann_steering_controller` | Drive controller to start | | ||
| | `use_3dof` | `false` | `true` `false` | Enable 3 DOF wrist joints on arm | | ||
| | `deactivate_talon` | `false` | `true` `false` | Deactivate talon joints in URDF (use with `use_mock_hardware` to prevent CAN traffic) | | ||
|
|
||
| --- | ||
|
|
||
| ## Node breakdown by mode | ||
|
|
||
| ### Delivery / Equipment Servicing | ||
|
|
||
| | Node group | jetson | base_station | standalone | | ||
| |---|:---:|:---:|:---:| | ||
| | Drive hardware + controllers | ✓ | | ✓ | | ||
| | Drive teleop (joystick) | | ✓ | ✓ | | ||
| | Arm hardware + controllers | ✓ | | ✓ | | ||
| | Arm teleop (joystick) | | ✓ | ✓ | | ||
| | GPS (athena_gps / pixhawk) | ✓ | | ✓ | | ||
| | Magnetometer heading | ✓ | | ✓ | | ||
|
|
||
| ### Autonomous Navigation | ||
|
|
||
| | Node group | jetson | base_station | standalone | | ||
| |---|:---:|:---:|:---:| | ||
| | Drive hardware + controllers | ✓ | | ✓ | | ||
| | Drive teleop (joystick) | | ✓ | ✓ | | ||
| | ZED camera | ✓ | | ✓ | | ||
| | GPS (athena_gps / pixhawk) | ✓ | | ✓ | | ||
| | ZED spatial localizer (default) | ✓ | | ✓ | | ||
| | EKF localizer (`use_zed_localizer:=false`) | ✓ | | ✓ | | ||
| | Nav2 stack | ✓ | | ✓ | | ||
| | Magnetometer heading | ✓ | | ✓ | |
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,162 @@ | ||
| from launch import LaunchDescription | ||
| from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction | ||
| from launch.launch_description_sources import PythonLaunchDescriptionSource | ||
| from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, PythonExpression | ||
| from launch_ros.substitutions import FindPackageShare | ||
| from ament_index_python.packages import get_package_share_directory | ||
| import os | ||
|
|
||
|
|
||
| def generate_launch_description(): | ||
| default_params = PathJoinSubstitution([ | ||
| FindPackageShare('athena_planner'), 'config', 'nav2_params.yaml' | ||
| ]) | ||
| minimal_params = PathJoinSubstitution([ | ||
| FindPackageShare('athena_planner'), 'config', 'nav2_params_minimal.yaml' | ||
| ]) | ||
| selected_params = PythonExpression([ | ||
| "'", minimal_params, "' if '", LaunchConfiguration('use_minimal'), "' == 'true' else '", default_params, "'" | ||
| ]) | ||
|
|
||
| return LaunchDescription([ | ||
| DeclareLaunchArgument( | ||
| 'mode', | ||
| default_value='standalone', | ||
| choices=['standalone', 'jetson', 'base_station'], | ||
| description=( | ||
| "'jetson': hardware + nav nodes on the rover. " | ||
| "'base_station': operator teleop nodes. " | ||
| "'standalone': all nodes on one machine." | ||
| ), | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'use_sim', | ||
| default_value='false', | ||
| choices=['true', 'false'], | ||
| description='Enable sim time and RViz2.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'use_mock_hardware', | ||
| default_value='false', | ||
| choices=['true', 'false'], | ||
| description='Start drive with mock hardware mirroring commands to states.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'mock_sensor_commands', | ||
| default_value='false', | ||
| choices=['true', 'false'], | ||
| description='Enable mock command interfaces for sensors. Only used when use_mock_hardware is true.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'robot_controller', | ||
| default_value='rear_ackermann_controller', | ||
| choices=['front_ackermann_controller', 'ackermann_steering_controller', 'rear_ackermann_controller'], | ||
| description='Drive controller to start.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'use_zed_localizer', | ||
| default_value='true', | ||
| choices=['true', 'false'], | ||
| description='Use ZED spatial localization instead of the EKF localizer.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'enable_gnss', | ||
| default_value='true', | ||
| choices=['true', 'false'], | ||
| description='Enable GNSS fusion inside the ZED camera.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'use_minimal', | ||
| default_value='false', | ||
| choices=['true', 'false'], | ||
| description='Use minimal Nav2 config (empty costmaps, basic BT) for ackermann testing.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'params_file', | ||
| default_value=selected_params, | ||
| description='Full path to the Nav2 params YAML. Defaults to minimal or full config based on use_minimal.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'use_dem', | ||
| default_value='false', | ||
| choices=['true', 'false'], | ||
| description='Enable DEM costmap layer.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'use_respawn', | ||
| default_value='false', | ||
| choices=['true', 'false'], | ||
| description='Respawn nav2 nodes if they crash.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'log_level', | ||
| default_value='info', | ||
| description='Log level for nav2 nodes.', | ||
| ), | ||
| DeclareLaunchArgument( | ||
| 'use_config', | ||
| default_value='false', | ||
| choices=['true', 'false'], | ||
| description='Launch the Nav2 config GUI.', | ||
| ), | ||
| OpaqueFunction(function=launch_setup), | ||
| ]) | ||
|
|
||
|
|
||
| def launch_setup(context, *args, **kwargs): | ||
| mode = LaunchConfiguration('mode').perform(context) | ||
| use_sim = LaunchConfiguration('use_sim').perform(context) | ||
| use_mock_hardware = LaunchConfiguration('use_mock_hardware').perform(context) | ||
| mock_sensor_commands = LaunchConfiguration('mock_sensor_commands').perform(context) | ||
| robot_controller = LaunchConfiguration('robot_controller').perform(context) | ||
| use_zed_localizer = LaunchConfiguration('use_zed_localizer').perform(context) | ||
| enable_gnss = LaunchConfiguration('enable_gnss').perform(context) | ||
| params_file = LaunchConfiguration('params_file').perform(context) | ||
| use_dem = LaunchConfiguration('use_dem').perform(context) | ||
| use_respawn = LaunchConfiguration('use_respawn').perform(context) | ||
| log_level = LaunchConfiguration('log_level').perform(context) | ||
| use_config = LaunchConfiguration('use_config').perform(context) | ||
|
|
||
| drive_bringup = get_package_share_directory('drive_bringup') | ||
| nav_bringup = get_package_share_directory('nav_bringup') | ||
| mag_heading = get_package_share_directory('mag_heading') | ||
|
|
||
| drive = IncludeLaunchDescription( | ||
| PythonLaunchDescriptionSource( | ||
| os.path.join(drive_bringup, 'launch', 'athena_drive.launch.py') | ||
| ), | ||
| launch_arguments={ | ||
| 'mode': mode, | ||
| 'use_sim': use_sim, | ||
| 'use_mock_hardware': use_mock_hardware, | ||
| 'mock_sensor_commands': mock_sensor_commands, | ||
| 'robot_controller': robot_controller, | ||
| }.items(), | ||
| ) | ||
|
|
||
| nav = IncludeLaunchDescription( | ||
| PythonLaunchDescriptionSource( | ||
| os.path.join(nav_bringup, 'launch', 'nav_bringup.launch.py') | ||
| ), | ||
| launch_arguments={ | ||
| 'sim': use_sim, | ||
| 'use_zed_localizer': use_zed_localizer, | ||
| 'enable_gnss': enable_gnss, | ||
| 'params_file': params_file, | ||
| 'use_dem': use_dem, | ||
| 'use_respawn': use_respawn, | ||
| 'log_level': log_level, | ||
| 'use_config': use_config, | ||
| }.items(), | ||
| ) | ||
|
|
||
| heading = IncludeLaunchDescription( | ||
| PythonLaunchDescriptionSource( | ||
| os.path.join(mag_heading, 'launch', 'mag_heading.launch.py') | ||
| ), | ||
| ) | ||
|
|
||
| if mode == 'base_station': | ||
| return [drive] | ||
| else: | ||
| return [drive, nav, heading] | ||
Oops, something went wrong.
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.