Skip to content

Commit

Permalink
Set allow_nonzero_velocity_at_trajectory_end default false
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 17, 2023
1 parent 84bd61b commit d217547
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 12 deletions.
3 changes: 1 addition & 2 deletions joint_trajectory_controller/doc/parameters.rst
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ start_with_holding (bool)
allow_nonzero_velocity_at_trajectory_end (boolean)
If false, the last velocity point has to be zero or the goal will be rejected.

Default: true
Default: false

cmd_timeout (double)
Timeout after which the input command is considered stale.
Expand Down Expand Up @@ -147,5 +147,4 @@ gains.<joint_name>.angle_wraparound (bool)
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
position :math:`s` from the state interface.


Default: false
Original file line number Diff line number Diff line change
Expand Up @@ -64,15 +64,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_init()
return CallbackReturn::ERROR;
}

// TODO(christophfroehlich): remove deprecation warning
if (params_.allow_nonzero_velocity_at_trajectory_end)
{
RCLCPP_WARN(
get_node()->get_logger(),
"[Deprecated]: \"allow_nonzero_velocity_at_trajectory_end\" is set to "
"true. The default behavior will change to false.");
}

return CallbackReturn::SUCCESS;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ joint_trajectory_controller:
}
allow_nonzero_velocity_at_trajectory_end: {
type: bool,
default_value: true,
default_value: false,
description: "If false, the last velocity point has to be zero or the goal will be rejected",
}
cmd_timeout: {
Expand Down

0 comments on commit d217547

Please sign in to comment.