Skip to content

Commit bbfecd0

Browse files
Merge pull request #66 from MaximilienNaveau/topic/mnaveau/rebase-humble-onto-humble-devel
Merge humble onto humble-devel
2 parents 2bd4c13 + d8c3c67 commit bbfecd0

17 files changed

+2174
-10
lines changed

.pre-commit-config.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ ci:
22
autoupdate_branch: 'devel'
33
repos:
44
- repo: https://github.com/pre-commit/mirrors-clang-format
5-
rev: v16.0.0
5+
rev: v19.1.7
66
hooks:
77
- id: clang-format
88
args: [--style=Google]
@@ -25,7 +25,7 @@ repos:
2525
- id: mixed-line-ending
2626
- id: trailing-whitespace
2727
- repo: https://github.com/psf/black
28-
rev: 23.1.0
28+
rev: 24.10.0
2929
hooks:
3030
- id: black
3131
- repo: https://github.com/cheshirekow/cmake-format-precommit

CMakeLists.txt

Lines changed: 15 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ sec_generate_parameter_library(
3131
add_dependencies(${PROJECT_NAME}_parameters ${PROJECT_NAME}_parameters_doc)
3232
# Joint estimator params
3333
sec_generate_parameter_library_markdown(joint_state_estimator_parameters_doc
34-
src/linear_feedback_controller.yaml)
34+
src/joint_state_estimator.yaml)
3535
sec_generate_parameter_library(
3636
joint_state_estimator_generated_parameters # Lib name
3737
joint_state_estimator_parameters # CMake target name for the parameter
@@ -97,6 +97,16 @@ if(BUILD_TESTING)
9797
test_robot_model_builder
9898
PROPERTIES ENVIRONMENT_MODIFICATION
9999
LD_LIBRARY_PATH=path_list_prepend:${CMAKE_CURRENT_BINARY_DIR})
100+
101+
ament_auto_add_gtest(test_pd_controller tests/test_pd_controller.cpp)
102+
target_link_libraries(test_pd_controller ${PROJECT_NAME})
103+
104+
ament_auto_add_gtest(test_lf_controller tests/test_lf_controller.cpp)
105+
target_link_libraries(test_lf_controller ${PROJECT_NAME})
106+
107+
ament_auto_add_gtest(test_linear_feedback_controller
108+
tests/test_linear_feedback_controller.cpp)
109+
target_link_libraries(test_linear_feedback_controller ${PROJECT_NAME})
100110
endif()
101111

102112
#
@@ -108,8 +118,10 @@ pluginlib_export_plugin_description_file(controller_interface
108118
#
109119
# Installation
110120
#
111-
install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/doc
112-
DESTINATION share/${PROJECT_NAME})
121+
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/linear_feedback_controller.md
122+
${CMAKE_CURRENT_BINARY_DIR}/joint_state_estimator.md
123+
DESTINATION share/${PROJECT_NAME}/doc)
124+
113125
install(
114126
PROGRAMS tests/pd_plus_controller.py
115127
DESTINATION lib/${PROJECT_NAME}

cmake/sec_generate_parameter_library.cmake

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,7 @@ function(sec_generate_parameter_library_markdown TARGET_NAME YAML_FILE)
111111

112112
# Set the output parameter header file name
113113
get_filename_component(MARKDOWN_FILE ${YAML_FILE} NAME_WE)
114-
set(MARKDOWN_FILE ${CMAKE_CURRENT_BINARY_DIR}/doc/${MARKDOWN_FILE}.md)
114+
set(MARKDOWN_FILE ${CMAKE_CURRENT_BINARY_DIR}/${MARKDOWN_FILE}.md)
115115

116116
# Generate the header for the library
117117
add_custom_target(

include/linear_feedback_controller/averaging_filter.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ class AveragingFilter {
1616
/**
1717
* @brief Destroy the Averaging Filter object
1818
*/
19-
~AveragingFilter(){};
19+
~AveragingFilter() {};
2020

2121
/**
2222
* @brief Add another data in the buffer in a FIFO manner;

include/linear_feedback_controller/time.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,6 @@
1+
#ifndef LINEAR_FEEDBACK_CONTROLLER__TIME_HPP_
2+
#define LINEAR_FEEDBACK_CONTROLLER__TIME_HPP_
3+
14
#include <chrono>
25

36
namespace linear_feedback_controller {
@@ -6,3 +9,5 @@ using TimePoint = std::chrono::time_point<std::chrono::high_resolution_clock,
69

710
using Duration = std::chrono::duration<double>;
811
} // namespace linear_feedback_controller
12+
13+
#endif

src/linear_feedback_controller.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -81,9 +81,13 @@ const Eigen::VectorXd& LinearFeedbackController::compute_control(
8181
if (remove_gravity_compensation_effort) {
8282
robot_model_builder_->construct_robot_state(sensor, robot_configuration_,
8383
robot_velocity_);
84-
control_ -= pinocchio::rnea(
85-
robot_model_builder_->get_model(), robot_model_builder_->get_data(),
86-
robot_configuration_, robot_velocity_null_, robot_velocity_null_);
84+
85+
// NOTE: .tail() is used to remove the freeflyer components
86+
control_ -=
87+
pinocchio::rnea(robot_model_builder_->get_model(),
88+
robot_model_builder_->get_data(), robot_configuration_,
89+
robot_velocity_null_, robot_velocity_null_)
90+
.tail(control_.size());
8791
}
8892

8993
return control_;

tests/test_lf_controller.cpp

Lines changed: 244 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,244 @@
1+
#include <sstream>
2+
#include <string_view>
3+
#include <tuple>
4+
5+
#include "utils/mutation.hpp"
6+
using tests::utils::TemporaryMutate;
7+
8+
#include "utils/lf_controller.hpp"
9+
using tests::utils::ExpectedLFControlFrom;
10+
using tests::utils::MakeValidRandomControlFor;
11+
using tests::utils::MakeValidRandomSensorFor;
12+
13+
#include "utils/robot_model.hpp"
14+
using tests::utils::JointType;
15+
using tests::utils::MakeAllModelDescriptionsFor;
16+
using tests::utils::ModelDescription;
17+
18+
#include "utils/eigen_conversions.hpp"
19+
using tests::utils::PushNewJointStateTo;
20+
21+
#include "linear_feedback_controller/lf_controller.hpp"
22+
using linear_feedback_controller::LFController;
23+
24+
#include "gtest/gtest.h"
25+
26+
using namespace std::literals::string_view_literals;
27+
28+
namespace {
29+
30+
struct LFControllerTest : public ::testing::TestWithParam<ModelDescription> {};
31+
32+
TEST(LFControllerTest, Ctor) {
33+
EXPECT_NO_THROW({ auto ctrl = LFController(); });
34+
}
35+
36+
TEST(LFControllerTest, DISABLED_InitializeNullptr) {
37+
auto ctrl = LFController();
38+
EXPECT_ANY_THROW({ ctrl.initialize(nullptr); });
39+
}
40+
41+
TEST(LFControllerTest, DISABLED_InitializeEmptyModel) {
42+
auto ctrl = LFController();
43+
EXPECT_ANY_THROW({
44+
ctrl.initialize(
45+
std::make_shared<linear_feedback_controller::RobotModelBuilder>());
46+
});
47+
}
48+
49+
TEST_P(LFControllerTest, Initialize) {
50+
const auto model_ptr = std::shared_ptr{MakeRobotModelBuilderFrom(GetParam())};
51+
ASSERT_NE(model_ptr, nullptr);
52+
53+
auto ctrl = LFController();
54+
EXPECT_NO_THROW({ ctrl.initialize(model_ptr); });
55+
}
56+
57+
TEST(LFControllerTest, DISABLED_ComputeControlNotInitialized) {
58+
auto ctrl = LFController();
59+
EXPECT_ANY_THROW({ auto _ = ctrl.compute_control({}, {}); });
60+
}
61+
62+
TEST_P(LFControllerTest, DISABLED_ComputeControlNoInput) {
63+
const auto model_ptr = std::shared_ptr{MakeRobotModelBuilderFrom(GetParam())};
64+
ASSERT_NE(model_ptr, nullptr);
65+
66+
auto ctrl = LFController();
67+
ctrl.initialize(model_ptr);
68+
69+
EXPECT_ANY_THROW({ auto _ = ctrl.compute_control({}, {}); });
70+
}
71+
72+
TEST_P(LFControllerTest, DISABLED_ComputeControlUnknownJoints) {
73+
const auto model_ptr = std::shared_ptr{MakeRobotModelBuilderFrom(GetParam())};
74+
ASSERT_NE(model_ptr, nullptr);
75+
76+
auto ctrl = LFController();
77+
ctrl.initialize(model_ptr);
78+
79+
const auto sensor = MakeValidRandomSensorFor(*model_ptr);
80+
const auto control = MakeValidRandomControlFor(*model_ptr);
81+
82+
EXPECT_ANY_THROW({
83+
auto wrong_sensor = sensor;
84+
wrong_sensor.joint_state.name[0] = "this joint doesn't exist";
85+
auto _ = ctrl.compute_control(wrong_sensor, control);
86+
});
87+
}
88+
89+
TEST_P(LFControllerTest, DISABLED_ComputeControlSizeMismatch) {
90+
const auto model_ptr = std::shared_ptr{MakeRobotModelBuilderFrom(GetParam())};
91+
ASSERT_NE(model_ptr, nullptr);
92+
93+
auto ctrl = LFController();
94+
ctrl.initialize(model_ptr);
95+
96+
const auto sensor = MakeValidRandomSensorFor(*model_ptr);
97+
const auto control = MakeValidRandomControlFor(*model_ptr);
98+
99+
EXPECT_ANY_THROW({
100+
auto wrong_sensor = sensor;
101+
102+
// One more unknown joint inside sensor
103+
PushNewJointStateTo(
104+
wrong_sensor.joint_state,
105+
{.name = "foo", .position = 0.0, .velocity = 0.0, .effort = 0.0});
106+
107+
auto _ = ctrl.compute_control(wrong_sensor, control);
108+
});
109+
110+
EXPECT_ANY_THROW({
111+
auto wrong_control = control;
112+
113+
// One more unknown joint inside control.initial_state
114+
PushNewJointStateTo(
115+
wrong_control.initial_state.joint_state,
116+
{.name = "foo", .position = 0.0, .velocity = 0.0, .effort = 0.0});
117+
118+
auto _ = ctrl.compute_control(sensor, wrong_control);
119+
});
120+
121+
EXPECT_ANY_THROW({
122+
auto wrong_control = control;
123+
124+
// One more feed forward term
125+
tests::utils::Grow(wrong_control.feedforward, 1);
126+
wrong_control.feedforward.tail<1>()[0] = 0.0;
127+
128+
auto _ = ctrl.compute_control(sensor, wrong_control);
129+
});
130+
131+
EXPECT_ANY_THROW({
132+
auto wrong_control = control;
133+
134+
// One more row/col to feedback gain
135+
tests::utils::Grow(wrong_control.feedback_gain, 1);
136+
137+
wrong_control.feedback_gain.bottomRows<1>() =
138+
::Eigen::VectorXd::Random(wrong_control.feedback_gain.cols());
139+
140+
wrong_control.feedback_gain.rightCols<1>() =
141+
::Eigen::VectorXd::Random(wrong_control.feedback_gain.rows());
142+
143+
auto _ = ctrl.compute_control(sensor, wrong_control);
144+
});
145+
}
146+
147+
/// Create a std::tuple<T&, string_view> with the ref expression as string
148+
#define MakeRefOf(val) std::make_tuple(std::ref((val)), std::string_view{#val})
149+
150+
TEST_P(LFControllerTest, DISABLED_ComputeControlSpecialDouble) {
151+
const auto model_ptr = std::shared_ptr{MakeRobotModelBuilderFrom(GetParam())};
152+
ASSERT_NE(model_ptr, nullptr);
153+
154+
auto ctrl = LFController();
155+
ctrl.initialize(model_ptr);
156+
157+
auto sensor = MakeValidRandomSensorFor(*model_ptr);
158+
auto control = MakeValidRandomControlFor(*model_ptr);
159+
160+
// Test for special double values acceptance or not ?
161+
for (const auto& [ref, str] : {
162+
MakeRefOf(sensor.base_pose(0)),
163+
MakeRefOf(sensor.base_pose(3)),
164+
MakeRefOf(sensor.base_twist(4)),
165+
MakeRefOf(sensor.joint_state.position(0)),
166+
MakeRefOf(sensor.joint_state.velocity(0)),
167+
MakeRefOf(control.feedforward(0)),
168+
MakeRefOf(control.feedback_gain(0, 0)),
169+
}) {
170+
for (auto tmp_value : {
171+
std::numeric_limits<double>::infinity(),
172+
std::numeric_limits<double>::quiet_NaN(),
173+
std::numeric_limits<double>::signaling_NaN(),
174+
}) {
175+
const auto mutation = TemporaryMutate(ref, tmp_value);
176+
EXPECT_ANY_THROW({ auto _ = ctrl.compute_control(sensor, control); })
177+
<< str << " = " << tmp_value << " (was " << mutation.OldValue()
178+
<< ")";
179+
}
180+
}
181+
}
182+
183+
TEST_P(LFControllerTest, ComputeControl) {
184+
const auto model_ptr = std::shared_ptr{MakeRobotModelBuilderFrom(GetParam())};
185+
ASSERT_NE(model_ptr, nullptr);
186+
187+
auto ctrl = LFController();
188+
ctrl.initialize(model_ptr);
189+
190+
const auto sensor = MakeValidRandomSensorFor(*model_ptr);
191+
const auto control = MakeValidRandomControlFor(*model_ptr);
192+
EXPECT_EQ(ExpectedLFControlFrom(*model_ptr, sensor, control),
193+
ctrl.compute_control(sensor, control));
194+
}
195+
196+
constexpr auto dummy_urdf =
197+
"<?xml version=\"1.0\" encoding=\"utf-8\"?>"
198+
"<robot name=\"dummy\">"
199+
" <link name=\"l0\"/>"
200+
" "
201+
" <joint name=\"l01\" type=\"revolute\">"
202+
" <parent link=\"l0\"/>"
203+
" <child link=\"l1\"/>"
204+
" <origin xyz=\"0 0 1\" rpy=\"0 0 1\"/>"
205+
" <axis xyz=\"0 0 1\"/>"
206+
" <limit lower=\"0\" upper=\"3.14\" velocity=\"100\" effort=\"100\"/>"
207+
" </joint>"
208+
" "
209+
" <link name=\"l1\"/>"
210+
" "
211+
" <joint name=\"l12\" type=\"revolute\">"
212+
" <parent link=\"l1\"/>"
213+
" <child link=\"l2\"/>"
214+
" <origin xyz=\"0 1 0\" rpy=\"1 0 0\"/>"
215+
" <axis xyz=\"0 1 0\"/>"
216+
" <limit lower=\"-3.14\" upper=\"3.14\" velocity=\"100\" effort=\"10\"/>"
217+
" </joint>"
218+
" "
219+
" <link name=\"l2\"/>"
220+
"</robot>"sv;
221+
222+
INSTANTIATE_TEST_SUITE_P(
223+
DummyUrdf, LFControllerTest,
224+
::testing::ValuesIn(MakeAllModelDescriptionsFor(
225+
dummy_urdf,
226+
{
227+
{
228+
{.name = "l01"},
229+
},
230+
{
231+
{.name = "l02", .type = JointType::Controlled},
232+
},
233+
{
234+
{.name = "l01"},
235+
{.name = "l12"},
236+
},
237+
})),
238+
[](const auto& info) {
239+
std::stringstream stream;
240+
PrintTo(info.param, &stream, {.as_param_name = true});
241+
return stream.str();
242+
});
243+
244+
} // namespace

0 commit comments

Comments
 (0)