Skip to content
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

Launch heartbeat in physical bringup #236

Merged
merged 2 commits into from
Jan 26, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 16 additions & 10 deletions urc_bringup/launch/bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,12 @@ def generate_launch_description():
get_package_share_directory("urc_bringup"), "config", "nmea_serial_driver.yaml"
)

heartbeat_node = Node(
package="urc_bringup",
executable="urc_bringup_HeartbeatPublisher",
parameters=[{"heartbeatInterval": 1000}],
)

control_node = Node(
package="controller_manager",
executable="ros2_control_node",
Expand All @@ -69,7 +75,7 @@ def generate_launch_description():
load_joint_state_broadcaster = Node(
package="controller_manager",
executable="spawner",
arguments=["-p", controller_config_file_dir, "joint_state_broadcaster"]
arguments=["-p", controller_config_file_dir, "joint_state_broadcaster"],
)

load_drivetrain_controller = Node(
Expand All @@ -81,7 +87,7 @@ def generate_launch_description():
load_status_light_controller = Node(
package="controller_manager",
executable="spawner",
arguments=["-p", controller_config_file_dir, "status_light_controller"]
arguments=["-p", controller_config_file_dir, "status_light_controller"],
)

twist_mux_node = Node(
Expand All @@ -93,17 +99,17 @@ def generate_launch_description():
launch_gps = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(
pkg_nmea_navsat_driver,
"launch", "nmea_serial_driver.launch.py"
pkg_nmea_navsat_driver, "launch", "nmea_serial_driver.launch.py"
)
)
)

launch_gps = Node(
package='nmea_navsat_driver',
executable='nmea_serial_driver',
output='screen',
parameters=[gps_config])
package="nmea_navsat_driver",
executable="nmea_serial_driver",
output="screen",
parameters=[gps_config],
)

launch_vectornav = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
Expand All @@ -128,8 +134,7 @@ def generate_launch_description():
)

odom_frame_node = Node(
package="urc_tf", executable="urc_tf_WorldFrameBroadcaster",
output="screen"
package="urc_tf", executable="urc_tf_WorldFrameBroadcaster", output="screen"
)

return LaunchDescription(
Expand All @@ -154,5 +159,6 @@ def generate_launch_description():
rosbridge_server_node,
odom_frame_node,
launch_vectornav,
heartbeat_node,
]
)
8 changes: 8 additions & 0 deletions urc_bringup/launch/bringup_simulation.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,13 @@ def generate_launch_description():
],
)

rosbridge_server_node = Node(
package="rosbridge_server",
name="rosbridge_server",
executable="rosbridge_websocket.py",
parameters=[{"port": 9090}],
)

load_robot_state_publisher = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
Expand Down Expand Up @@ -218,5 +225,6 @@ def generate_launch_description():
load_robot_state_publisher,
spawn_robot,
map_to_odom_transform_node,
rosbridge_server_node,
]
)
Loading