|
1 | 1 | #include "stiffness_control/joint_stiffness_controller.hpp"
|
2 | 2 |
|
3 |
| -namespace joint_stiffness_controller { |
| 3 | +namespace joint_stiffness_controller |
| 4 | +{ |
4 | 5 |
|
5 |
| -JointStiffnessController::JointStiffnessController() {} |
| 6 | +JointStiffnessController::JointStiffnessController() |
| 7 | +{ |
| 8 | +} |
6 | 9 |
|
7 |
| -controller_interface::CallbackReturn JointStiffnessController::on_init() { |
| 10 | +controller_interface::CallbackReturn JointStiffnessController::on_init() |
| 11 | +{ |
8 | 12 | return controller_interface::CallbackReturn::SUCCESS;
|
9 | 13 | }
|
10 | 14 |
|
11 |
| -controller_interface::CallbackReturn JointStiffnessController::on_configure(const rclcpp_lifecycle::State&) { |
| 15 | +controller_interface::CallbackReturn JointStiffnessController::on_configure(const rclcpp_lifecycle::State&) |
| 16 | +{ |
12 | 17 | auto node = get_node();
|
13 | 18 | command_sub_ = node->create_subscription<std_msgs::msg::Float64MultiArray>(
|
14 |
| - "~/command", 10, std::bind(&JointStiffnessController::command_callback, this, std::placeholders::_1)); |
| 19 | + "~/command", 10, std::bind(&JointStiffnessController::command_callback, this, std::placeholders::_1)); |
15 | 20 | return controller_interface::CallbackReturn::SUCCESS;
|
16 | 21 | }
|
17 | 22 |
|
18 |
| -controller_interface::InterfaceConfiguration JointStiffnessController::command_interface_configuration() const { |
| 23 | +controller_interface::InterfaceConfiguration JointStiffnessController::command_interface_configuration() const |
| 24 | +{ |
19 | 25 | return {
|
20 | 26 | controller_interface::interface_configuration_type::INDIVIDUAL,
|
21 |
| - {"joint1/position", "joint2/position"} // replace with your actual joints |
| 27 | + { "joint1/position", "joint2/position" } // replace with your actual joints |
22 | 28 | };
|
23 | 29 | }
|
24 | 30 |
|
25 |
| -controller_interface::InterfaceConfiguration JointStiffnessController::state_interface_configuration() const { |
| 31 | +controller_interface::InterfaceConfiguration JointStiffnessController::state_interface_configuration() const |
| 32 | +{ |
26 | 33 | return {
|
27 | 34 | controller_interface::interface_configuration_type::INDIVIDUAL,
|
28 |
| - {"joint1/position", "joint2/position"} // same joints |
| 35 | + { "joint1/position", "joint2/position" } // same joints |
29 | 36 | };
|
30 | 37 | }
|
31 | 38 |
|
32 |
| -void JointStiffnessController::command_callback(const std_msgs::msg::Float64MultiArray::SharedPtr msg) { |
| 39 | +void JointStiffnessController::command_callback(const std_msgs::msg::Float64MultiArray::SharedPtr msg) |
| 40 | +{ |
33 | 41 | size_t n = msg->data.size() / 2;
|
34 | 42 | desired_positions_.resize(n);
|
35 | 43 | stiffness_gains_.resize(n);
|
36 |
| - for (size_t i = 0; i < n; ++i) { |
| 44 | + for (size_t i = 0; i < n; ++i) |
| 45 | + { |
37 | 46 | desired_positions_[i] = msg->data[i];
|
38 | 47 | stiffness_gains_[i] = msg->data[i + n];
|
39 | 48 | }
|
40 | 49 | }
|
41 | 50 |
|
42 |
| -controller_interface::return_type JointStiffnessController::update( |
43 |
| - const rclcpp::Time&, const rclcpp::Duration&) { |
44 |
| - for (size_t i = 0; i < position_cmd_handles_.size(); ++i) { |
| 51 | +controller_interface::return_type JointStiffnessController::update(const rclcpp::Time&, const rclcpp::Duration&) |
| 52 | +{ |
| 53 | + for (size_t i = 0; i < position_cmd_handles_.size(); ++i) |
| 54 | + { |
45 | 55 | double error = desired_positions_[i] - position_state_handles_[i].get_optional().value_or(0.0);
|
46 | 56 | double command = stiffness_gains_[i] * error;
|
47 |
| - bool success = position_cmd_handles_[i].set_value(position_state_handles_[i].get_optional().value_or(0.0) + command); |
48 |
| - if (!success) { |
| 57 | + bool success = |
| 58 | + position_cmd_handles_[i].set_value(position_state_handles_[i].get_optional().value_or(0.0) + command); |
| 59 | + if (!success) |
| 60 | + { |
49 | 61 | RCLCPP_WARN(get_node()->get_logger(), "Failed to set command for joint %zu", i);
|
50 |
| -} |
| 62 | + } |
51 | 63 | }
|
52 | 64 | return controller_interface::return_type::OK;
|
53 | 65 | }
|
54 | 66 |
|
55 |
| -} // namespace joint_stiffness_controller |
| 67 | +} // namespace joint_stiffness_controller |
56 | 68 |
|
57 | 69 | #include "pluginlib/class_list_macros.hpp"
|
58 | 70 | PLUGINLIB_EXPORT_CLASS(joint_stiffness_controller::JointStiffnessController, controller_interface::ControllerInterface)
|
0 commit comments