ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

[ERROR] [launch]: Caught exception in launch: get_launch_arguments() missing 1 required positional argument: 'self'

asked 2020-02-27 04:02:33 -0500

snvk gravatar image

updated 2023-04-18 10:46:19 -0500

130s gravatar image

Hi, I'm just trying to work with ros2 launch file.. it runs well but i could not launch it, following error pops up :

[INFO] [launch]: Default logging verbosity is set to INFO
[ERROR] [launch]: Caught exception in launch (see debug for traceback): get_launch_arguments() missing 1 required positional argument: 'self'

find cpp:

int main(int argc, char * argv[])
{  
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("test");
RCLCPP_INFO(node->get_logger(), "Hello!, Ros2 launch worked for me");
rclcpp::shutdown();
return 0;
}

mytext.launch.py file :

import launch
import launch.actions
import launch.substitutions
import launch_ros.actions

def generate_launch_description():
    return launch.LaunchDescription
    (
        [
        launch_ros.actions.Node
            (
            package='simple_test', 
            node_executable='my_test',
            output='screen'
            )
        ]
    )

Cmakelsit.txt:

cmake_minimum_required(VERSION 3.5)
project(simple_test)

if(NOT CMAKE_C_STANDARD)
  set(CMAKE_C_STANDARD 99)
endif()


if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()


find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  ament_lint_auto_find_test_dependencies()
endif()


add_executable(my_test src/test.cpp)
ament_target_dependencies(my_test rclcpp std_msgs)

install(TARGETS
my_test
DESTINATION lib/${PROJECT_NAME}
)

install(DIRECTORY
  launch
  DESTINATION share/${PROJECT_NAME}/
) 

ament_package()
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-02-27 13:31:45 -0500

jacobperron gravatar image

The issue is your use of whitespace in the Python launch file. Python cares about whitespace.

I believe what is happening is that the class launch.LaunchDescription is being returned instead of an object instance. To fix your file, move the opening parenthesis for the LaunchDescription constructor next to the type name. It's probably best to do this for the Node as well:

def generate_launch_description():
    return launch.LaunchDescription(
        [
            launch_ros.actions.Node(
                package='simple_test', 
                node_executable='my_test',
                output='screen'
            )
        ]
    )

Generally, I'd recommend following the Python style guide, PEP 8, when writing your launch files.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2020-02-27 04:02:33 -0500

Seen: 10,812 times

Last updated: Apr 18 '23