|
| 1 | +// Copyright (c) 2023, PAL Robotics |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | +/// \author Sai Kishor Kothakota |
| 15 | + |
| 16 | +#include <functional> |
| 17 | +#include <memory> |
| 18 | +#include <string> |
| 19 | +#include <utility> |
| 20 | +#include <vector> |
| 21 | + |
| 22 | +#include "gmock/gmock.h" |
| 23 | + |
| 24 | +#include "hardware_interface/loaned_command_interface.hpp" |
| 25 | +#include "lifecycle_msgs/msg/state.hpp" |
| 26 | +#include "rclcpp/node.hpp" |
| 27 | +#include "rclcpp/qos.hpp" |
| 28 | +#include "rclcpp/subscription.hpp" |
| 29 | +#include "rclcpp/utilities.hpp" |
| 30 | +#include "rclcpp/wait_set.hpp" |
| 31 | +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" |
| 32 | +#include "test_passthrough_controller.hpp" |
| 33 | + |
| 34 | +using hardware_interface::LoanedCommandInterface; |
| 35 | + |
| 36 | +namespace |
| 37 | +{ |
| 38 | +rclcpp::WaitResultKind wait_for(rclcpp::SubscriptionBase::SharedPtr subscription) |
| 39 | +{ |
| 40 | + rclcpp::WaitSet wait_set; |
| 41 | + wait_set.add_subscription(subscription); |
| 42 | + const auto timeout = std::chrono::seconds(10); |
| 43 | + return wait_set.wait(timeout).kind(); |
| 44 | +} |
| 45 | +} // namespace |
| 46 | + |
| 47 | +void PassthroughControllerTest::SetUpTestCase() { rclcpp::init(0, nullptr); } |
| 48 | + |
| 49 | +void PassthroughControllerTest::TearDownTestCase() { rclcpp::shutdown(); } |
| 50 | + |
| 51 | +void PassthroughControllerTest::SetUp() |
| 52 | +{ |
| 53 | + // initialize controller |
| 54 | + controller_ = std::make_unique<FriendPassthroughController>(); |
| 55 | +} |
| 56 | + |
| 57 | +void PassthroughControllerTest::TearDown() { controller_.reset(nullptr); } |
| 58 | + |
| 59 | +void PassthroughControllerTest::SetUpController() |
| 60 | +{ |
| 61 | + const auto result = controller_->init("passthrough_controller"); |
| 62 | + ASSERT_EQ(result, controller_interface::return_type::OK); |
| 63 | + |
| 64 | + std::vector<LoanedCommandInterface> command_ifs; |
| 65 | + command_ifs.emplace_back(joint_1_pos_cmd_); |
| 66 | + command_ifs.emplace_back(joint_2_pos_cmd_); |
| 67 | + command_ifs.emplace_back(joint_3_pos_cmd_); |
| 68 | + controller_->assign_interfaces(std::move(command_ifs), {}); |
| 69 | +} |
| 70 | + |
| 71 | +TEST_F(PassthroughControllerTest, InterfaceParameterNotSet) |
| 72 | +{ |
| 73 | + SetUpController(); |
| 74 | + // configure failed, 'interfaces' parameter not set |
| 75 | + ASSERT_EQ( |
| 76 | + controller_->on_configure(rclcpp_lifecycle::State()), |
| 77 | + controller_interface::CallbackReturn::ERROR); |
| 78 | +} |
| 79 | + |
| 80 | +TEST_F(PassthroughControllerTest, InterfaceParameterEmpty) |
| 81 | +{ |
| 82 | + SetUpController(); |
| 83 | + controller_->get_node()->set_parameter({"interfaces", std::vector<std::string>()}); |
| 84 | + |
| 85 | + // configure failed, 'interfaces' is empty |
| 86 | + ASSERT_EQ( |
| 87 | + controller_->on_configure(rclcpp_lifecycle::State()), |
| 88 | + controller_interface::CallbackReturn::ERROR); |
| 89 | +} |
| 90 | + |
| 91 | +TEST_F(PassthroughControllerTest, ConfigureParamsSuccess) |
| 92 | +{ |
| 93 | + SetUpController(); |
| 94 | + |
| 95 | + controller_->get_node()->set_parameter( |
| 96 | + {"interfaces", std::vector<std::string>{"joint1/interface", "joint2/interface"}}); |
| 97 | + |
| 98 | + // configure successful |
| 99 | + ASSERT_EQ( |
| 100 | + controller_->on_configure(rclcpp_lifecycle::State()), |
| 101 | + controller_interface::CallbackReturn::SUCCESS); |
| 102 | +} |
| 103 | + |
| 104 | +TEST_F(PassthroughControllerTest, ActivateWithWrongInterfaceNameFails) |
| 105 | +{ |
| 106 | + SetUpController(); |
| 107 | + |
| 108 | + controller_->get_node()->set_parameter( |
| 109 | + {"interfaces", std::vector<std::string>{"joint1/input", "joint2/input"}}); |
| 110 | + |
| 111 | + // activate failed, 'input' is not a registered interface for `joint1` |
| 112 | + ASSERT_EQ( |
| 113 | + controller_->on_configure(rclcpp_lifecycle::State()), |
| 114 | + controller_interface::CallbackReturn::SUCCESS); |
| 115 | + ASSERT_EQ( |
| 116 | + controller_->on_activate(rclcpp_lifecycle::State()), |
| 117 | + controller_interface::CallbackReturn::ERROR); |
| 118 | +} |
| 119 | + |
| 120 | +TEST_F(PassthroughControllerTest, ActivateSuccess) |
| 121 | +{ |
| 122 | + SetUpController(); |
| 123 | + |
| 124 | + controller_->get_node()->set_parameter( |
| 125 | + {"interfaces", std::vector<std::string>{"joint1/interface", "joint2/interface"}}); |
| 126 | + |
| 127 | + // activate successful |
| 128 | + ASSERT_EQ( |
| 129 | + controller_->on_configure(rclcpp_lifecycle::State()), |
| 130 | + controller_interface::CallbackReturn::SUCCESS); |
| 131 | + ASSERT_EQ( |
| 132 | + controller_->on_activate(rclcpp_lifecycle::State()), |
| 133 | + controller_interface::CallbackReturn::SUCCESS); |
| 134 | +} |
| 135 | + |
| 136 | +TEST_F(PassthroughControllerTest, CommandSuccessTest) |
| 137 | +{ |
| 138 | + SetUpController(); |
| 139 | + |
| 140 | + // configure controller |
| 141 | + controller_->get_node()->set_parameter( |
| 142 | + {"interfaces", |
| 143 | + std::vector<std::string>{"joint1/interface", "joint2/interface", "joint3/interface"}}); |
| 144 | + |
| 145 | + ASSERT_EQ( |
| 146 | + controller_->on_configure(rclcpp_lifecycle::State()), |
| 147 | + controller_interface::CallbackReturn::SUCCESS); |
| 148 | + |
| 149 | + // update successful though no command has been send yet |
| 150 | + ASSERT_EQ( |
| 151 | + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), |
| 152 | + controller_interface::return_type::OK); |
| 153 | + |
| 154 | + // check joint commands are still the default ones |
| 155 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1); |
| 156 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1); |
| 157 | + ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1); |
| 158 | + |
| 159 | + // send command |
| 160 | + auto command_ptr = std::make_shared<passthrough_controller::DataType>(); |
| 161 | + command_ptr->data = {10.0, 20.0, 30.0}; |
| 162 | + controller_->rt_buffer_ptr_.writeFromNonRT(command_ptr); |
| 163 | + |
| 164 | + // update successful, command received |
| 165 | + ASSERT_EQ( |
| 166 | + controller_->update(rclcpp::Time(0.1), rclcpp::Duration::from_seconds(0.01)), |
| 167 | + controller_interface::return_type::OK); |
| 168 | + |
| 169 | + // check joint commands have been modified |
| 170 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0); |
| 171 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20.0); |
| 172 | + ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30.0); |
| 173 | +} |
| 174 | + |
| 175 | +TEST_F(PassthroughControllerTest, WrongCommandCheckTest) |
| 176 | +{ |
| 177 | + SetUpController(); |
| 178 | + |
| 179 | + // configure controller |
| 180 | + controller_->get_node()->set_parameter( |
| 181 | + {"interfaces", std::vector<std::string>{"joint1/interface", "joint2/interface"}}); |
| 182 | + |
| 183 | + ASSERT_EQ( |
| 184 | + controller_->on_configure(rclcpp_lifecycle::State()), |
| 185 | + controller_interface::CallbackReturn::SUCCESS); |
| 186 | + |
| 187 | + // send command with wrong number of joints |
| 188 | + auto command_ptr = std::make_shared<passthrough_controller::DataType>(); |
| 189 | + command_ptr->data = {10.0}; |
| 190 | + controller_->rt_buffer_ptr_.writeFromNonRT(command_ptr); |
| 191 | + |
| 192 | + // update failed, command size does not match number of joints |
| 193 | + ASSERT_EQ( |
| 194 | + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), |
| 195 | + controller_interface::return_type::ERROR); |
| 196 | + |
| 197 | + // check joint commands are still the default ones |
| 198 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1); |
| 199 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1); |
| 200 | +} |
| 201 | + |
| 202 | +TEST_F(PassthroughControllerTest, NoCommandCheckTest) |
| 203 | +{ |
| 204 | + SetUpController(); |
| 205 | + |
| 206 | + // configure controller |
| 207 | + controller_->get_node()->set_parameter( |
| 208 | + {"interfaces", std::vector<std::string>{"joint1/interface", "joint2/interface"}}); |
| 209 | + |
| 210 | + ASSERT_EQ( |
| 211 | + controller_->on_configure(rclcpp_lifecycle::State()), |
| 212 | + controller_interface::CallbackReturn::SUCCESS); |
| 213 | + |
| 214 | + // update successful, no command received yet |
| 215 | + ASSERT_EQ( |
| 216 | + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), |
| 217 | + controller_interface::return_type::OK); |
| 218 | + |
| 219 | + // check joint commands are still the default ones |
| 220 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1); |
| 221 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1); |
| 222 | +} |
| 223 | + |
| 224 | +TEST_F(PassthroughControllerTest, CommandCallbackTest) |
| 225 | +{ |
| 226 | + SetUpController(); |
| 227 | + |
| 228 | + // configure controller |
| 229 | + controller_->get_node()->set_parameter( |
| 230 | + {"interfaces", |
| 231 | + std::vector<std::string>{"joint1/interface", "joint2/interface", "joint3/interface"}}); |
| 232 | + |
| 233 | + // default values |
| 234 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1); |
| 235 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1); |
| 236 | + ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1); |
| 237 | + |
| 238 | + auto node_state = controller_->get_node()->configure(); |
| 239 | + ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); |
| 240 | + |
| 241 | + node_state = controller_->get_node()->activate(); |
| 242 | + ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); |
| 243 | + |
| 244 | + // send a new command |
| 245 | + rclcpp::Node test_node("test_node"); |
| 246 | + auto command_pub = test_node.create_publisher<std_msgs::msg::Float64MultiArray>( |
| 247 | + std::string(controller_->get_node()->get_name()) + "/commands", rclcpp::SystemDefaultsQoS()); |
| 248 | + std_msgs::msg::Float64MultiArray command_msg; |
| 249 | + command_msg.data = {10.0, 20.0, 30.0}; |
| 250 | + command_pub->publish(command_msg); |
| 251 | + |
| 252 | + // wait for command message to be passed |
| 253 | + ASSERT_EQ(wait_for(controller_->joints_cmd_sub_), rclcpp::WaitResultKind::Ready); |
| 254 | + |
| 255 | + // process callbacks |
| 256 | + rclcpp::spin_some(controller_->get_node()->get_node_base_interface()); |
| 257 | + |
| 258 | + // update successful |
| 259 | + ASSERT_EQ( |
| 260 | + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), |
| 261 | + controller_interface::return_type::OK); |
| 262 | + |
| 263 | + // check command in handle was set |
| 264 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0); |
| 265 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20.0); |
| 266 | + ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30.0); |
| 267 | +} |
| 268 | + |
| 269 | +TEST_F(PassthroughControllerTest, ActivateDeactivateCommandsResetSuccess) |
| 270 | +{ |
| 271 | + SetUpController(); |
| 272 | + |
| 273 | + // configure controller |
| 274 | + controller_->get_node()->set_parameter( |
| 275 | + {"interfaces", |
| 276 | + std::vector<std::string>{"joint1/interface", "joint2/interface", "joint3/interface"}}); |
| 277 | + |
| 278 | + // default values |
| 279 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1); |
| 280 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1); |
| 281 | + ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1); |
| 282 | + |
| 283 | + auto node_state = controller_->configure(); |
| 284 | + ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); |
| 285 | + |
| 286 | + node_state = controller_->get_node()->activate(); |
| 287 | + ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); |
| 288 | + |
| 289 | + auto command_msg = std::make_shared<std_msgs::msg::Float64MultiArray>(); |
| 290 | + command_msg->data = {10.0, 20.0, 30.0}; |
| 291 | + |
| 292 | + controller_->rt_buffer_ptr_.writeFromNonRT(command_msg); |
| 293 | + |
| 294 | + // update successful |
| 295 | + ASSERT_EQ( |
| 296 | + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), |
| 297 | + controller_interface::return_type::OK); |
| 298 | + |
| 299 | + // check command in handle was set |
| 300 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10); |
| 301 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20); |
| 302 | + ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30); |
| 303 | + |
| 304 | + node_state = controller_->get_node()->deactivate(); |
| 305 | + ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE); |
| 306 | + |
| 307 | + // command ptr should be reset (nullptr) after deactivation - same check as in `update` |
| 308 | + ASSERT_FALSE( |
| 309 | + controller_->rt_buffer_ptr_.readFromNonRT() && *(controller_->rt_buffer_ptr_.readFromNonRT())); |
| 310 | + ASSERT_FALSE( |
| 311 | + controller_->rt_buffer_ptr_.readFromRT() && *(controller_->rt_buffer_ptr_.readFromRT())); |
| 312 | + |
| 313 | + // Controller is inactive but let's put some data into buffer (simulate callback when inactive) |
| 314 | + command_msg = std::make_shared<std_msgs::msg::Float64MultiArray>(); |
| 315 | + command_msg->data = {5.5, 6.6, 7.7}; |
| 316 | + |
| 317 | + controller_->rt_buffer_ptr_.writeFromNonRT(command_msg); |
| 318 | + |
| 319 | + // command ptr should be available and message should be there - same check as in `update` |
| 320 | + ASSERT_TRUE( |
| 321 | + controller_->rt_buffer_ptr_.readFromNonRT() && *(controller_->rt_buffer_ptr_.readFromNonRT())); |
| 322 | + ASSERT_TRUE( |
| 323 | + controller_->rt_buffer_ptr_.readFromRT() && *(controller_->rt_buffer_ptr_.readFromRT())); |
| 324 | + |
| 325 | + // Now activate again |
| 326 | + node_state = controller_->get_node()->activate(); |
| 327 | + ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); |
| 328 | + |
| 329 | + // command ptr should be reset (nullptr) after activation - same check as in `update` |
| 330 | + ASSERT_FALSE( |
| 331 | + controller_->rt_buffer_ptr_.readFromNonRT() && *(controller_->rt_buffer_ptr_.readFromNonRT())); |
| 332 | + ASSERT_FALSE( |
| 333 | + controller_->rt_buffer_ptr_.readFromRT() && *(controller_->rt_buffer_ptr_.readFromRT())); |
| 334 | + |
| 335 | + // update successful |
| 336 | + ASSERT_EQ( |
| 337 | + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), |
| 338 | + controller_interface::return_type::OK); |
| 339 | + |
| 340 | + // values should not change |
| 341 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10); |
| 342 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20); |
| 343 | + ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30); |
| 344 | + |
| 345 | + // set commands again |
| 346 | + controller_->rt_buffer_ptr_.writeFromNonRT(command_msg); |
| 347 | + |
| 348 | + // update successful |
| 349 | + ASSERT_EQ( |
| 350 | + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), |
| 351 | + controller_interface::return_type::OK); |
| 352 | + |
| 353 | + // check command in handle was set |
| 354 | + ASSERT_EQ(joint_1_pos_cmd_.get_value(), 5.5); |
| 355 | + ASSERT_EQ(joint_2_pos_cmd_.get_value(), 6.6); |
| 356 | + ASSERT_EQ(joint_3_pos_cmd_.get_value(), 7.7); |
| 357 | +} |
0 commit comments