Skip to content

Commit a7b2af5

Browse files
authored
[PID Controller] Export state interfaces for easier chaining with other controllers (ros-navigation#1214)
1 parent 3be3fe9 commit a7b2af5

File tree

5 files changed

+86
-0
lines changed

5 files changed

+86
-0
lines changed

pid_controller/include/pid_controller/pid_controller.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -117,6 +117,8 @@ class PidController : public controller_interface::ChainableControllerInterface
117117
// override methods from ChainableControllerInterface
118118
std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
119119

120+
std::vector<hardware_interface::StateInterface> on_export_state_interfaces() override;
121+
120122
bool on_set_chained_mode(bool chained_mode) override;
121123

122124
// internal methods

pid_controller/src/pid_controller.cpp

+64
Original file line numberDiff line numberDiff line change
@@ -187,6 +187,43 @@ controller_interface::CallbackReturn PidController::on_configure(
187187
auto measured_state_callback =
188188
[&](const std::shared_ptr<ControllerMeasuredStateMsg> state_msg) -> void
189189
{
190+
if (state_msg->dof_names.size() != reference_and_state_dof_names_.size())
191+
{
192+
RCLCPP_ERROR(
193+
get_node()->get_logger(),
194+
"Size of input data names (%zu) is not matching the expected size (%zu).",
195+
state_msg->dof_names.size(), reference_and_state_dof_names_.size());
196+
return;
197+
}
198+
if (state_msg->values.size() != reference_and_state_dof_names_.size())
199+
{
200+
RCLCPP_ERROR(
201+
get_node()->get_logger(),
202+
"Size of input data values (%zu) is not matching the expected size (%zu).",
203+
state_msg->values.size(), reference_and_state_dof_names_.size());
204+
return;
205+
}
206+
207+
if (!state_msg->values_dot.empty())
208+
{
209+
if (params_.reference_and_state_interfaces.size() != 2)
210+
{
211+
RCLCPP_ERROR(
212+
get_node()->get_logger(),
213+
"The reference_and_state_interfaces parameter has to have two interfaces [the "
214+
"interface and the derivative of the interface], in order to use the values_dot "
215+
"field.");
216+
return;
217+
}
218+
if (state_msg->values_dot.size() != reference_and_state_dof_names_.size())
219+
{
220+
RCLCPP_ERROR(
221+
get_node()->get_logger(),
222+
"Size of input data values_dot (%zu) is not matching the expected size (%zu).",
223+
state_msg->values_dot.size(), reference_and_state_dof_names_.size());
224+
return;
225+
}
226+
}
190227
// TODO(destogl): Sort the input values based on joint and interface names
191228
measured_state_.writeFromNonRT(state_msg);
192229
};
@@ -363,6 +400,27 @@ std::vector<hardware_interface::CommandInterface> PidController::on_export_refer
363400
return reference_interfaces;
364401
}
365402

403+
std::vector<hardware_interface::StateInterface> PidController::on_export_state_interfaces()
404+
{
405+
std::vector<hardware_interface::StateInterface> state_interfaces;
406+
state_interfaces.reserve(state_interfaces_values_.size());
407+
408+
state_interfaces_values_.resize(
409+
reference_and_state_dof_names_.size() * params_.reference_and_state_interfaces.size(),
410+
std::numeric_limits<double>::quiet_NaN());
411+
size_t index = 0;
412+
for (const auto & interface : params_.reference_and_state_interfaces)
413+
{
414+
for (const auto & dof_name : reference_and_state_dof_names_)
415+
{
416+
state_interfaces.push_back(hardware_interface::StateInterface(
417+
get_node()->get_name(), dof_name + "/" + interface, &state_interfaces_values_[index]));
418+
++index;
419+
}
420+
}
421+
return state_interfaces;
422+
}
423+
366424
bool PidController::on_set_chained_mode(bool chained_mode)
367425
{
368426
// Always accept switch to/from chained mode
@@ -438,6 +496,12 @@ controller_interface::return_type PidController::update_and_write_commands(
438496
}
439497
}
440498

499+
// Fill the information of the exported state interfaces
500+
for (size_t i = 0; i < measured_state_values_.size(); ++i)
501+
{
502+
state_interfaces_values_[i] = measured_state_values_[i];
503+
}
504+
441505
for (size_t i = 0; i < dof_; ++i)
442506
{
443507
double tmp_command = std::numeric_limits<double>::quiet_NaN();

pid_controller/src/pid_controller.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ pid_controller:
3434
read_only: true,
3535
validation: {
3636
not_empty<>: null,
37+
size_gt<>: 0,
3738
size_lt<>: 3,
3839
}
3940
}

pid_controller/test/test_pid_controller.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,7 @@ class TestablePidController : public pid_controller::PidController
7171
const rclcpp_lifecycle::State & previous_state) override
7272
{
7373
auto ref_itfs = on_export_reference_interfaces();
74+
auto state_itfs = on_export_state_interfaces();
7475
return pid_controller::PidController::on_activate(previous_state);
7576
}
7677

pid_controller/test/test_pid_controller_preceding.cpp

+18
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,24 @@ TEST_F(PidControllerTest, check_exported_interfaces)
9090
++ri_index;
9191
}
9292
}
93+
94+
// check exported state itfs
95+
auto exported_state_itfs = controller_->export_state_interfaces();
96+
ASSERT_EQ(exported_state_itfs.size(), dof_state_values_.size());
97+
size_t esi_index = 0;
98+
for (const auto & interface : state_interfaces_)
99+
{
100+
for (const auto & dof_name : reference_and_state_dof_names_)
101+
{
102+
const std::string state_itf_name =
103+
std::string(controller_->get_node()->get_name()) + "/" + dof_name + "/" + interface;
104+
EXPECT_EQ(exported_state_itfs[esi_index].get_name(), state_itf_name);
105+
EXPECT_EQ(
106+
exported_state_itfs[esi_index].get_prefix_name(), controller_->get_node()->get_name());
107+
EXPECT_EQ(exported_state_itfs[esi_index].get_interface_name(), dof_name + "/" + interface);
108+
++esi_index;
109+
}
110+
}
93111
}
94112

95113
int main(int argc, char ** argv)

0 commit comments

Comments
 (0)