Skip to content

Commit 73d5dca

Browse files
mini-1235saikishorbmagyarchristophfroehlich
authored
Statically allocate string concatenations using FMT formatting (#2205)
--------- Signed-off-by: mini-1235 <[email protected]> Co-authored-by: Sai Kishor Kothakota <[email protected]> Co-authored-by: Bence Magyar <[email protected]> Co-authored-by: Christoph Fröhlich <[email protected]>
1 parent b3ef6d8 commit 73d5dca

25 files changed

+430
-256
lines changed

controller_interface/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
99
hardware_interface
1010
rclcpp_lifecycle
1111
realtime_tools
12+
fmt
1213
)
1314

1415
find_package(ament_cmake REQUIRED)

controller_interface/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
<build_depend>realtime_tools</build_depend>
1919
<build_depend>ros2_control_cmake</build_depend>
2020
<build_depend>sensor_msgs</build_depend>
21+
<build_depend>fmt</build_depend>
2122

2223
<build_export_depend>hardware_interface</build_export_depend>
2324
<build_export_depend>realtime_tools</build_export_depend>

controller_interface/src/chainable_controller_interface.cpp

Lines changed: 48 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414

1515
#include "controller_interface/chainable_controller_interface.hpp"
1616

17+
#include <fmt/compile.h>
18+
1719
#include <vector>
1820

1921
#include "controller_interface/helpers.hpp"
@@ -62,12 +64,12 @@ ChainableControllerInterface::export_state_interfaces()
6264
{
6365
if (interface.get_prefix_name().find(get_node()->get_name()) != 0)
6466
{
65-
std::string error_msg =
66-
"The prefix of the interface '" + interface.get_prefix_name() +
67-
"' should begin with the controller's name '" + get_node()->get_name() +
68-
"'. This is mandatory for state interfaces. No state interface will be exported. Please "
69-
"correct and recompile the controller with name '" +
70-
get_node()->get_name() + "' and try again.";
67+
const std::string error_msg = fmt::format(
68+
FMT_COMPILE(
69+
"The prefix of the interface '{}' should begin with the controller's name '{}'. "
70+
"This is mandatory for state interfaces. No state interface will be exported. "
71+
"Please correct and recompile the controller with name '{}' and try again."),
72+
interface.get_prefix_name(), get_node()->get_name(), get_node()->get_name());
7173
throw std::runtime_error(error_msg);
7274
}
7375
auto state_interface = std::make_shared<hardware_interface::StateInterface>(interface);
@@ -78,13 +80,13 @@ ChainableControllerInterface::export_state_interfaces()
7880
// inform cm by throwing exception
7981
if (!succ)
8082
{
81-
std::string error_msg =
82-
"Could not insert StateInterface<" + interface_name +
83-
"> into exported_state_interfaces_ map. Check if you export duplicates. The "
84-
"map returned iterator with interface_name<" +
85-
it->second->get_name() +
86-
">. If its a duplicate adjust exportation of InterfacesDescription so that all the "
87-
"interface names are unique.";
83+
std::string error_msg = fmt::format(
84+
FMT_COMPILE(
85+
"Could not insert StateInterface<{}> into exported_state_interfaces_ map. "
86+
"Check if you export duplicates. The map returned iterator with interface_name<{}>. "
87+
"If its a duplicate adjust exportation of InterfacesDescription so that all the "
88+
"interface names are unique."),
89+
interface_name, it->second->get_name());
8890
exported_state_interfaces_.clear();
8991
exported_state_interface_names_.clear();
9092
state_interfaces_ptrs_vec.clear();
@@ -98,14 +100,13 @@ ChainableControllerInterface::export_state_interfaces()
98100

99101
if (exported_state_interfaces_.size() != state_interfaces.size())
100102
{
101-
std::string error_msg =
102-
"The internal storage for state interface ptrs 'exported_state_interfaces_' variable has "
103-
"size '" +
104-
std::to_string(exported_state_interfaces_.size()) +
105-
"', but it is expected to have the size '" + std::to_string(state_interfaces.size()) +
106-
"' equal to the number of exported reference interfaces. Please correct and recompile the "
107-
"controller with name '" +
108-
get_node()->get_name() + "' and try again.";
103+
std::string error_msg = fmt::format(
104+
FMT_COMPILE(
105+
"The internal storage for state interface ptrs 'exported_state_interfaces_' variable has "
106+
"size '{}', but it is expected to have the size '{}' equal to the number of exported "
107+
"reference interfaces. Please correct and recompile the controller with name '{}' and try "
108+
"again."),
109+
exported_state_interfaces_.size(), state_interfaces.size(), get_node()->get_name());
109110
throw std::runtime_error(error_msg);
110111
}
111112

@@ -128,13 +129,12 @@ ChainableControllerInterface::export_reference_interfaces()
128129
// check if the "reference_interfaces_" variable is resized to number of interfaces
129130
if (reference_interfaces_.size() != reference_interfaces.size())
130131
{
131-
std::string error_msg =
132-
"The internal storage for reference values 'reference_interfaces_' variable has size '" +
133-
std::to_string(reference_interfaces_.size()) + "', but it is expected to have the size '" +
134-
std::to_string(reference_interfaces.size()) +
135-
"' equal to the number of exported reference interfaces. Please correct and recompile the "
136-
"controller with name '" +
137-
get_node()->get_name() + "' and try again.";
132+
std::string error_msg = fmt::format(
133+
FMT_COMPILE(
134+
"The internal storage for reference values 'reference_interfaces_' variable has size '{}', "
135+
"but it is expected to have the size '{}' equal to the number of exported reference "
136+
"interfaces. Please correct and recompile the controller with name '{}' and try again."),
137+
reference_interfaces_.size(), reference_interfaces.size(), get_node()->get_name());
138138
throw std::runtime_error(error_msg);
139139
}
140140
// END
@@ -145,12 +145,12 @@ ChainableControllerInterface::export_reference_interfaces()
145145
{
146146
if (interface.get_prefix_name().find(get_node()->get_name()) != 0)
147147
{
148-
std::string error_msg = "The prefix of the interface '" + interface.get_prefix_name() +
149-
"' should begin with the controller's name '" +
150-
get_node()->get_name() +
151-
"'. This is mandatory for reference interfaces. Please correct and "
152-
"recompile the controller with name '" +
153-
get_node()->get_name() + "' and try again.";
148+
std::string error_msg = fmt::format(
149+
FMT_COMPILE(
150+
"The prefix of the interface '{}' should begin with the controller's name '{}'. "
151+
"This is mandatory for reference interfaces. Please correct and recompile the "
152+
"controller with name '{}' and try again."),
153+
interface.get_prefix_name(), get_node()->get_name(), get_node()->get_name());
154154
throw std::runtime_error(error_msg);
155155
}
156156

@@ -164,13 +164,13 @@ ChainableControllerInterface::export_reference_interfaces()
164164
// inform cm by throwing exception
165165
if (!succ)
166166
{
167-
std::string error_msg =
168-
"Could not insert Reference interface<" + interface_name +
169-
"> into reference_interfaces_ map. Check if you export duplicates. The "
170-
"map returned iterator with interface_name<" +
171-
it->second->get_name() +
172-
">. If its a duplicate adjust exportation of InterfacesDescription so that all the "
173-
"interface names are unique.";
167+
std::string error_msg = fmt::format(
168+
FMT_COMPILE(
169+
"Could not insert Reference interface<{}> into reference_interfaces_ map. "
170+
"Check if you export duplicates. The map returned iterator with interface_name<{}>. "
171+
"If its a duplicate adjust exportation of InterfacesDescription so that all the "
172+
"interface names are unique."),
173+
interface_name, it->second->get_name());
174174
reference_interfaces_.clear();
175175
exported_reference_interface_names_.clear();
176176
reference_interfaces_ptrs_vec.clear();
@@ -183,14 +183,13 @@ ChainableControllerInterface::export_reference_interfaces()
183183

184184
if (exported_reference_interfaces_.size() != ref_interface_size)
185185
{
186-
std::string error_msg =
187-
"The internal storage for exported reference ptrs 'exported_reference_interfaces_' variable "
188-
"has size '" +
189-
std::to_string(exported_reference_interfaces_.size()) +
190-
"', but it is expected to have the size '" + std::to_string(ref_interface_size) +
191-
"' equal to the number of exported reference interfaces. Please correct and recompile the "
192-
"controller with name '" +
193-
get_node()->get_name() + "' and try again.";
186+
std::string error_msg = fmt::format(
187+
FMT_COMPILE(
188+
"The internal storage for exported reference ptrs 'exported_reference_interfaces_' "
189+
"variable has size '{}', but it is expected to have the size '{}' equal to the number of "
190+
"exported reference interfaces. Please correct and recompile the controller with name '{}' "
191+
"and try again."),
192+
exported_reference_interfaces_.size(), ref_interface_size, get_node()->get_name());
194193
throw std::runtime_error(error_msg);
195194
}
196195

controller_manager/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1616
std_msgs
1717
libstatistics_collector
1818
generate_parameter_library
19+
fmt
1920
)
2021

2122
find_package(ament_cmake REQUIRED)

controller_manager/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
<depend>std_msgs</depend>
3333
<depend>libstatistics_collector</depend>
3434
<depend>generate_parameter_library</depend>
35+
<depend>fmt</depend>
3536
<exec_depend>python3-filelock</exec_depend>
3637

3738
<test_depend>ament_cmake_gmock</test_depend>

0 commit comments

Comments
 (0)