Giter Site home page Giter Site logo

Comments (2)

clalancette avatar clalancette commented on September 15, 2024 2

[rclcpp]: failed to initialize rcl: Couldn't parse parameter override rule: '-p bla'. Error: Expected lexeme type (22) not found, search ended at index 3, at /root/ros2_ws/colcon_ws/src/ros2/rcl/rcl/src/rcl/lexer_lookahead.c:239, at /root/ros2_ws/colcon_ws/src/ros2/rcl/rcl/src/rcl/arguments.c:343

I still think this error message isn't as useful as it could be. It's exposing a low-level detail (the lexer parse error), rather than the higher-level "you provided an parameter argument that is missing :=", which is arguably more useful to the end-user.

from rcl.

fujitatomoya avatar fujitatomoya commented on September 15, 2024

I think that this is because application does not catch the exception from rclcpp::init (rcl_init)

# ros2 run demo_nodes_cpp add_two_ints_client 1 2 --ros-args -p bla
[ERROR] [1660931840.357026857] [rcl]: Failed to parse global arguments
terminate called after throwing an instance of 'rclcpp::exceptions::RCLInvalidROSArgsError'
  what():  failed to initialize rcl: Couldn't parse parameter override rule: '-p bla'. Error: Expected lexeme type (22) not found, search ended at index 3, at /root/ros2_ws/colcon_ws/src/ros2/rcl/rcl/src/rcl/lexer_lookahead.c:239, at /root/ros2_ws/colcon_ws/src/ros2/rcl/rcl/src/rcl/arguments.c:343
[ros2run]: Aborted

this can be with following patch,

diff --git a/demo_nodes_cpp/src/services/add_two_ints_client.cpp b/demo_nodes_cpp/src/services/add_two_ints_client.cpp
index 8442801..b0cdf0d 100644
--- a/demo_nodes_cpp/src/services/add_two_ints_client.cpp
+++ b/demo_nodes_cpp/src/services/add_two_ints_client.cpp
@@ -43,7 +43,12 @@ int main(int argc, char ** argv)
   // Force flush of the stdout buffer.
   setvbuf(stdout, NULL, _IONBF, BUFSIZ);
 
-  rclcpp::init(argc, argv);
+  try {
+    rclcpp::init(argc, argv);
+  } catch (const std::exception & exception) {
+    RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), exception.what());
+    return EXIT_FAILURE;
+  }
 
   auto node = rclcpp::Node::make_shared("add_two_ints_client");
# ros2 run demo_nodes_cpp add_two_ints_client 1 2 --ros-args -p bla
[ERROR] [1660931652.776928271] [rcl]: Failed to parse global arguments
[ERROR] [1660931652.776993285] [rclcpp]: failed to initialize rcl: Couldn't parse parameter override rule: '-p bla'. Error: Expected lexeme type (22) not found, search ended at index 3, at /root/ros2_ws/colcon_ws/src/ros2/rcl/rcl/src/rcl/lexer_lookahead.c:239, at /root/ros2_ws/colcon_ws/src/ros2/rcl/rcl/src/rcl/arguments.c:343
[ros2run]: Process exited with failure 1

from rcl.

Related Issues (20)

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.