@@ -101,12 +101,17 @@ JointTrajectoryController::command_interface_configuration() const
101
101
conf.names .push_back (joint_name + " /" + interface_type);
102
102
}
103
103
}
104
+ if (!params_.speed_scaling_command_interface_name .empty ())
105
+ {
106
+ conf.names .push_back (params_.speed_scaling_command_interface_name );
107
+ }
104
108
return conf;
105
109
}
106
110
107
111
controller_interface::InterfaceConfiguration
108
112
JointTrajectoryController::state_interface_configuration () const
109
113
{
114
+ const auto logger = get_node ()->get_logger ();
110
115
controller_interface::InterfaceConfiguration conf;
111
116
conf.type = controller_interface::interface_configuration_type::INDIVIDUAL;
112
117
conf.names .reserve (dof_ * params_.state_interfaces .size ());
@@ -117,33 +122,36 @@ JointTrajectoryController::state_interface_configuration() const
117
122
conf.names .push_back (joint_name + " /" + interface_type);
118
123
}
119
124
}
120
- if (params_.exchange_scaling_factor_with_hardware )
125
+ if (! params_.speed_scaling_state_interface_name . empty () )
121
126
{
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 );
123
131
}
124
132
return conf;
125
133
}
126
134
127
135
controller_interface::return_type JointTrajectoryController::update (
128
136
const rclcpp::Time & time, const rclcpp::Duration & period)
129
137
{
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
131
143
{
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 )
133
145
{
134
146
scaling_factor_ = state_interfaces_.back ().get_value ();
135
147
}
136
148
else
137
149
{
138
150
RCLCPP_ERROR (
139
151
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 ());
141
153
}
142
154
}
143
- else
144
- {
145
- scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT ());
146
- }
147
155
148
156
if (get_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
149
157
{
@@ -478,7 +486,8 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
478
486
auto interface_has_values = [](const auto & joint_interface)
479
487
{
480
488
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)
482
491
{ return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
483
492
};
484
493
@@ -548,7 +557,8 @@ bool JointTrajectoryController::read_commands_from_command_interfaces(
548
557
auto interface_has_values = [](const auto & joint_interface)
549
558
{
550
559
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)
552
562
{ return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
553
563
};
554
564
@@ -919,6 +929,8 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
919
929
std::placeholders::_1, std::placeholders::_2));
920
930
921
931
// set scaling factor to low value default
932
+ RCLCPP_INFO (
933
+ logger, " Setting initial scaling factor to %2f" , params_.scaling_factor_initial_default );
922
934
scaling_factor_rt_buff_.writeFromNonRT (params_.scaling_factor_initial_default );
923
935
924
936
return CallbackReturn::SUCCESS;
@@ -1630,7 +1642,26 @@ bool JointTrajectoryController::set_scaling_factor(
1630
1642
}
1631
1643
1632
1644
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
+ }
1634
1665
resp->success = true ;
1635
1666
return true ;
1636
1667
}
0 commit comments