|
| 1 | +// Copyright 2015 Open Source Robotics Foundation, Inc. |
| 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 | + |
| 15 | +#ifndef PENDULUM_DEMO_PENDULUM_CONTROLLER_HPP_ |
| 16 | +#define PENDULUM_DEMO_PENDULUM_CONTROLLER_HPP_ |
| 17 | + |
| 18 | +#include <chrono> |
| 19 | + |
| 20 | +#include <pendulum_msgs/msg/joint_command.hpp> |
| 21 | +#include <pendulum_msgs/msg/joint_state.hpp> |
| 22 | + |
| 23 | +#ifndef PI |
| 24 | +#define PI 3.14159265359 |
| 25 | +#endif |
| 26 | + |
| 27 | +namespace pendulum_control |
| 28 | +{ |
| 29 | + |
| 30 | +struct PIDProperties |
| 31 | +{ |
| 32 | + // Properties of a PID controller |
| 33 | + double p = 1; |
| 34 | + double i = 0; |
| 35 | + double d = 0; |
| 36 | + double command = PI / 2; |
| 37 | +}; |
| 38 | + |
| 39 | +class PendulumController |
| 40 | +{ |
| 41 | +public: |
| 42 | + PendulumController(std::chrono::nanoseconds period, PIDProperties pid) |
| 43 | + : publish_period_(period), pid_(pid), |
| 44 | + command_message_(std::make_shared<pendulum_msgs::msg::JointCommand>()), |
| 45 | + message_ready_(false) |
| 46 | + { |
| 47 | + command_message_->position = pid_.command; |
| 48 | + dt_ = publish_period_.count() / (1000.0 * 1000.0 * 1000.0); |
| 49 | + if (isnan(dt_) || dt_ == 0) { |
| 50 | + throw std::runtime_error("Invalid dt_ calculated in PendulumController constructor"); |
| 51 | + } |
| 52 | + } |
| 53 | + |
| 54 | + // Calculate new command based on new sensor state and PID controller properties |
| 55 | + void on_sensor_message(const pendulum_msgs::msg::JointState::SharedPtr msg) |
| 56 | + { |
| 57 | + ++messages_received; |
| 58 | + |
| 59 | + if (isnan(msg->position)) { |
| 60 | + throw std::runtime_error("Sensor value was NaN in on_sensor_message callback"); |
| 61 | + } |
| 62 | + double error = pid_.command - msg->position; |
| 63 | + double p_gain = pid_.p * error; |
| 64 | + i_gain_ = pid_.i * (i_gain_ + error * dt_); |
| 65 | + double d_gain = pid_.d * (error - last_error_) / dt_; |
| 66 | + last_error_ = error; |
| 67 | + |
| 68 | + // TODO consider filtering the PID output |
| 69 | + command_message_->position = msg->position + p_gain + i_gain_ + d_gain; |
| 70 | + // limits |
| 71 | + if (command_message_->position > PI) { |
| 72 | + command_message_->position = PI; |
| 73 | + } else if (command_message_->position < 0) { |
| 74 | + command_message_->position = 0; |
| 75 | + } |
| 76 | + |
| 77 | + if (isnan(command_message_->position)) { |
| 78 | + throw std::runtime_error("Resulting command was NaN in on_sensor_message callback"); |
| 79 | + } |
| 80 | + message_ready_ = true; |
| 81 | + } |
| 82 | + |
| 83 | + const pendulum_msgs::msg::JointCommand::SharedPtr get_next_command_message() |
| 84 | + { |
| 85 | + return command_message_; |
| 86 | + } |
| 87 | + |
| 88 | + bool next_message_ready() const |
| 89 | + { |
| 90 | + return message_ready_; |
| 91 | + } |
| 92 | + |
| 93 | + std::chrono::nanoseconds get_publish_period() const |
| 94 | + { |
| 95 | + return publish_period_; |
| 96 | + } |
| 97 | + |
| 98 | + void set_pid_properties(const PIDProperties & properties) |
| 99 | + { |
| 100 | + pid_ = properties; |
| 101 | + } |
| 102 | + |
| 103 | + const PIDProperties & get_pid_properties() const |
| 104 | + { |
| 105 | + return pid_; |
| 106 | + } |
| 107 | + |
| 108 | + void set_command(double command) |
| 109 | + { |
| 110 | + pid_.command = command; |
| 111 | + } |
| 112 | + |
| 113 | + double get_command() const |
| 114 | + { |
| 115 | + return pid_.command; |
| 116 | + } |
| 117 | + |
| 118 | + // gather statistics |
| 119 | + size_t messages_received = 0; |
| 120 | + |
| 121 | +private: |
| 122 | + // controller should publish less frequently than the motor |
| 123 | + std::chrono::nanoseconds publish_period_; |
| 124 | + PIDProperties pid_; |
| 125 | + pendulum_msgs::msg::JointCommand::SharedPtr command_message_; |
| 126 | + bool message_ready_; |
| 127 | + |
| 128 | + // state for PID controller |
| 129 | + double last_error_ = 0; |
| 130 | + double i_gain_ = 0; |
| 131 | + double dt_; |
| 132 | +}; |
| 133 | + |
| 134 | +} /* namespace pendulum_demo */ |
| 135 | + |
| 136 | +#endif /* PENDULUM_DEMO_PENDULUM_CONTROLLER_HPP_ */ |
0 commit comments