Skip to content

Commit 9851eac

Browse files
author
Felix Exner
committed
Improve scaling exchange with hardware
1 parent 5fc7b41 commit 9851eac

File tree

2 files changed

+53
-21
lines changed

2 files changed

+53
-21
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 43 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -101,12 +101,17 @@ JointTrajectoryController::command_interface_configuration() const
101101
conf.names.push_back(joint_name + "/" + interface_type);
102102
}
103103
}
104+
if (!params_.speed_scaling_command_interface_name.empty())
105+
{
106+
conf.names.push_back(params_.speed_scaling_command_interface_name);
107+
}
104108
return conf;
105109
}
106110

107111
controller_interface::InterfaceConfiguration
108112
JointTrajectoryController::state_interface_configuration() const
109113
{
114+
const auto logger = get_node()->get_logger();
110115
controller_interface::InterfaceConfiguration conf;
111116
conf.type = controller_interface::interface_configuration_type::INDIVIDUAL;
112117
conf.names.reserve(dof_ * params_.state_interfaces.size());
@@ -117,33 +122,36 @@ JointTrajectoryController::state_interface_configuration() const
117122
conf.names.push_back(joint_name + "/" + interface_type);
118123
}
119124
}
120-
if (params_.exchange_scaling_factor_with_hardware)
125+
if (!params_.speed_scaling_state_interface_name.empty())
121126
{
122-
conf.names.push_back(params_.speed_scaling_interface_name);
127+
RCLCPP_INFO(
128+
logger, "Using scaling state from the hardware from interface %s.",
129+
params_.speed_scaling_state_interface_name.c_str());
130+
conf.names.push_back(params_.speed_scaling_state_interface_name);
123131
}
124132
return conf;
125133
}
126134

127135
controller_interface::return_type JointTrajectoryController::update(
128136
const rclcpp::Time & time, const rclcpp::Duration & period)
129137
{
130-
if (params_.exchange_scaling_factor_with_hardware)
138+
if (params_.speed_scaling_state_interface_name.empty())
139+
{
140+
scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT());
141+
}
142+
else
131143
{
132-
if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name)
144+
if (state_interfaces_.back().get_name() == params_.speed_scaling_state_interface_name)
133145
{
134146
scaling_factor_ = state_interfaces_.back().get_value();
135147
}
136148
else
137149
{
138150
RCLCPP_ERROR(
139151
get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.",
140-
params_.speed_scaling_interface_name.c_str());
152+
params_.speed_scaling_state_interface_name.c_str());
141153
}
142154
}
143-
else
144-
{
145-
scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT());
146-
}
147155

148156
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
149157
{
@@ -478,7 +486,8 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
478486
auto interface_has_values = [](const auto & joint_interface)
479487
{
480488
return std::find_if(
481-
joint_interface.begin(), joint_interface.end(), [](const auto & interface)
489+
joint_interface.begin(), joint_interface.end(),
490+
[](const auto & interface)
482491
{ return std::isnan(interface.get().get_value()); }) == joint_interface.end();
483492
};
484493

@@ -548,7 +557,8 @@ bool JointTrajectoryController::read_commands_from_command_interfaces(
548557
auto interface_has_values = [](const auto & joint_interface)
549558
{
550559
return std::find_if(
551-
joint_interface.begin(), joint_interface.end(), [](const auto & interface)
560+
joint_interface.begin(), joint_interface.end(),
561+
[](const auto & interface)
552562
{ return std::isnan(interface.get().get_value()); }) == joint_interface.end();
553563
};
554564

@@ -919,6 +929,8 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
919929
std::placeholders::_1, std::placeholders::_2));
920930

921931
// set scaling factor to low value default
932+
RCLCPP_INFO(
933+
logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default);
922934
scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default);
923935

924936
return CallbackReturn::SUCCESS;
@@ -1630,7 +1642,26 @@ bool JointTrajectoryController::set_scaling_factor(
16301642
}
16311643

16321644
RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", req->scaling_factor);
1633-
scaling_factor_rt_buff_.writeFromNonRT(req->scaling_factor);
1645+
if (params_.speed_scaling_command_interface_name.empty())
1646+
{
1647+
if (!params_.speed_scaling_state_interface_name.empty())
1648+
{
1649+
RCLCPP_WARN(
1650+
get_node()->get_logger(),
1651+
"Setting the scaling factor while only one-way communication with the hardware is setup. "
1652+
"This will likely get overwritten by the hardware again. If available, please also setup "
1653+
"the speed_scaling_command_interface_name");
1654+
}
1655+
scaling_factor_rt_buff_.writeFromNonRT(req->scaling_factor);
1656+
}
1657+
else
1658+
{
1659+
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
1660+
{
1661+
// TODO(Felix): Use proper adressing here.
1662+
command_interfaces_.back().set_value(static_cast<double>(req->scaling_factor));
1663+
}
1664+
}
16341665
resp->success = true;
16351666
return true;
16361667
}

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -39,21 +39,22 @@ joint_trajectory_controller:
3939
"joint_trajectory_controller::state_interface_type_combinations": null,
4040
}
4141
}
42-
exchange_scaling_factor_with_hardware: {
43-
type: bool,
44-
default_value: false,
45-
description: "Flag that mark is hardware supports setting and reading of scaling factor.\n
46-
If set to 'true' corresponding command and state interfaces are created."
47-
}
4842
scaling_factor_initial_default: {
4943
type: double,
5044
default_value: 1.0,
5145
description: "The initial value of the scaling factor if not exchange with hardware takes place."
5246
}
53-
speed_scaling_interface_name: {
47+
speed_scaling_state_interface_name: {
5448
type: string,
55-
default_value: "speed_scaling/speed_scaling_factor",
56-
description: "Fully qualified name of the speed scaling interface name"
49+
default_value: "",
50+
read_only: true,
51+
description: "Fully qualified name of the speed scaling state interface name"
52+
}
53+
speed_scaling_command_interface_name: {
54+
type: string,
55+
default_value: "",
56+
read_only: true,
57+
description: "Command interface name used for setting the speed scaling factor on the hardware."
5758
}
5859
allow_partial_joints_goal: {
5960
type: bool,

0 commit comments

Comments
 (0)