Skip to content

Commit 00727bf

Browse files
committed
Only load speed scaling interface
1 parent 4e90259 commit 00727bf

File tree

2 files changed

+5
-2
lines changed

2 files changed

+5
-2
lines changed

ur_controllers/src/speed_scaling_state_controller.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,10 @@ controller_interface::InterfaceConfiguration SpeedScalingStateController::comman
6565

6666
controller_interface::InterfaceConfiguration SpeedScalingStateController::state_interface_configuration() const
6767
{
68-
return controller_interface::InterfaceConfiguration{ controller_interface::interface_configuration_type::ALL };
68+
controller_interface::InterfaceConfiguration config;
69+
config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
70+
config.names.push_back("speed_scaling/speed_scaling_factor");
71+
return config;
6972
}
7073

7174
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -129,7 +129,7 @@ std::vector<hardware_interface::StateInterface> URPositionHardwareInterface::exp
129129
}
130130

131131
state_interfaces.emplace_back(
132-
hardware_interface::StateInterface("speed", "speed_scaling_factor", &speed_scaling_combined_));
132+
hardware_interface::StateInterface("speed_scaling", "speed_scaling_factor", &speed_scaling_combined_));
133133

134134
for (auto& sensor : info_.sensors)
135135
{

0 commit comments

Comments
 (0)