Skip to content

Commit 6cbcaf1

Browse files
authored
Remove deprecated code from sjtc (#1362)
The open_loop parameter has been removed upstream, so we'll have to remove it from here, as well.
1 parent e8e8423 commit 6cbcaf1

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
133133
// if sampling the first time, set the point before you sample
134134
if (!current_trajectory_->is_sampled_already()) {
135135
first_sample = true;
136-
if (params_.interpolate_from_desired_state || params_.open_loop_control) {
136+
if (params_.interpolate_from_desired_state) {
137137
if (std::abs(last_commanded_time_.seconds()) < std::numeric_limits<float>::epsilon()) {
138138
last_commanded_time_ = time;
139139
}

0 commit comments

Comments
 (0)