Skip to content

Commit 8a1dd35

Browse files
author
Felix Exner
committed
[SJTC] Make scaling interface optional
This way, the controller can be used on systems, where no scaling interface is available (e.g. GZ). The upstream version in ros2_controllers will have the same behavior.
1 parent 912f9ac commit 8a1dd35

File tree

2 files changed

+29
-7
lines changed

2 files changed

+29
-7
lines changed

ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,8 @@
3737
#ifndef UR_CONTROLLERS__SCALED_JOINT_TRAJECTORY_CONTROLLER_HPP_
3838
#define UR_CONTROLLERS__SCALED_JOINT_TRAJECTORY_CONTROLLER_HPP_
3939

40+
#include <optional>
41+
#include <memory>
4042
#include "angles/angles.h"
4143
#include "joint_trajectory_controller/joint_trajectory_controller.hpp"
4244
#include "joint_trajectory_controller/trajectory.hpp"
@@ -73,9 +75,12 @@ class ScaledJointTrajectoryController : public joint_trajectory_controller::Join
7375
};
7476

7577
private:
76-
double scaling_factor_{};
78+
double scaling_factor_{ 1.0 };
7779
realtime_tools::RealtimeBuffer<TimeData> time_data_;
7880

81+
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>> scaling_state_interface_ =
82+
std::nullopt;
83+
7984
std::shared_ptr<scaled_joint_trajectory_controller::ParamListener> scaled_param_listener_;
8085
scaled_joint_trajectory_controller::Params scaled_params_;
8186
};

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 23 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,14 @@ controller_interface::InterfaceConfiguration ScaledJointTrajectoryController::st
5858
{
5959
controller_interface::InterfaceConfiguration conf;
6060
conf = JointTrajectoryController::state_interface_configuration();
61-
conf.names.push_back(scaled_params_.speed_scaling_interface_name);
61+
62+
if (!scaled_params_.speed_scaling_interface_name.empty()) {
63+
RCLCPP_INFO(get_node()->get_logger(), "Using scaling state from the hardware from interface %s.",
64+
scaled_params_.speed_scaling_interface_name.c_str());
65+
conf.names.push_back(scaled_params_.speed_scaling_interface_name);
66+
} else {
67+
RCLCPP_INFO(get_node()->get_logger(), "No scaling interface set. This controller will not use speed scaling.");
68+
}
6269

6370
return conf;
6471
}
@@ -70,17 +77,27 @@ controller_interface::CallbackReturn ScaledJointTrajectoryController::on_activat
7077
time_data.period = rclcpp::Duration::from_nanoseconds(0);
7178
time_data.uptime = get_node()->now();
7279
time_data_.initRT(time_data);
80+
81+
// Set scaling interfaces
82+
if (!scaled_params_.speed_scaling_interface_name.empty()) {
83+
auto it = std::find_if(state_interfaces_.begin(), state_interfaces_.end(), [&](auto& interface) {
84+
return (interface.get_name() == scaled_params_.speed_scaling_interface_name);
85+
});
86+
if (it != state_interfaces_.end()) {
87+
scaling_state_interface_ = *it;
88+
} else {
89+
RCLCPP_ERROR(get_node()->get_logger(), "Did not find speed scaling interface in state interfaces.");
90+
}
91+
}
92+
7393
return JointTrajectoryController::on_activate(state);
7494
}
7595

7696
controller_interface::return_type ScaledJointTrajectoryController::update(const rclcpp::Time& time,
7797
const rclcpp::Duration& period)
7898
{
79-
if (state_interfaces_.back().get_name() == scaled_params_.speed_scaling_interface_name) {
80-
scaling_factor_ = state_interfaces_.back().get_value();
81-
} else {
82-
RCLCPP_ERROR(get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.",
83-
scaled_params_.speed_scaling_interface_name.c_str());
99+
if (scaling_state_interface_.has_value()) {
100+
scaling_factor_ = scaling_state_interface_->get().get_value();
84101
}
85102

86103
if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {

0 commit comments

Comments
 (0)