Skip to content

JTC add more options for tolerance configuration #1677

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

Draft
wants to merge 4 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
controller_interface::CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state) override;

// New methods to handle velocity and acceleration tolerances
void setVelocityTolerance(double tolerance);
void setAccelerationTolerance(double tolerance);

protected:
// To reduce number of variables and to make the code shorter the interfaces are ordered in types
// as the following constants
Expand Down Expand Up @@ -290,6 +294,9 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
joint_interface[index].get().set_value(trajectory_point_interface[map_cmd_to_joints_[index]]);
}
}

double velocity_tolerance_;
double acceleration_tolerance_;
};

} // namespace joint_trajectory_controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,10 @@ controller_interface::CallbackReturn JointTrajectoryController::on_init()
// Create the parameter listener and get the parameters
param_listener_ = std::make_shared<ParamListener>(get_node());
params_ = param_listener_->get_params();
// Read new velocity and acceleration tolerances
velocity_tolerance_ = get_node()->get_parameter("constraints.velocity_tolerance").as_double();
acceleration_tolerance_ =
get_node()->get_parameter("constraints.acceleration_tolerance").as_double();
Comment on lines +58 to +61
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

you don't need to use get_parameter() method. Have a look at the structure params_ , generate_parameter_library automatically fills this.

}
catch (const std::exception & e)
{
Expand Down
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I suggest adding the parameters constraints.__map_joints.trajectory_velocity, constraints.__map_joints.goal_velocity etc. We cannot easily rename the old parameters, as it would change existing code. If necessary, we have to deprecate the old parameters and add something like
constraints.__map_joints.path.position
constraints.__map_joints.path.velocity
constraints.__map_joints.path.acceleration

Original file line number Diff line number Diff line change
Expand Up @@ -160,3 +160,13 @@ joint_trajectory_controller:
default_value: 0.0,
description: "Per-joint trajectory offset tolerance at the goal position.",
}
velocity_tolerance: {
type: double,
default_value: 0.0,
description: "Velocity tolerance for trajectory segments.",
}
acceleration_tolerance: {
type: double,
default_value: 0.0,
description: "Acceleration tolerance for trajectory segments.",
}
Original file line number Diff line number Diff line change
Expand Up @@ -10,3 +10,7 @@ test_joint_trajectory_controller:

state_interfaces:
- position

constraints:
velocity_tolerance: 0.05
acceleration_tolerance: 0.1
Loading