Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Deprecate set_on_parameters_set_callback #1123

Merged
merged 25 commits into from May 27, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
7ea9978
add deprecate statement
claireyywang May 20, 2020
f6dc89e
replace tests to use add_on_param fn
claireyywang May 21, 2020
4640360
deprecate set_on_pram fn in node_parameters
claireyywang May 21, 2020
2f78102
deprecate in lifecycle_node and add replacement fn
claireyywang May 21, 2020
f4837e8
replace set_on_param
claireyywang May 21, 2020
2bd8006
deref shared_ptr
claireyywang May 21, 2020
de49681
deref ptrs 2 try
claireyywang May 21, 2020
c63ddf4
correct typo in lifecycle node
claireyywang May 21, 2020
a0ba91b
correct type in rclcpp_lifecyclenode
claireyywang May 22, 2020
3187942
update documentation
claireyywang May 22, 2020
ba8e395
add warning suppression to test_node.cpp
claireyywang May 22, 2020
5f72b50
correct namespace in lifecycle_node.cpp
claireyywang May 22, 2020
4faa099
remove whitespace
claireyywang May 22, 2020
193a07d
fix line length in lifecycle_node
claireyywang May 22, 2020
a5220c6
fix deprecate typo
claireyywang May 26, 2020
e937b50
remove add_on and remove_on fns
claireyywang May 26, 2020
3f9819f
move reset fn to below add_on
claireyywang May 26, 2020
4e1951a
correct deprecated typo
claireyywang May 26, 2020
339f119
correct another deprecate typo
claireyywang May 26, 2020
9969c54
correct typo
claireyywang May 26, 2020
713191e
deprecate set_on in test_lifecycle_node
claireyywang May 26, 2020
7796902
Merge branch 'master' into claire/deprecate_set_on_param_fn
claireyywang May 26, 2020
b6b7d3d
Merge branch 'master' into claire/deprecate_set_on_param_fn
claireyywang May 26, 2020
8c5666c
suppress deprecation warning in node.cpp
claireyywang May 26, 2020
3bc9cfc
suppress warning in lifecycle_node.cpp
claireyywang May 26, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
16 changes: 9 additions & 7 deletions rclcpp/include/rclcpp/node.hpp
Expand Up @@ -277,7 +277,7 @@ class Node : public std::enable_shared_from_this<Node>
* If `ignore_override` is `true`, the parameter override will be ignored.
*
* This method, if successful, will result in any callback registered with
* set_on_parameters_set_callback to be called.
* add_on_set_parameters_callback to be called.
* If that callback prevents the initial value for the parameter from being
* set then rclcpp::exceptions::InvalidParameterValueException is thrown.
*
Expand Down Expand Up @@ -359,7 +359,7 @@ class Node : public std::enable_shared_from_this<Node>
* by the function call will be ignored.
*
* This method, if successful, will result in any callback registered with
* set_on_parameters_set_callback to be called, once for each parameter.
* add_on_set_parameters_callback to be called, once for each parameter.
* If that callback prevents the initial value for any parameter from being
* set then rclcpp::exceptions::InvalidParameterValueException is thrown.
*
Expand Down Expand Up @@ -401,7 +401,7 @@ class Node : public std::enable_shared_from_this<Node>
/// Undeclare a previously declared parameter.
/**
* This method will not cause a callback registered with
* set_on_parameters_set_callback to be called.
* add_on_set_parameters_callback to be called.
*
* \param[in] name The name of the parameter to be undeclared.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if the parameter
Expand Down Expand Up @@ -435,7 +435,7 @@ class Node : public std::enable_shared_from_this<Node>
* Parameter overrides are ignored by set_parameter.
*
* This method will result in any callback registered with
* set_on_parameters_set_callback to be called.
* add_on_set_parameters_callback to be called.
* If the callback prevents the parameter from being set, then it will be
* reflected in the SetParametersResult that is returned, but no exception
* will be thrown.
Expand Down Expand Up @@ -476,7 +476,7 @@ class Node : public std::enable_shared_from_this<Node>
* corresponding SetParametersResult in the vector returned by this function.
*
* This method will result in any callback registered with
* set_on_parameters_set_callback to be called, once for each parameter.
* add_on_set_parameters_callback to be called, once for each parameter.
* If the callback prevents the parameter from being set, then, as mentioned
* before, it will be reflected in the corresponding SetParametersResult
* that is returned, but no exception will be thrown.
Expand Down Expand Up @@ -507,7 +507,7 @@ class Node : public std::enable_shared_from_this<Node>
* If the exception is thrown then none of the parameters will have been set.
*
* This method will result in any callback registered with
* set_on_parameters_set_callback to be called, just one time.
* add_on_set_parameters_callback to be called, just one time.
* If the callback prevents the parameters from being set, then it will be
* reflected in the SetParametersResult which is returned, but no exception
* will be thrown.
Expand Down Expand Up @@ -787,7 +787,7 @@ class Node : public std::enable_shared_from_this<Node>
* of the {get,list,describe}_parameter() methods), but may *not* modify
* other parameters (by calling any of the {set,declare}_parameter() methods)
* or modify the registered callback itself (by calling the
* set_on_parameters_set_callback() method). If a callback tries to do any
* add_on_set_parameters_callback() method). If a callback tries to do any
* of the latter things,
* rclcpp::exceptions::ParameterModifiedInCallbackException will be thrown.
*
Expand Down Expand Up @@ -839,6 +839,7 @@ class Node : public std::enable_shared_from_this<Node>

/// Register a callback to be called anytime a parameter is about to be changed.
/**
* \deprecated Use add_on_set_parameters_callback instead.
* With this method, only one callback can be set at a time. The callback that was previously
* set by this method is returned or `nullptr` if no callback was previously set.
*
Expand All @@ -851,6 +852,7 @@ class Node : public std::enable_shared_from_this<Node>
* \return The previous callback that was registered, if there was one,
* otherwise nullptr.
*/
[[deprecated("use add_on_set_parameters_callback(OnParametersSetCallbackType callback) instead")]]
RCLCPP_PUBLIC
OnParametersSetCallbackType
set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback);
Expand Down
Expand Up @@ -167,6 +167,7 @@ class NodeParameters : public NodeParametersInterface
void
remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * const handler) override;

[[deprecated("use add_on_set_parameters_callback(OnParametersSetCallbackType callback) instead")]]
RCLCPP_PUBLIC
OnParametersSetCallbackType
set_on_parameters_set_callback(OnParametersSetCallbackType callback) override;
Expand Down
Expand Up @@ -193,8 +193,10 @@ class NodeParametersInterface

/// Register a callback for when parameters are being set, return an existing one.
/**
* \deprecated Use add_on_set_parameters_callback instead.
* \sa rclcpp::Node::set_on_parameters_set_callback
*/
[[deprecated("use add_on_set_parameters_callback(OnParametersSetCallbackType callback) instead")]]
RCLCPP_PUBLIC
virtual
OnParametersSetCallbackType
Expand Down
16 changes: 16 additions & 0 deletions rclcpp/src/rclcpp/node.cpp
Expand Up @@ -328,12 +328,28 @@ Node::remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * co
return node_parameters_->remove_on_set_parameters_callback(callback);
}

// suppress deprecated function warning
#if !defined(_WIN32)
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else // !defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif

rclcpp::Node::OnParametersSetCallbackType
Node::set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback)
{
return node_parameters_->set_on_parameters_set_callback(callback);
}

// remove warning suppression
#if !defined(_WIN32)
# pragma GCC diagnostic pop
#else // !defined(_WIN32)
# pragma warning(pop)
#endif

std::vector<std::string>
Node::get_node_names() const
{
Expand Down
44 changes: 30 additions & 14 deletions rclcpp/test/test_node.cpp
Expand Up @@ -349,7 +349,6 @@ TEST_F(TestNode, declare_parameter_with_no_initial_values) {
}
{
// parameter rejected throws
RCLCPP_SCOPE_EXIT({node->set_on_parameters_set_callback(nullptr);}); // always reset
auto name = "parameter"_unq;
auto on_set_parameters =
[&name](const std::vector<rclcpp::Parameter> & parameters) {
Expand All @@ -366,7 +365,8 @@ TEST_F(TestNode, declare_parameter_with_no_initial_values) {
}
return result;
};
EXPECT_EQ(node->set_on_parameters_set_callback(on_set_parameters), nullptr);
auto handler = node->add_on_set_parameters_callback(on_set_parameters);
RCLCPP_SCOPE_EXIT({node->remove_on_set_parameters_callback(handler.get());}); // always reset
EXPECT_THROW(
{node->declare_parameter<std::string>(name, "not an int");},
rclcpp::exceptions::InvalidParameterValueException);
Expand Down Expand Up @@ -546,7 +546,6 @@ TEST_F(TestNode, declare_parameter_with_overrides) {
}
{
// parameter rejected throws, with initial value
RCLCPP_SCOPE_EXIT({node->set_on_parameters_set_callback(nullptr);}); // always reset
auto name = std::string("parameter_rejected");
auto on_set_parameters =
[&name](const std::vector<rclcpp::Parameter> & parameters) {
Expand All @@ -565,7 +564,8 @@ TEST_F(TestNode, declare_parameter_with_overrides) {
}
return result;
};
EXPECT_EQ(node->set_on_parameters_set_callback(on_set_parameters), nullptr);
auto handler = node->add_on_set_parameters_callback(on_set_parameters);
RCLCPP_SCOPE_EXIT({node->remove_on_set_parameters_callback(handler.get());}); // always reset
EXPECT_THROW(
{node->declare_parameter<int>(name, 43);},
rclcpp::exceptions::InvalidParameterValueException);
Expand Down Expand Up @@ -659,7 +659,6 @@ TEST_F(TestNode, declare_parameters_with_no_initial_values) {
}
{
// parameter rejected throws
RCLCPP_SCOPE_EXIT({node->set_on_parameters_set_callback(nullptr);}); // always reset
auto name = "parameter"_unq;
auto on_set_parameters =
[&name](const std::vector<rclcpp::Parameter> & parameters) {
Expand All @@ -676,7 +675,8 @@ TEST_F(TestNode, declare_parameters_with_no_initial_values) {
}
return result;
};
EXPECT_EQ(node->set_on_parameters_set_callback(on_set_parameters), nullptr);
auto handler = node->add_on_set_parameters_callback(on_set_parameters);
RCLCPP_SCOPE_EXIT({node->remove_on_set_parameters_callback(handler.get());}); // always reset
EXPECT_THROW(
{node->declare_parameters<std::string>("", {{name, "not an int"}});},
rclcpp::exceptions::InvalidParameterValueException);
Expand Down Expand Up @@ -854,15 +854,15 @@ TEST_F(TestNode, set_parameter_undeclared_parameters_not_allowed) {
auto name = "parameter"_unq;
node->declare_parameter(name, 42);

RCLCPP_SCOPE_EXIT({node->set_on_parameters_set_callback(nullptr);}); // always reset
auto on_set_parameters =
[](const std::vector<rclcpp::Parameter> &) {
rcl_interfaces::msg::SetParametersResult result;
result.successful = false;
result.reason = "no parameter may not be set right now";
return result;
};
node->set_on_parameters_set_callback(on_set_parameters);
auto handler = node->add_on_set_parameters_callback(on_set_parameters);
RCLCPP_SCOPE_EXIT({node->remove_on_set_parameters_callback(handler.get());}); // always reset

EXPECT_FALSE(node->set_parameter(rclcpp::Parameter(name, 43)).successful);
}
Expand Down Expand Up @@ -1350,7 +1350,6 @@ TEST_F(TestNode, set_parameters_undeclared_parameters_not_allowed) {
node->declare_parameter(name2, true);
node->declare_parameter<std::string>(name3, "blue");

RCLCPP_SCOPE_EXIT({node->set_on_parameters_set_callback(nullptr);}); // always reset
auto on_set_parameters =
[&name2](const std::vector<rclcpp::Parameter> & ps) {
rcl_interfaces::msg::SetParametersResult result;
Expand All @@ -1361,7 +1360,8 @@ TEST_F(TestNode, set_parameters_undeclared_parameters_not_allowed) {
}
return result;
};
node->set_on_parameters_set_callback(on_set_parameters);
auto handler = node->add_on_set_parameters_callback(on_set_parameters);
RCLCPP_SCOPE_EXIT({node->remove_on_set_parameters_callback(handler.get());}); // always reset

auto rets = node->set_parameters(
{
Expand Down Expand Up @@ -1527,7 +1527,6 @@ TEST_F(TestNode, set_parameters_atomically_undeclared_parameters_not_allowed) {
node->declare_parameter(name2, true);
node->declare_parameter<std::string>(name3, "blue");

RCLCPP_SCOPE_EXIT({node->set_on_parameters_set_callback(nullptr);}); // always reset
auto on_set_parameters =
[&name2](const std::vector<rclcpp::Parameter> & ps) {
rcl_interfaces::msg::SetParametersResult result;
Expand All @@ -1538,7 +1537,8 @@ TEST_F(TestNode, set_parameters_atomically_undeclared_parameters_not_allowed) {
}
return result;
};
node->set_on_parameters_set_callback(on_set_parameters);
auto handler = node->add_on_set_parameters_callback(on_set_parameters);
RCLCPP_SCOPE_EXIT({node->remove_on_set_parameters_callback(handler.get());}); // always reset

auto ret = node->set_parameters_atomically(
{
Expand Down Expand Up @@ -1638,7 +1638,6 @@ TEST_F(TestNode, set_parameters_atomically_undeclared_parameters_allowed) {
EXPECT_TRUE(node->has_parameter(name3));
EXPECT_EQ(node->get_parameter(name3).get_value<std::string>(), "test");

RCLCPP_SCOPE_EXIT({node->set_on_parameters_set_callback(nullptr);}); // always reset
auto on_set_parameters =
[&name3](const std::vector<rclcpp::Parameter> & ps) {
rcl_interfaces::msg::SetParametersResult result;
Expand All @@ -1649,7 +1648,8 @@ TEST_F(TestNode, set_parameters_atomically_undeclared_parameters_allowed) {
}
return result;
};
node->set_on_parameters_set_callback(on_set_parameters);
auto handler = node->add_on_set_parameters_callback(on_set_parameters);
RCLCPP_SCOPE_EXIT({node->remove_on_set_parameters_callback(handler.get());}); // always reset

auto ret = node->set_parameters_atomically(
{
Expand Down Expand Up @@ -2329,6 +2329,15 @@ TEST_F(TestNode, get_parameter_types_undeclared_parameters_allowed) {
}
}

// suppress deprecated function test warnings
#if !defined(_WIN32)
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else // !defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif

// test that it is possible to call get_parameter within the set_callback
TEST_F(TestNode, set_on_parameters_set_callback_get_parameter) {
auto node = std::make_shared<rclcpp::Node>("test_set_callback_get_parameter_node"_unq);
Expand Down Expand Up @@ -2513,6 +2522,13 @@ TEST_F(TestNode, set_on_parameters_set_callback_set_on_parameters_set_callback)
}, rclcpp::exceptions::ParameterModifiedInCallbackException);
}

// remove warning suppression
#if !defined(_WIN32)
# pragma GCC diagnostic pop
#else // !defined(_WIN32)
# pragma warning(pop)
#endif

void expect_qos_profile_eq(
const rmw_qos_profile_t & qos1, const rmw_qos_profile_t & qos2, bool is_publisher)
{
Expand Down
Expand Up @@ -472,8 +472,10 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,

/// Register a callback to be called anytime a parameter is about to be changed.
/**
* \deprecated Use add_on_set_parameters_callback instead.
* \sa rclcpp::Node::set_on_parameters_set_callback
*/
[[deprecated("use add_on_set_parameters_callback(OnParametersSetCallbackType callback) instead")]]
RCLCPP_LIFECYCLE_PUBLIC
rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType
set_on_parameters_set_callback(
Expand Down
16 changes: 16 additions & 0 deletions rclcpp_lifecycle/src/lifecycle_node.cpp
Expand Up @@ -268,12 +268,28 @@ LifecycleNode::remove_on_set_parameters_callback(
node_parameters_->remove_on_set_parameters_callback(callback);
}

// suppress deprecated function warning
#if !defined(_WIN32)
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else // !defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif

rclcpp::Node::OnParametersSetCallbackType
LifecycleNode::set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback)
{
return node_parameters_->set_on_parameters_set_callback(callback);
}

// remove warning suppression
#if !defined(_WIN32)
# pragma GCC diagnostic pop
#else // !defined(_WIN32)
# pragma warning(pop)
#endif

std::vector<std::string>
LifecycleNode::get_node_names() const
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_lifecycle/test/test_lifecycle_node.cpp
Expand Up @@ -427,7 +427,7 @@ TEST_F(TestDefaultStateMachine, check_parameters) {
return result;
};

test_node->set_on_parameters_set_callback(callback);
test_node->add_on_set_parameters_callback(callback);
rclcpp::Parameter bool_parameter(bool_name, rclcpp::ParameterValue(false));
EXPECT_TRUE(test_node->set_parameter(bool_parameter).successful);
EXPECT_EQ(parameters_set, 1u);
Expand Down