Skip to content

Commit

Permalink
deal with implicitly undeclared parameters
Browse files Browse the repository at this point in the history
  • Loading branch information
christianrauch committed Feb 9, 2025
1 parent 2ddf0b0 commit 0acf73d
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 3 deletions.
6 changes: 3 additions & 3 deletions src/CameraNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ namespace camera
class CameraNode : public rclcpp::Node
{
public:
explicit CameraNode(const rclcpp::NodeOptions &options);
explicit CameraNode(rclcpp::NodeOptions options);

~CameraNode();

Expand Down Expand Up @@ -187,8 +187,8 @@ compressImageMsg(const sensor_msgs::msg::Image &source,
}


CameraNode::CameraNode(const rclcpp::NodeOptions &options)
: Node("camera", options),
CameraNode::CameraNode(rclcpp::NodeOptions options)
: Node("camera", options.allow_undeclared_parameters(true)),
cim(this),
parameter_handler(this),
param_cb_change(
Expand Down
5 changes: 5 additions & 0 deletions src/ParameterHandler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,11 @@ ParameterHandler::declare(const libcamera::ControlInfoMap &controls)
// to unset them (set their type to 'rclcpp::ParameterType::PARAMETER_NOT_SET').
// Unsetting a statically typed parameter causes "cannot undeclare a statically typed parameter".

// However, rclcpp::Node::set_parameter() implicitly undeclares a parameter if its type is
// set to rclcpp::PARAMETER_NOT_SET when it had a different type before.
// In order to re-set implicitly undeclared parameters, the node has to set
// "allow_undeclared_parameters".

ParameterConflictHandler::ParameterValueMap parameters;
for (const auto &[id, info] : controls) {
// store control name with id and info
Expand Down

0 comments on commit 0acf73d

Please sign in to comment.