|
| 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