Skip to content

Commit e685997

Browse files
authored
Fixed pre-commit failures.
1 parent dcc31af commit e685997

File tree

1 file changed

+16
-12
lines changed

1 file changed

+16
-12
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp

Lines changed: 16 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -28,10 +28,10 @@ namespace
2828
{
2929

3030
/// Converts a string to lowercase for case-agnostic checking.
31-
inline std::string convert_to_lowercase(const std::string& str)
31+
inline std::string convert_to_lowercase(const std::string & str)
3232
{
3333
std::string s = str;
34-
for (char& c : s)
34+
for (char & c : s)
3535
{
3636
// C++ std requires the argument passed to std::tolower must be representable as
3737
// unsigned char or equal to EOF.
@@ -40,7 +40,7 @@ inline std::string convert_to_lowercase(const std::string& str)
4040
return s;
4141
}
4242

43-
} // namespace
43+
} // namespace
4444

4545

4646
/// \brief Setup interpolation_methods' rclcpp::Logger instance.
@@ -100,12 +100,13 @@ const std::unordered_map<std::string, InterpolationMethod> InterpolationMethodMa
100100
*
101101
* \returns The corresponding InterpolationMethod.
102102
*
103-
* \note If interpolation_method does not have any corresponding InterpolationMethod (i.e., "Unknown"),
104-
* It defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`.
103+
* \note If interpolation_method does not have any corresponding InterpolationMethod
104+
* (i.e., "Unknown"), it defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`.
105105
*/
106-
[[nodiscard]] inline InterpolationMethod from_string(const std::string& interpolation_method)
106+
[[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method)
107107
{
108-
// Convert to lowercase, so we have an case-agnostic checking. (i.e., None and none, etc are treated same.)
108+
// Convert to lowercase, so we have an case-agnostic checking,
109+
// (i.e., None and none, etc are treated same.)
109110
std::string method = convert_to_lowercase(interpolation_method);
110111

111112
// Iterator to InterpolationMethodMap
@@ -140,14 +141,17 @@ const std::unordered_map<std::string, InterpolationMethod> InterpolationMethodMa
140141
*
141142
* \note Defaults to return "UNKNOWN".
142143
*/
143-
[[nodiscard]] inline std::string to_string(const InterpolationMethod& interpolation_method)
144+
[[nodiscard]] inline std::string to_string(const InterpolationMethod & interpolation_method)
144145
{
145-
switch(interpolation_method)
146+
switch (interpolation_method)
146147
{
147-
case InterpolationMethod::NONE: return "none";
148-
case InterpolationMethod::VARIABLE_DEGREE_SPLINE: return "splines";
148+
case InterpolationMethod::NONE:
149+
return "none";
150+
case InterpolationMethod::VARIABLE_DEGREE_SPLINE:
151+
return "splines";
149152
// Default
150-
default: return "UNKNOWN";
153+
default:
154+
return "UNKNOWN";
151155
}
152156
}
153157

0 commit comments

Comments
 (0)