Skip to content

Commit 3506801

Browse files
author
AndyZe
authored
Fix warning about deprecated controller_interface::return_type::SUCCESS (#68)
1 parent 3aaf9c3 commit 3506801

File tree

3 files changed

+6
-6
lines changed

3 files changed

+6
-6
lines changed

ur_controllers/src/force_torque_sensor_controller.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ ForceTorqueStateController::ForceTorqueStateController()
2424
controller_interface::return_type ForceTorqueStateController::init(const std::string& controller_name)
2525
{
2626
auto ret = ControllerInterface::init(controller_name);
27-
if (ret != controller_interface::return_type::SUCCESS)
27+
if (ret != controller_interface::return_type::OK)
2828
{
2929
return ret;
3030
}
@@ -43,7 +43,7 @@ controller_interface::return_type ForceTorqueStateController::init(const std::st
4343
return controller_interface::return_type::ERROR;
4444
}
4545

46-
return controller_interface::return_type::SUCCESS;
46+
return controller_interface::return_type::OK;
4747
}
4848

4949
controller_interface::InterfaceConfiguration ForceTorqueStateController::command_interface_configuration() const
@@ -110,7 +110,7 @@ controller_interface::return_type ur_controllers::ForceTorqueStateController::up
110110
// publish
111111
wrench_state_publisher_->publish(wrench_state_msg_);
112112

113-
return controller_interface::return_type::SUCCESS;
113+
return controller_interface::return_type::OK;
114114
}
115115

116116
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update()
6262
halt();
6363
is_halted = true;
6464
}
65-
return controller_interface::return_type::SUCCESS;
65+
return controller_interface::return_type::OK;
6666
}
6767

6868
auto resize_joint_trajectory_point = [](trajectory_msgs::msg::JointTrajectoryPoint& point, size_t size) {
@@ -217,7 +217,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update()
217217
}
218218

219219
publish_state(state_desired, state_current, state_error);
220-
return controller_interface::return_type::SUCCESS;
220+
return controller_interface::return_type::OK;
221221
}
222222

223223
} // namespace ur_controllers

ur_controllers/src/speed_scaling_state_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ controller_interface::return_type SpeedScalingStateController::update()
110110
speed_scaling_state_publisher_->publish(speed_scaling_state_msg_);
111111
last_publish_time_ = node_->now();
112112
}
113-
return controller_interface::return_type::SUCCESS;
113+
return controller_interface::return_type::OK;
114114
}
115115

116116
} // namespace ur_controllers

0 commit comments

Comments
 (0)