mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 03:41:17 -05:00
rewrite the launch file
This commit is contained in:
@@ -1,139 +1,91 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, Shutdown
|
||||
from launch.substitutions import (
|
||||
LaunchConfiguration,
|
||||
ThisLaunchFileDir,
|
||||
PathJoinSubstitution,
|
||||
)
|
||||
from launch_ros.actions import Node
|
||||
from launch.actions import DeclareLaunchArgument, Shutdown
|
||||
from launch.conditions import IfCondition
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
|
||||
|
||||
# Prevent making __pycache__ directories
|
||||
from sys import dont_write_bytecode
|
||||
def generate_launch_description():
|
||||
connector = LaunchConfiguration("connector")
|
||||
use_ptz = LaunchConfiguration("use_ptz")
|
||||
|
||||
dont_write_bytecode = True
|
||||
ld = LaunchDescription()
|
||||
|
||||
# arguments
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"connector",
|
||||
default_value="auto",
|
||||
description="Connector parameter for anchor node (default: auto)",
|
||||
)
|
||||
)
|
||||
|
||||
def launch_setup(context, *args, **kwargs):
|
||||
# Retrieve the resolved value of the launch argument 'mode'
|
||||
mode = LaunchConfiguration("mode").perform(context)
|
||||
connector = LaunchConfiguration("connector").perform(context)
|
||||
nodes = []
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"use_ptz",
|
||||
default_value="true", # must be string for launch system
|
||||
description="Whether to launch PTZ node (default: true)",
|
||||
)
|
||||
)
|
||||
|
||||
if mode == "anchor":
|
||||
# Launch every node and pass "anchor" as the parameter
|
||||
|
||||
nodes.append(
|
||||
Node(
|
||||
package="arm_pkg",
|
||||
executable="arm", # change as needed
|
||||
name="arm",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
nodes.append(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="core", # change as needed
|
||||
name="core",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
nodes.append(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="ptz", # change as needed
|
||||
name="ptz",
|
||||
output="both",
|
||||
condition=IfCondition(LaunchConfiguration("use_ptz", default="true")),
|
||||
# Currently don't shutdown all nodes if the PTZ node fails, as it is not critical
|
||||
# on_exit=Shutdown() # Uncomment if you want to shutdown on PTZ failure
|
||||
)
|
||||
)
|
||||
nodes.append(
|
||||
Node(
|
||||
package="bio_pkg",
|
||||
executable="bio", # change as needed
|
||||
name="bio",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
nodes.append(
|
||||
Node(
|
||||
package="anchor_pkg",
|
||||
executable="anchor", # change as needed
|
||||
name="anchor",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode, "connector": connector}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
elif mode in ["arm", "core", "bio", "ptz"]:
|
||||
# Only launch the node corresponding to the provided mode.
|
||||
if mode == "arm":
|
||||
nodes.append(
|
||||
# nodes
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="arm_pkg",
|
||||
executable="arm",
|
||||
name="arm",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
parameters=[{"launch_mode": "anchor"}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
elif mode == "core":
|
||||
nodes.append(
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="core",
|
||||
name="core",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
parameters=[{"launch_mode": "anchor"}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
elif mode == "bio":
|
||||
nodes.append(
|
||||
Node(
|
||||
package="bio_pkg",
|
||||
executable="bio",
|
||||
name="bio",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
elif mode == "ptz":
|
||||
nodes.append(
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="ptz",
|
||||
name="ptz",
|
||||
output="both",
|
||||
on_exit=Shutdown(), # on fail, shutdown if this was the only node to be launched
|
||||
condition=IfCondition(use_ptz),
|
||||
)
|
||||
)
|
||||
else:
|
||||
# If an invalid mode is provided, print an error.
|
||||
print("Invalid mode provided. Choose one of: arm, core, bio, anchor, ptz.")
|
||||
|
||||
return nodes
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
declare_arg = DeclareLaunchArgument(
|
||||
"mode",
|
||||
default_value="anchor",
|
||||
description="Launch mode: arm, core, bio, anchor, or ptz",
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="bio_pkg",
|
||||
executable="bio",
|
||||
name="bio",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": "anchor"}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
|
||||
return LaunchDescription([declare_arg, OpaqueFunction(function=launch_setup)])
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="anchor_pkg",
|
||||
executable="anchor",
|
||||
name="anchor",
|
||||
output="both",
|
||||
parameters=[
|
||||
{
|
||||
"launch_mode": "anchor",
|
||||
"connector": connector,
|
||||
}
|
||||
],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
|
||||
return ld
|
||||
|
||||
Reference in New Issue
Block a user