Skip to content

Commit

Permalink
Make most parameters read-only
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Sep 9, 2023
1 parent fb46a77 commit 5d38539
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -885,6 +885,12 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
controller_interface::CallbackReturn JointTrajectoryController::on_activate(
const rclcpp_lifecycle::State &)
{
// update dynamic parameters
if (param_listener_->is_old(params_))
{
params_ = param_listener_->get_params();
}

// order all joints in the storage
for (const auto & interface : params_.command_interfaces)
{
Expand Down Expand Up @@ -951,7 +957,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
last_commanded_state_ = state;
}

// Should the controller start by holding position after on_configure?
// Should the controller start by holding position at the beginning of active state?
if (params_.start_with_holding)
{
add_new_trajectory_msg(set_hold_position());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ joint_trajectory_controller:
type: string_array,
default_value: [],
description: "Names of joints used by the controller",
read_only: true,
validation: {
unique<>: null,
}
Expand All @@ -11,6 +12,7 @@ joint_trajectory_controller:
type: string_array,
default_value: [],
description: "Names of the commanding joints used by the controller",
read_only: true,
validation: {
unique<>: null,
}
Expand All @@ -19,6 +21,7 @@ joint_trajectory_controller:
type: string_array,
default_value: [],
description: "Names of command interfaces to claim",
read_only: true,
validation: {
unique<>: null,
subset_of<>: [["position", "velocity", "acceleration", "effort",]],
Expand All @@ -29,6 +32,7 @@ joint_trajectory_controller:
type: string_array,
default_value: [],
description: "Names of state interfaces to claim",
read_only: true,
validation: {
unique<>: null,
subset_of<>: [["position", "velocity", "acceleration",]],
Expand All @@ -44,6 +48,7 @@ joint_trajectory_controller:
type: bool,
default_value: false,
description: "Run the controller in open-loop, i.e., read hardware states only when starting controller. This is useful when robot is not exactly following the commanded trajectory.",
read_only: true,
}
allow_integration_in_goal_trajectories: {
type: bool,
Expand All @@ -54,6 +59,7 @@ joint_trajectory_controller:
type: double,
default_value: 20.0,
description: "Rate status changes will be monitored",
read_only: true,
validation: {
gt_eq: [0.1]
}
Expand All @@ -62,6 +68,7 @@ joint_trajectory_controller:
type: string,
default_value: "splines",
description: "The type of interpolation to use, if any",
read_only: true,
validation: {
one_of<>: [["splines", "none"]],
}
Expand Down

0 comments on commit 5d38539

Please sign in to comment.