forked from PickNikRobotics/generate_parameter_library
-
Notifications
You must be signed in to change notification settings - Fork 0
Separate declare and get params #1
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
Open
saikishor
wants to merge
19
commits into
main
Choose a base branch
from
separate_declare_and_get_params
base: main
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Changes from 3 commits
Commits
Show all changes
19 commits
Select commit
Hold shift + click to select a range
e8a11b4
add retrieve_params method to get params from the declare_params
saikishor 4007b53
added initialize_params parameter ad some helper methods to check the…
saikishor 54e2205
Added method to get the internal params copy
saikishor 52a14cc
apply formatting suggestions
saikishor 2281dd2
revert the changes
saikishor 46c0270
add latest_stamp variable to track the changes of the parameters
saikishor 3ee6864
update get_params method to get the declared params locally
saikishor 5bf0775
separate dynamic parameters declaration and parameter value retrieval
saikishor dc4d5a0
update parameters in update cb only when there is a validation present
saikishor 2a7a2ec
always have normal parameter as they might be useful for map of dynam…
saikishor 1648e53
remove the unused update_interal_params method and internal params va…
saikishor 4e557b3
deprecate the refresh_dynamic_parameters method
saikishor dc8500d
remove timestamp update from the declare_params method
saikishor 7651f1c
throw exception if the params are not loaded yet and get_params is in…
saikishor a89d00f
don't perform validation in the get_params method
saikishor acfbd73
use Params object instead of get_params method in the update callback
saikishor aa207d6
use internal methods to update the param state for update callback
saikishor 9ecb96f
optimize get_params to use internal variable with some logic
saikishor 62383cb
retrieve the main dynamic map parameter parent params and pass to set…
saikishor File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -91,45 +91,57 @@ struct StackParams { | |
class ParamListener{ | ||
public: | ||
// throws rclcpp::exceptions::InvalidParameterValueException on initialization if invalid parameter are loaded | ||
ParamListener(rclcpp::Node::SharedPtr node, std::string const& prefix = "") | ||
: ParamListener(node->get_node_parameters_interface(), node->get_logger(), prefix) {} | ||
ParamListener(rclcpp::Node::SharedPtr node, std::string const& prefix = "", bool initialize_params = true) | ||
: ParamListener(node->get_node_parameters_interface(), node->get_logger(), prefix, initialize_params) {} | ||
|
||
ParamListener(rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::string const& prefix = "") | ||
: ParamListener(node->get_node_parameters_interface(), node->get_logger(), prefix) {} | ||
ParamListener(rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::string const& prefix = "", bool initialize_params = true) | ||
: ParamListener(node->get_node_parameters_interface(), node->get_logger(), prefix, initialize_params) {} | ||
|
||
ParamListener(const std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>& parameters_interface, | ||
std::string const& prefix = "") | ||
: ParamListener(parameters_interface, rclcpp::get_logger("{{namespace}}"), prefix) { | ||
std::string const& prefix = "", bool initialize_params = true) | ||
: ParamListener(parameters_interface, rclcpp::get_logger("{{namespace}}"), prefix, initialize_params) { | ||
RCLCPP_DEBUG(logger_, "ParameterListener: Not using node logger, recommend using other constructors to use a node logger"); | ||
} | ||
|
||
ParamListener(const std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>& parameters_interface, | ||
rclcpp::Logger logger, std::string const& prefix = "") { | ||
rclcpp::Logger logger, std::string const& prefix = "", bool initialize_params = true) { | ||
logger_ = logger; | ||
prefix_ = prefix; | ||
are_parameters_initialized_ = false; | ||
if (!prefix_.empty() && prefix_.back() != '.') { | ||
prefix_ += "."; | ||
} | ||
|
||
parameters_interface_ = parameters_interface; | ||
declare_params(); | ||
if(initialize_params) | ||
initialize_parameters(); | ||
auto update_param_cb = [this](const std::vector<rclcpp::Parameter> ¶meters){return this->update(parameters);}; | ||
handle_ = parameters_interface_->add_on_set_parameters_callback(update_param_cb); | ||
clock_ = rclcpp::Clock(); | ||
} | ||
|
||
Params get_params() const{ | ||
std::lock_guard<std::mutex> lock(mutex_); | ||
if(!are_parameters_initialized_) | ||
{ | ||
throw std::runtime_error("Please initialize the parameters using initialize_parameters method, before getting them!"); | ||
} | ||
return params_; | ||
} | ||
|
||
bool are_params_initialized() const | ||
{ | ||
return are_parameters_initialized_; | ||
} | ||
|
||
bool is_old(Params const& other) const { | ||
std::lock_guard<std::mutex> lock(mutex_); | ||
return params_.__stamp != other.__stamp; | ||
} | ||
|
||
StackParams get_stack_params() { | ||
Params params = get_params(); | ||
Params params = get_internal_params_copy(); | ||
StackParams output; | ||
|
||
{%- filter indent(width=6) %} | ||
|
@@ -140,7 +152,7 @@ struct StackParams { | |
} | ||
|
||
void refresh_dynamic_parameters() { | ||
auto updated_params = get_params(); | ||
auto updated_params = get_internal_params_copy(); | ||
// TODO remove any destroyed dynamic parameters | ||
{%- filter indent(width=6) %} | ||
{{remove_dynamic_parameters}} | ||
|
@@ -153,7 +165,7 @@ struct StackParams { | |
} | ||
|
||
rcl_interfaces::msg::SetParametersResult update(const std::vector<rclcpp::Parameter> ¶meters) { | ||
auto updated_params = get_params(); | ||
auto updated_params = get_internal_params_copy(); | ||
|
||
for (const auto ¶m: parameters) { | ||
{%- filter indent(width=8) %} | ||
|
@@ -174,11 +186,15 @@ struct StackParams { | |
} | ||
|
||
void declare_params(){ | ||
auto updated_params = get_params(); | ||
auto updated_params = get_internal_params_copy(); | ||
// declare all parameters and give default values to non-required ones | ||
{%- filter indent(width=6) %} | ||
{{declare_params}} | ||
{%- endfilter %} | ||
} | ||
|
||
void initialize_parameters(){ | ||
auto updated_params = get_internal_params_copy(); | ||
// get parameters and fill struct fields | ||
rclcpp::Parameter param; | ||
|
||
|
@@ -194,17 +210,25 @@ struct StackParams { | |
|
||
updated_params.__stamp = clock_.now(); | ||
update_interal_params(updated_params); | ||
} | ||
are_parameters_initialized_ = true; | ||
} | ||
|
||
private: | ||
void update_interal_params(Params updated_params) { | ||
std::lock_guard<std::mutex> lock(mutex_); | ||
params_ = updated_params; | ||
} | ||
|
||
Params get_internal_params_copy() const{ | ||
std::lock_guard<std::mutex> lock(mutex_); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. so we need the mutex here? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I think as we are accessing the the |
||
return params_; | ||
} | ||
|
||
|
||
std::string prefix_; | ||
Params params_; | ||
rclcpp::Clock clock_; | ||
bool are_parameters_initialized_; | ||
std::shared_ptr<rclcpp::node_interfaces::OnSetParametersCallbackHandle> handle_; | ||
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface_; | ||
|
||
|
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.