Skip to content
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

[JTC] Deprecate start_with_holding #1076

Merged
Merged
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 @@ -930,6 +930,14 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
{
add_new_trajectory_msg(set_hold_position());
}
else
{
RCLCPP_WARN(
get_node()->get_logger(),
"Parameter \"start_with_holding\" is deprecated. "
"It will be removed in a future release and start with holding position will be the default "
"behavior.");
}
rt_is_holding_.writeFromNonRT(true);

// parse timeout parameter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ joint_trajectory_controller:
start_with_holding: {
type: bool,
default_value: true,
description: "If true, start with holding position after activation. Otherwise, no command will be sent until the first trajectory is received.",
description: "(Deprecated) If true, start with holding position after activation. Otherwise, no command will be sent until the first trajectory is received.",
}
allow_nonzero_velocity_at_trajectory_end: {
type: bool,
Expand Down
Loading