diff --git a/rclcpp/include/rclcpp/node_options.hpp b/rclcpp/include/rclcpp/node_options.hpp
index 1a7fcfd52d..43141b6bdc 100644
--- a/rclcpp/include/rclcpp/node_options.hpp
+++ b/rclcpp/include/rclcpp/node_options.hpp
@@ -99,8 +99,7 @@ class NodeOptions
   /// Set the arguments, return this for parameter idiom.
   /**
    * These arguments are used to extract remappings used by the node and other
-   * settings. Being specific to a ROS node, an implicit `--ros-args` scope flag
-   * always precedes these arguments.
+   * ROS specific settings, as well as user defined non-ROS arguments.
    *
    * This will cause the internal rcl_node_options_t struct to be invalidated.
    */
diff --git a/rclcpp/src/rclcpp/node_options.cpp b/rclcpp/src/rclcpp/node_options.cpp
index 7b348c4d08..a207c4401a 100644
--- a/rclcpp/src/rclcpp/node_options.cpp
+++ b/rclcpp/src/rclcpp/node_options.cpp
@@ -93,27 +93,16 @@ NodeOptions::get_rcl_node_options() const
     int c_argc = 0;
     std::unique_ptr<const char *[]> c_argv;
     if (!this->arguments_.empty()) {
-      auto it = std::find(
-        this->arguments_.cbegin(), this->arguments_.cend(), RCL_ROS_ARGS_FLAG);
-
-      c_argc = static_cast<int>(this->arguments_.size());
-      if (it == this->arguments_.cend()) {
-        c_argc += 1;
+      if (this->arguments_.size() > static_cast<size_t>(std::numeric_limits<int>::max())) {
+        throw_from_rcl_error(RCL_RET_INVALID_ARGUMENT, "Too many args");
       }
 
+      c_argc = static_cast<int>(this->arguments_.size());
       c_argv.reset(new const char *[c_argc]);
 
-      std::size_t i = 0;
-      if (it == this->arguments_.cend()) {
-        c_argv[i++] = RCL_ROS_ARGS_FLAG;
+      for (std::size_t i = 0; i < this->arguments_.size(); ++i) {
+        c_argv[i] = this->arguments_[i].c_str();
       }
-      for (std::size_t j = 0; j < this->arguments_.size(); ++i, ++j) {
-        c_argv[i] = this->arguments_[j].c_str();
-      }
-    }
-
-    if (this->arguments_.size() > static_cast<size_t>(std::numeric_limits<int>::max())) {
-      throw_from_rcl_error(RCL_RET_INVALID_ARGUMENT, "Too many args");
     }
 
     rmw_ret_t ret = rcl_parse_arguments(
diff --git a/rclcpp/test/test_node.cpp b/rclcpp/test/test_node.cpp
index a1a61ccdd4..583a697593 100644
--- a/rclcpp/test/test_node.cpp
+++ b/rclcpp/test/test_node.cpp
@@ -66,7 +66,7 @@ TEST_F(TestNode, get_name_and_namespace) {
   }
   {
     auto options = rclcpp::NodeOptions()
-      .arguments({"-r", "__ns:=/another_ns"});
+      .arguments({"--ros-args", "-r", "__ns:=/another_ns"});
     auto node = std::make_shared<rclcpp::Node>("my_node", "/ns", options);
     EXPECT_STREQ("my_node", node->get_name());
     EXPECT_STREQ("/another_ns", node->get_namespace());
diff --git a/rclcpp/test/test_node_global_args.cpp b/rclcpp/test/test_node_global_args.cpp
index 998bf5df7e..febef6bb37 100644
--- a/rclcpp/test/test_node_global_args.cpp
+++ b/rclcpp/test/test_node_global_args.cpp
@@ -36,7 +36,7 @@ class TestNodeWithGlobalArgs : public ::testing::Test
 
 TEST_F(TestNodeWithGlobalArgs, local_arguments_before_global) {
   auto options = rclcpp::NodeOptions()
-    .arguments({"-r", "__node:=local_arguments_test"});
+    .arguments({"--ros-args", "-r", "__node:=local_arguments_test"});
 
   auto node = rclcpp::Node::make_shared("orig_name", options);
   EXPECT_STREQ("local_arguments_test", node->get_name());
diff --git a/rclcpp/test/test_node_options.cpp b/rclcpp/test/test_node_options.cpp
index 3d66d034f7..25348f0141 100644
--- a/rclcpp/test/test_node_options.cpp
+++ b/rclcpp/test/test_node_options.cpp
@@ -24,32 +24,7 @@
 #include "rclcpp/node_options.hpp"
 
 
-TEST(TestNodeOptions, implicit_ros_args) {
-  rcl_allocator_t allocator = rcl_get_default_allocator();
-  auto options = rclcpp::NodeOptions(allocator)
-    .arguments({"-r", "__node:=some_node", "-r", "__ns:=/some_ns"});
-
-  const rcl_node_options_t * rcl_options = options.get_rcl_node_options();
-  ASSERT_TRUE(rcl_options != nullptr);
-  ASSERT_EQ(0, rcl_arguments_get_count_unparsed(&rcl_options->arguments));
-  ASSERT_EQ(0, rcl_arguments_get_count_unparsed_ros(&rcl_options->arguments));
-
-  char * node_name = nullptr;
-  EXPECT_EQ(RCL_RET_OK, rcl_remap_node_name(
-      &rcl_options->arguments, nullptr, "my_node", allocator, &node_name));
-  ASSERT_TRUE(node_name != nullptr);
-  EXPECT_STREQ("some_node", node_name);
-  allocator.deallocate(node_name, allocator.state);
-
-  char * namespace_name = nullptr;
-  EXPECT_EQ(RCL_RET_OK, rcl_remap_node_namespace(
-      &rcl_options->arguments, nullptr, "my_ns", allocator, &namespace_name));
-  ASSERT_TRUE(namespace_name != nullptr);
-  EXPECT_STREQ("/some_ns", namespace_name);
-  allocator.deallocate(namespace_name, allocator.state);
-}
-
-TEST(TestNodeOptions, explicit_ros_args) {
+TEST(TestNodeOptions, ros_args_only) {
   rcl_allocator_t allocator = rcl_get_default_allocator();
   auto options = rclcpp::NodeOptions(allocator)
     .arguments({"--ros-args", "-r", "__node:=some_node", "-r", "__ns:=/some_ns"});
@@ -74,7 +49,7 @@ TEST(TestNodeOptions, explicit_ros_args) {
   allocator.deallocate(namespace_name, allocator.state);
 }
 
-TEST(TestNodeOptions, explicit_ros_args_and_non_ros_args) {
+TEST(TestNodeOptions, ros_args_and_non_ros_args) {
   rcl_allocator_t allocator = rcl_get_default_allocator();
   auto options = rclcpp::NodeOptions(allocator).arguments({
     "--non-ros-flag", "--ros-args", "-r", "__node:=some_node",
diff --git a/rclcpp_components/src/component_manager.cpp b/rclcpp_components/src/component_manager.cpp
index a19c26407b..edd20fdb9f 100644
--- a/rclcpp_components/src/component_manager.cpp
+++ b/rclcpp_components/src/component_manager.cpp
@@ -143,7 +143,8 @@ ComponentManager::OnLoadNode(
       }
 
       std::vector<std::string> remap_rules;
-      remap_rules.reserve(request->remap_rules.size() * 2);
+      remap_rules.reserve(request->remap_rules.size() * 2 + 1);
+      remap_rules.push_back("--ros-args");
       for (const std::string & rule : request->remap_rules) {
         remap_rules.push_back("-r");
         remap_rules.push_back(rule);