You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Including the bringup_launch.py into another launch file (for example, in a supposed tb_nav package) and simply map all the arguments using no namespace.
Expected behavior
Nav2 is able to do the bringup
Actual behavior
I get errors in controller_server:
[lifecycle_manager-5] [ERROR] [1732801697.158933701] [lifecycle_manager_localization]: Failed to change state for node: map_server
[lifecycle_manager-5] [ERROR] [1732801697.158979996] [lifecycle_manager_localization]: Failed to bring up all requested nodes. Aborting bringup.
[bt_navigator-10] [INFO] [1732801697.165182434] [bt_navigator]:
[bt_navigator-10] bt_navigator lifecycle node launched.
[bt_navigator-10] Waiting on external lifecycle transitions to activate
[bt_navigator-10] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-10] [INFO] [1732801697.165360277] [bt_navigator]: Creating
[controller_server-6] [INFO] [1732801697.171776012] [controller_server]: Creating controller server
[planner_server-8] [INFO] [1732801697.232687539] [global_costmap.global_costmap]:
[planner_server-8] global_costmap lifecycle node launched.
[planner_server-8] Waiting on external lifecycle transitions to activate
[planner_server-8] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-8] [INFO] [1732801697.247297223] [global_costmap.global_costmap]: Creating Costmap
[controller_server-6] [INFO] [1732801697.252753698] [local_costmap.local_costmap]:
[controller_server-6] local_costmap lifecycle node launched.
[controller_server-6] Waiting on external lifecycle transitions to activate
[controller_server-6] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[velocity_smoother-12] [INFO] [1732801697.265705738] [velocity_smoother]:
[velocity_smoother-12] velocity_smoother lifecycle node launched.
[velocity_smoother-12] Waiting on external lifecycle transitions to activate
[velocity_smoother-12] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[lifecycle_manager-13] [INFO] [1732801697.306324939] [lifecycle_manager_navigation]: Creating
[lifecycle_manager-13] [INFO] [1732801697.312174904] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[waypoint_follower-11] [INFO] [1732801697.313905654] [waypoint_follower]:
[waypoint_follower-11] waypoint_follower lifecycle node launched.
[waypoint_follower-11] Waiting on external lifecycle transitions to activate
[waypoint_follower-11] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-11] [INFO] [1732801697.325595632] [waypoint_follower]: Creating
[controller_server-6] [INFO] [1732801697.331784491] [local_costmap.local_costmap]: Creating Costmap
[behavior_server-9] [INFO] [1732801697.400330003] [behavior_server]:
[behavior_server-9] behavior_server lifecycle node launched.
[behavior_server-9] Waiting on external lifecycle transitions to activate
[behavior_server-9] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[lifecycle_manager-13] [INFO] [1732801697.461628676] [lifecycle_manager_navigation]: Starting managed nodes bringup...
[lifecycle_manager-13] [INFO] [1732801697.461703820] [lifecycle_manager_navigation]: Configuring controller_server
[controller_server-6] [INFO] [1732801697.462576347] [controller_server]: Configuring controller interface
[controller_server-6] [INFO] [1732801697.462819862] [controller_server]: getting goal checker plugins..
[controller_server-6] [INFO] [1732801697.463074770] [controller_server]: Controller frequency set to 20.0000Hz
[controller_server-6] [INFO] [1732801697.463123176] [local_costmap.local_costmap]: Configuring
[controller_server-6] [INFO] [1732801697.474313005] [local_costmap.local_costmap]: Using plugin "static_layer"
[controller_server-6] [INFO] [1732801697.485957028] [local_costmap.local_costmap]: Subscribing to the map topic (/map) with transient local durability
[ERROR] [kobuki_ros_node-1]: process has died [pid 672, exit code -6, cmd '/root/turtlebot2_ws/install/kobuki_node/lib/kobuki_node/kobuki_ros_node --ros-args --params-file /root/catkin_ws/install/tb_unizar_nav/share/tb_unizar_nav/params/kobuki_params.yaml'].
[controller_server-6] [INFO] [1732801697.487589588] [local_costmap.local_costmap]: Initialized plugin "static_layer"
[controller_server-6] [INFO] [1732801697.487635720] [local_costmap.local_costmap]: Using plugin "obstacle_layer"
[controller_server-6] [INFO] [1732801697.490855754] [local_costmap.local_costmap]: Subscribed to Topics:
[controller_server-6] [INFO] [1732801697.490970440] [local_costmap.local_costmap]: Initialized plugin "obstacle_layer"
[controller_server-6] [INFO] [1732801697.491212137] [local_costmap.local_costmap]: Using plugin "inflation_layer"
[controller_server-6] [INFO] [1732801697.493822734] [local_costmap.local_costmap]: Initialized plugin "inflation_layer"
[controller_server-6] [INFO] [1732801697.505518077] [controller_server]: Created progress_checker : progress_checker of type nav2_controller::SimpleProgressChecker
[controller_server-6] [INFO] [1732801697.508044109] [controller_server]: Created goal checker : goal_checker of type nav2_controller::SimpleGoalChecker
[controller_server-6] [INFO] [1732801697.509441767] [controller_server]: Controller Server has goal_checker goal checkers available.
[controller_server-6] [INFO] [1732801697.515445833] [controller_server]: Created controller : FollowPath of type dwb_core::DWBLocalPlanner
[controller_server-6] [INFO] [1732801697.518945205] [controller_server]: Setting transform_tolerance to 0.100000
[controller_server-6] [ERROR] [1732801697.533337914] [controller_server]: Couldn't load critics! Caught exception: No critics defined for FollowPath
[controller_server-6] [ERROR] [1732801697.539661116] [controller_server]: Caught exception in callback for transition 10
[controller_server-6] [ERROR] [1732801697.539727130] [controller_server]: Original error: No critics defined for FollowPath
[controller_server-6] [WARN] [1732801697.539763969] [controller_server]: Error occurred while doing error handling.
[controller_server-6] [FATAL] [1732801697.539780076] [controller_server]: Lifecycle node controller_server does not have error state implemented
[lifecycle_manager-13] [ERROR] [1732801697.540161913] [lifecycle_manager_navigation]: Failed to change state for node: controller_server
[lifecycle_manager-13] [ERROR] [1732801697.540239723] [lifecycle_manager_navigation]: Failed to bring up all requested nodes. Aborting bringup.
Additional information
This is the launchfile I created. Notice that use_namespace, slam, use_localization, and use_composition (trying to follow issue #3644 ) are set to false. If there is anything wrong with my approach in general and you can tell me it would also be very helpful.
import os
import yaml
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, GroupAction
from launch_ros.actions import PushRosNamespace, Node
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from ament_index_python.packages import get_package_share_directory
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
# Paths to bringup and custom package
bringup_dir = get_package_share_directory('nav2_bringup')
tb_nav_dir = get_package_share_directory('tb_nav')
# Paths to launch and params files
bringup_launch_path = os.path.join(bringup_dir, 'launch', 'bringup_launch.py')
default_nav_params_file = os.path.join(tb_nav_dir, 'params', 'nav2_params.yaml')
default_kobuki_params_file = os.path.join(tb_nav_dir, 'params', 'kobuki_params.yaml')
default_map_file = os.path.join(tb_nav_dir, 'maps', 'dummy.yaml')
# Create the launch configuration variables
namespace = LaunchConfiguration('namespace')
use_namespace = LaunchConfiguration('use_namespace')
slam = LaunchConfiguration('slam')
map_yaml_file = LaunchConfiguration('map')
use_sim_time = LaunchConfiguration('use_sim_time')
nav_params_file = LaunchConfiguration('nav_params_file')
kobuki_params_file = LaunchConfiguration('kobuki_params_file')
autostart = LaunchConfiguration('autostart')
use_composition = LaunchConfiguration('use_composition')
use_respawn = LaunchConfiguration('use_respawn')
log_level = LaunchConfiguration('log_level')
use_localization = LaunchConfiguration('use_localization')
use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
# Map fully qualified names to relative ones so the node's namespace can be prepended.
# In case of the transforms (tf), currently, there doesn't seem to be a better alternative
# https://github.com/ros/geometry2/issues/32
# https://github.com/ros/robot_state_publisher/pull/30
# TODO(orduno) Substitute with `PushNodeRemapping`
# https://github.com/ros2/launch_ros/issues/56
remappings = [('/tf', 'tf'),
('/tf_static', 'tf_static')]
# Declare launch arguments
declarenamespace_cmd = DeclareLaunchArgument(
'namespace', default_value='ugv0', description='Namespace for the robot'
)
declare_use_namespace_cmd = DeclareLaunchArgument(
'use_namespace',
default_value='False',
description='Whether to apply a namespace to the navigation stack',
)
declare_slam_cmd = DeclareLaunchArgument(
'slam', default_value='False', description='Whether run a SLAM'
)
declare_map_yaml_cmd = DeclareLaunchArgument(
'map', default_value=default_map_file, description='Full path to map yaml file to load'
)
declare_use_localization_cmd = DeclareLaunchArgument(
'use_localization', default_value='False',
description='Whether to enable localization or not'
)
declare_use_sim_time_cmd = DeclareLaunchArgument(
'use_sim_time',
default_value='False',
description='Use simulation (Gazebo) clock if True',
)
declare_nav_params_file_cmd = DeclareLaunchArgument(
'nav_params_file',
default_value=default_nav_params_file,
description='Full path to the ROS2 parameters file to use for all launched nodes',
)
declare_kobuki_params_file_cmd = DeclareLaunchArgument(
'kobuki_params_file',
default_value=default_kobuki_params_file,
description='Full path to the ROS2 parameters file to use for all launched nodes',
)
declare_autostart_cmd = DeclareLaunchArgument(
'autostart',
default_value='True',
description='Automatically startup the nav2 stack',
)
declare_use_composition_cmd = DeclareLaunchArgument(
'use_composition',
default_value='False',
description='Whether to use composed bringup',
)
declare_use_respawn_cmd = DeclareLaunchArgument(
'use_respawn',
default_value='False',
description='Whether to respawn if a node crashes. Applied when composition is disabled.',
)
declare_log_level_cmd = DeclareLaunchArgument(
'log_level', default_value='info', description='log level'
)
declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
'use_robot_state_pub',
default_value='True',
description='Whether to start the robot state publisher')
declare_kobuki_ros_node = Node(package='kobuki_node',
executable='kobuki_ros_node',
output='both',
parameters=[kobuki_params_file])
# Locate description TODO: Fix the xacro compilation
urdf = os.path.join(tb_nav_dir, 'urdf', 'compiled_turtlebot.urdf')
with open(urdf, 'r') as infp:
robot_description = infp.read()
# Group the kobuki_node launch file under the specified namespace
# kobuki_group = GroupAction(
# actions=[
# PushRosNamespace(namespace), # Apply the namespace dynamically
# declare_kobuki_ros_node,
# ]
# )
start_robot_state_publisher_cmd = Node(
condition=IfCondition(use_robot_state_pub),
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
# namespace=namespace,
output='screen',
parameters=[{'use_sim_time': use_sim_time,
'robot_description': robot_description}],
remappings=remappings)
# Include the bringup launch file
bringup_launch = IncludeLaunchDescription(
PythonLaunchDescriptionSource(bringup_launch_path),
launch_arguments={
'namespace': namespace,
'use_namespace': use_namespace,
'slam': slam,
'map': map_yaml_file,
'use_localization': use_localization,
'use_sim_time': use_sim_time,
'params_file': nav_params_file,
'autostart': autostart,
'use_composition': use_composition,
'use_respawn': use_respawn,
'log_level': log_level
}.items(),
)
return LaunchDescription([
# Declare launch arguments
declarenamespace_cmd,
declare_use_namespace_cmd,
declare_slam_cmd,
declare_map_yaml_cmd,
declare_use_localization_cmd,
declare_use_sim_time_cmd,
declare_nav_params_file_cmd,
declare_kobuki_params_file_cmd,
declare_autostart_cmd,
declare_use_composition_cmd,
declare_use_respawn_cmd,
declare_log_level_cmd,
declare_use_robot_state_pub_cmd,
# Include the kobuki group
declare_kobuki_ros_node,
start_robot_state_publisher_cmd,
# Include the bringup launch file
bringup_launch,
])
``
The text was updated successfully, but these errors were encountered:
Bug report
Required Info:
Steps to reproduce issue
Including the bringup_launch.py into another launch file (for example, in a supposed tb_nav package) and simply map all the arguments using no namespace.
Expected behavior
Nav2 is able to do the bringup
Actual behavior
I get errors in controller_server:
Additional information
This is the launchfile I created. Notice that use_namespace, slam, use_localization, and use_composition (trying to follow issue #3644 ) are set to false. If there is anything wrong with my approach in general and you can tell me it would also be very helpful.
The text was updated successfully, but these errors were encountered: