Skip to content

Commit

Permalink
Address PR comments
Browse files Browse the repository at this point in the history
Signed-off-by: Mauro Passerino <mpasserino@irobot.com>
  • Loading branch information
Mauro Passerino authored and mergify-bot committed Nov 29, 2021
1 parent fa6e493 commit 835d435
Show file tree
Hide file tree
Showing 12 changed files with 15 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ namespace detail

/// Adds the guard condition to a waitset
/**
* This function is thread-safe.
* \param[in] wait_set reference to a wait set where to add the guard condition
* \param[in] guard_condition reference to the guard_condition to be added
*/
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -322,7 +322,7 @@ NodeBase::get_notify_guard_condition()
{
std::lock_guard<std::recursive_mutex> notify_condition_lock(notify_guard_condition_mutex_);
if (!notify_guard_condition_is_valid_) {
throw std::runtime_error("Trying to get invalid notify guard condition");
throw std::runtime_error("failed to get notify guard condition because it is invalid");
}
return notify_guard_condition_;
}
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -538,7 +538,7 @@ NodeGraph::notify_graph_change()
node_gc.trigger();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
std::string("Failed to notify wait set on graph change: ") + ex.what());
std::string("failed to notify wait set on graph change: ") + ex.what());
}
}

Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_services.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ NodeServices::add_service(
node_gc.trigger();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
std::string("Failed to notify wait set on service creation: ") + ex.what());
std::string("failed to notify wait set on service creation: ") + ex.what());
}
}

Expand All @@ -71,7 +71,7 @@ NodeServices::add_client(
node_gc.trigger();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
std::string("Failed to notify wait set on client creation: ") + ex.what());
std::string("failed to notify wait set on client creation: ") + ex.what());
}
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_timers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ NodeTimers::add_timer(
node_gc.trigger();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
std::string("Failed to notify wait set on timer creation: ") + ex.what());
std::string("failed to notify wait set on timer creation: ") + ex.what());
}

TRACEPOINT(
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_topics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ NodeTopics::add_publisher(
node_gc.trigger();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
std::string("Failed to notify wait set on publisher creation: ") + ex.what());
std::string("failed to notify wait set on publisher creation: ") + ex.what());
}
}

Expand Down Expand Up @@ -112,7 +112,7 @@ NodeTopics::add_subscription(
node_gc.trigger();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
std::string("Failed to notify wait set on subscription creation: ") + ex.what());
std::string("failed to notify wait set on subscription creation: ") + ex.what());
}
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ NodeWaitables::add_waitable(
node_gc.trigger();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
std::string("Failed to notify wait set on waitable creation: ") + ex.what());
std::string("failed to notify wait set on waitable creation: ") + ex.what());
}
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/node_interfaces/test_node_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -558,7 +558,7 @@ TEST_F(TestNodeGraph, notify_graph_change_rcl_error)
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node()->get_node_graph_interface()->notify_graph_change(),
std::runtime_error("Failed to notify wait set on graph change: error not set"));
std::runtime_error("failed to notify wait set on graph change: error not set"));
}

TEST_F(TestNodeGraph, get_info_by_topic)
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/rclcpp/node_interfaces/test_node_services.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ TEST_F(TestNodeService, add_service_rcl_trigger_guard_condition_error)
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_services->add_service(service, callback_group),
std::runtime_error("Failed to notify wait set on service creation: error not set"));
std::runtime_error("failed to notify wait set on service creation: error not set"));
}

TEST_F(TestNodeService, add_client)
Expand All @@ -130,7 +130,7 @@ TEST_F(TestNodeService, add_client_rcl_trigger_guard_condition_error)
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_services->add_client(client, callback_group),
std::runtime_error("Failed to notify wait set on client creation: error not set"));
std::runtime_error("failed to notify wait set on client creation: error not set"));
}

TEST_F(TestNodeService, resolve_service_name)
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/node_interfaces/test_node_timers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,5 +87,5 @@ TEST_F(TestNodeTimers, add_timer_rcl_trigger_guard_condition_error)
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_timers->add_timer(timer, callback_group),
std::runtime_error("Failed to notify wait set on timer creation: error not set"));
std::runtime_error("failed to notify wait set on timer creation: error not set"));
}
4 changes: 2 additions & 2 deletions rclcpp/test/rclcpp/node_interfaces/test_node_topics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ TEST_F(TestNodeTopics, add_publisher_rcl_trigger_guard_condition_error)
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_topics->add_publisher(publisher, callback_group),
std::runtime_error("Failed to notify wait set on publisher creation: error not set"));
std::runtime_error("failed to notify wait set on publisher creation: error not set"));
}

TEST_F(TestNodeTopics, add_subscription)
Expand Down Expand Up @@ -157,7 +157,7 @@ TEST_F(TestNodeTopics, add_subscription_rcl_trigger_guard_condition_error)
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_topics->add_subscription(subscription, callback_group),
std::runtime_error("Failed to notify wait set on subscription creation: error not set"));
std::runtime_error("failed to notify wait set on subscription creation: error not set"));
}

TEST_F(TestNodeTopics, resolve_topic_name)
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,5 +96,5 @@ TEST_F(TestNodeWaitables, add_waitable_rcl_trigger_guard_condition_error)
"lib:rclcpp", rcl_trigger_guard_condition, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node_waitables->add_waitable(waitable, callback_group),
std::runtime_error("Failed to notify wait set on waitable creation: error not set"));
std::runtime_error("failed to notify wait set on waitable creation: error not set"));
}

0 comments on commit 835d435

Please sign in to comment.