Skip to content

Commit

Permalink
always allow unconfigured param changes
Browse files Browse the repository at this point in the history
  • Loading branch information
Aron Svastits committed Apr 30, 2024
1 parent 554ac30 commit 48a83db
Show file tree
Hide file tree
Showing 5 changed files with 21 additions and 26 deletions.
8 changes: 4 additions & 4 deletions kuka_drivers_core/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ Improvements:
- The parameter type is enforced automatically.
- The registered callback has access over all of the registered parameters, therefore the parameter server and the node is always in sync
- It is easy to register a callback for additional checks before requested parameter value is accepted.
- The user can define the lifecycle states, in which parameter changes are allowed.
- The user can define the lifecycle states, in which parameter changes are allowed using the `ParameterSetAccessRights` structure.
- There is a different endpoint for static parameters, which cannot be changed after initialization.
The `Parameter<T>` class supports the following parameter types (identical to the types supported by `rclcpp::Parameter`):
Expand All @@ -98,7 +98,7 @@ The `Parameter<T>` class supports the following parameter types (identical to th
The nodes provide the `registerParameter()` and `registerStaticParameter()` endpoints with the following arguments:
- `name` [std::string]: name of the parameter
- `value` [T]: default value of the parameter
- `rights` [ParameterAccessRights]: structure defining in which states is the setting of the parameter allowed (only for ROS2BaseLCNode)
- `rights` [ParameterSetAccessRights]: structure defining whether modifying the parameter value is allowed in `inactive` and `active` states (only for `ROS2BaseLCNode`, value changes are always allowed in `unconfigured` state)
- `on_change_callback` [std::function<bool(const T &)>]: the callback to call when determining the validity of a parameter change request
Both methods register a parameter with the given `name` and `type`, and the `on_change_callback` is called if a parameter change is requested to check validity. In case of the `registerStaticParameter()`, the callback always returns false after initializing the value.
Expand All @@ -107,8 +107,8 @@ Example code for registering an integer parameter for both base nodes (`onRateCh
```C++
// For class derived from ROS2BaseLCNode
registerParameter<int>(
"rate", 2, kuka_drivers_core::ParameterSetAccessRights {true, true,
false}, [this](int rate) {
"rate", 2, kuka_drivers_core::ParameterSetAccessRights {true, false},
[this](int rate) {
return this->onRateChangeRequest(rate);
});
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,15 +28,14 @@ namespace kuka_drivers_core
{
struct ParameterSetAccessRights
{
bool unconfigured;
bool inactive;
bool active;
bool isSetAllowed(std::uint8_t current_state) const
{
switch (current_state)
{
case lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED:
return unconfigured;
return true;
case lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE:
return inactive;
case lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE:
Expand Down
13 changes: 6 additions & 7 deletions kuka_iiqka_eac_driver/src/robot_manager_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,38 +59,37 @@ RobotManagerNode::RobotManagerNode() : kuka_drivers_core::ROS2BaseLCNode("robot_
// Register parameters
this->registerParameter<std::string>(
"position_controller_name", kuka_drivers_core::JOINT_TRAJECTORY_CONTROLLER,
kuka_drivers_core::ParameterSetAccessRights{true, true, false},
kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](const std::string & controller_name)
{
return this->controller_handler_.UpdateControllerName(
kuka_drivers_core::ControllerType::JOINT_POSITION_CONTROLLER_TYPE, controller_name);
});
this->registerParameter<std::string>(
"impedance_controller_name", "joint_group_impedance_controllers",
kuka_drivers_core::ParameterSetAccessRights{true, true, false},
kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](const std::string & controller_name)
{
return this->controller_handler_.UpdateControllerName(
kuka_drivers_core::ControllerType::JOINT_IMPEDANCE_CONTROLLER_TYPE, controller_name);
});
this->registerParameter<std::string>(
"torque_controller_name", "effort_controller",
kuka_drivers_core::ParameterSetAccessRights{true, true, false},
kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](const std::string & controller_name)
{
return this->controller_handler_.UpdateControllerName(
kuka_drivers_core::ControllerType::TORQUE_CONTROLLER_TYPE, controller_name);
});
this->registerParameter<int>(
"control_mode", static_cast<int>(kuka_drivers_core::ControlMode::JOINT_POSITION_CONTROL),
kuka_drivers_core::ParameterSetAccessRights{true, true, true},
kuka_drivers_core::ParameterSetAccessRights{true, true},
[this](int control_mode) { return this->onControlModeChangeRequest(control_mode); });
this->registerStaticParameter<std::string>(
"controller_ip", "", kuka_drivers_core::ParameterSetAccessRights{true, false, false},
"controller_ip", "", kuka_drivers_core::ParameterSetAccessRights{false, false},
[this](const std::string &) { return true; });
this->registerStaticParameter<std::string>(
"robot_model", "lbr_iisy3_r760",
kuka_drivers_core::ParameterSetAccessRights{true, false, false},
"robot_model", "lbr_iisy3_r760", kuka_drivers_core::ParameterSetAccessRights{false, false},
[this](const std::string & robot_model)
{ return this->onRobotModelChangeRequest(robot_model); });
}
Expand Down
2 changes: 1 addition & 1 deletion kuka_kss_rsi_driver/src/robot_manager_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ RobotManagerNode::RobotManagerNode() : kuka_drivers_core::ROS2BaseLCNode("robot_
this->create_publisher<std_msgs::msg::Bool>("robot_manager/is_configured", is_configured_qos);

this->registerStaticParameter<std::string>(
"robot_model", "kr6_r700_sixx", kuka_drivers_core::ParameterSetAccessRights{true, false, false},
"robot_model", "kr6_r700_sixx", kuka_drivers_core::ParameterSetAccessRights{false, false},
[this](const std::string & robot_model)
{ return this->onRobotModelChangeRequest(robot_model); });
}
Expand Down
21 changes: 9 additions & 12 deletions kuka_sunrise_fri_driver/src/robot_manager_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,53 +68,51 @@ RobotManagerNode::RobotManagerNode() : kuka_drivers_core::ROS2BaseLCNode("robot_
sub_options);

registerStaticParameter<std::string>(
"robot_model", "lbr_iiwa14_r820",
kuka_drivers_core::ParameterSetAccessRights{true, false, false},
"robot_model", "lbr_iiwa14_r820", kuka_drivers_core::ParameterSetAccessRights{false, false},
[this](const std::string & robot_model)
{ return this->onRobotModelChangeRequest(robot_model); });

registerStaticParameter<std::string>(
"controller_ip", "", kuka_drivers_core::ParameterSetAccessRights{true, false, false},
"controller_ip", "", kuka_drivers_core::ParameterSetAccessRights{false, false},
[this](const std::string & controller_ip) { return this->ValidateIPAdress(controller_ip); });

registerParameter<int>(
"send_period_ms", 10, kuka_drivers_core::ParameterSetAccessRights{true, true, false},
"send_period_ms", 10, kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](const int & send_period) { return this->onSendPeriodChangeRequest(send_period); });

registerParameter<int>(
"receive_multiplier", 1, kuka_drivers_core::ParameterSetAccessRights{true, true, false},
"receive_multiplier", 1, kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](const int & receive_multiplier)
{ return this->onReceiveMultiplierChangeRequest(receive_multiplier); });

registerParameter<int>(
"control_mode", static_cast<int>(kuka_drivers_core::ControlMode::JOINT_POSITION_CONTROL),
kuka_drivers_core::ParameterSetAccessRights{true, true, false},
kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](int control_mode) { return this->onControlModeChangeRequest(control_mode); });

registerParameter<std::string>(
"position_controller_name", "", kuka_drivers_core::ParameterSetAccessRights{true, true, false},
"position_controller_name", "", kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](const std::string & controller_name)
{
return this->onControllerNameChangeRequest(
controller_name, kuka_drivers_core::ControllerType::JOINT_POSITION_CONTROLLER_TYPE);
});

registerParameter<std::string>(
"torque_controller_name", "", kuka_drivers_core::ParameterSetAccessRights{true, true, false},
"torque_controller_name", "", kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](const std::string & controller_name)
{
return this->onControllerNameChangeRequest(
controller_name, kuka_drivers_core::ControllerType::TORQUE_CONTROLLER_TYPE);
});

registerParameter<std::vector<double>>(
"joint_stiffness", joint_stiffness_,
kuka_drivers_core::ParameterSetAccessRights{true, true, false},
"joint_stiffness", joint_stiffness_, kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](const std::vector<double> & joint_stiffness)
{ return this->onJointStiffnessChangeRequest(joint_stiffness); });

registerParameter<std::vector<double>>(
"joint_damping", joint_damping_, kuka_drivers_core::ParameterSetAccessRights{true, true, false},
"joint_damping", joint_damping_, kuka_drivers_core::ParameterSetAccessRights{true, false},
[this](const std::vector<double> & joint_damping)
{ return this->onJointDampingChangeRequest(joint_damping); });
}
Expand Down Expand Up @@ -376,7 +374,6 @@ bool RobotManagerNode::ValidateIPAdress(std::string_view controller_ip) const
return true;
}


bool RobotManagerNode::onControllerNameChangeRequest(
std::string_view controller_name, kuka_drivers_core::ControllerType controller_type)
{
Expand Down

0 comments on commit 48a83db

Please sign in to comment.