Q;-}Ez!yPH2ut~YN?yY4m
z#F|D7F!8!rz@8)tIx0UWje9a
zD<;c3lO@(W5s}ej33VNmbmS)Nmh9li*gJ|8lx<-)kq=$n|LV)B?FK@}|4rGjQ`_Ir
z?jUO_&zgF+O!`+FQ{~v@_>G+|EcuV5R~OFxMbP`zxBrF1Hn+e0Cy{?XasMUK&8&@r
z?#q~M!DC@KZ`?cH&J`-ZX%>~fF;
zGlPZOk!BGX?u6fWf;v2gu|s7Mu6j@z!7xs!m7v55rui^27^MVVM88jjkufM{Vi?>1
rZ7)psK_QOe0;DA=xBj0pW0B*>ch2ISyfts(ee9@~zUC8kn;ZWh)^F|4
literal 0
HcmV?d00001
diff --git a/Software/ROS_Driver/ROS2-driver/doc/userdoc.rst b/Software/ROS_Driver/ROS2-driver/doc/userdoc.rst
new file mode 100644
index 0000000..4bc6f34
--- /dev/null
+++ b/Software/ROS_Driver/ROS2-driver/doc/userdoc.rst
@@ -0,0 +1,105 @@
+
+*********
+DiffBot
+*********
+
+*DiffBot*, or ''Differential Mobile Robot'', is a simple mobile base with differential drive.
+The robot is basically a box moving according to differential drive kinematics.
+
+For *example_2*, the hardware interface plugin is implemented having only one interface.
+
+* The communication is done using proprietary API to communicate with the robot control box.
+* Data for all joints is exchanged at once.
+
+The *DiffBot* URDF files can be found in ``description/urdf`` folder.
+
+.. include:: ../../doc/run_from_docker.rst
+
+Tutorial steps
+--------------------------
+
+1. To check that *DiffBot* description is working properly use following launch commands
+
+ .. code-block:: shell
+
+ ros2 launch ros2_control_demo_example_2 view_robot.launch.py
+
+ .. warning::
+ Getting the following output in terminal is OK: ``Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist``.
+ This happens because ``joint_state_publisher_gui`` node need some time to start.
+
+ .. image:: diffbot.png
+ :width: 400
+ :alt: Differential Mobile Robot
+
+2. To start *DiffBot* example open a terminal, source your ROS2-workspace and execute its launch file with
+
+ .. code-block:: shell
+
+ ros2 launch ros2_control_demo_example_2 diffbot.launch.py
+
+ The launch file loads and starts the robot hardware, controllers and opens *RViz*.
+ In the starting terminal you will see a lot of output from the hardware implementation showing its internal states.
+ This excessive printing is only added for demonstration. In general, printing to the terminal should be avoided as much as possible in a hardware interface implementation.
+
+ If you can see an orange box in *RViz* everything has started properly.
+ Still, to be sure, let's introspect the control system before moving *DiffBot*.
+
+3. Check if the hardware interface loaded properly, by opening another terminal and executing
+
+ .. code-block:: shell
+
+ ros2 control list_hardware_interfaces
+
+ You should get
+
+ .. code-block:: shell
+
+ command interfaces
+ left_wheel_joint/velocity [available] [claimed]
+ right_wheel_joint/velocity [available] [claimed]
+ state interfaces
+ left_wheel_joint/position
+ left_wheel_joint/velocity
+ right_wheel_joint/position
+ right_wheel_joint/velocity
+
+ The ``[claimed]`` marker on command interfaces means that a controller has access to command *DiffBot*.
+
+4. Check if controllers are running
+
+ .. code-block:: shell
+
+ ros2 control list_controllers
+
+ You should get
+
+ .. code-block:: shell
+
+ diffbot_base_controller[diff_drive_controller/DiffDriveController] active
+ joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active
+
+5. If everything is fine, now you can send a command to *Diff Drive Controller* using ROS 2 CLI interface:
+
+ .. code-block:: shell
+
+ ros2 topic pub --rate 30 /diffbot_base_controller/cmd_vel_unstamped geometry_msgs/msg/Twist "linear:
+ x: 0.7
+ y: 0.0
+ z: 0.0
+ angular:
+ x: 0.0
+ y: 0.0
+ z: 1.0"
+
+ You should now see an orange box circling in *RViz*.
+ Also, you should see changing states in the terminal where launch file is started.
+
+ .. code-block:: shell
+
+ [DiffBotSystemHardware]: Got command 43.33333 for 'left_wheel_joint'!
+ [DiffBotSystemHardware]: Got command 50.00000 for 'right_wheel_joint'!
+
+Files used for this demos
+--------------------------
+
diff --git a/Software/ROS_Driver/ROS2-driver/hardware/hoverboard_driver.cpp b/Software/ROS_Driver/ROS2-driver/hardware/hoverboard_driver.cpp
new file mode 100644
index 0000000..62e8d95
--- /dev/null
+++ b/Software/ROS_Driver/ROS2-driver/hardware/hoverboard_driver.cpp
@@ -0,0 +1,547 @@
+// Copyright 2021 ros2_control Development Team
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "hoverboard_driver/hoverboard_driver.hpp"
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "hardware_interface/types/hardware_interface_type_values.hpp"
+#include "rclcpp/rclcpp.hpp"
+
+namespace hoverboard_driver
+{
+
+ hoverboard_driver_node::hoverboard_driver_node() : Node("hoverboard_driver_node")
+ {
+ // These publishers are only for debugging purposes
+
+ vel_pub[left_wheel] = this->create_publisher("hoverboard/left_wheel/velocity", 3);
+ vel_pub[right_wheel] = this->create_publisher("hoverboard/right_wheel/velocity", 3);
+ pos_pub[left_wheel] = this->create_publisher("hoverboard/left_wheel/position", 3);
+ pos_pub[right_wheel] = this->create_publisher("hoverboard/right_wheel/position", 3);
+ cmd_pub[left_wheel] = this->create_publisher("hoverboard/left_wheel/cmd", 3);
+ cmd_pub[right_wheel] = this->create_publisher("hoverboard/right_wheel/cmd", 3);
+ voltage_pub = this->create_publisher("hoverboard/battery_voltage", 3);
+ temp_pub = this->create_publisher("hoverboard/temperature", 3);
+ curr_pub[left_wheel] = this->create_publisher("hoverboard/left_wheel/dc_current", 3);
+ curr_pub[right_wheel] = this->create_publisher("hoverboard/right_wheel/dc_current", 3);
+ connected_pub = this->create_publisher("hoverboard/connected", 3);
+
+ declare_parameter("f", 10.2);
+ declare_parameter("p", 1.0);
+ declare_parameter("i", 0.1);
+ declare_parameter("d", 1.0);
+ declare_parameter("i_clamp_min", -10.0);
+ declare_parameter("i_clamp_max", 10.0);
+ declare_parameter("antiwindup", false);
+ get_parameter("f", pid_config.f);
+ get_parameter("p", pid_config.p);
+ get_parameter("i", pid_config.i);
+ get_parameter("d", pid_config.d);
+ get_parameter("i_clamp_min", pid_config.i_clamp_min);
+ get_parameter("i_clamp_max", pid_config.i_clamp_max);
+ get_parameter("antiwindup", pid_config.antiwindup);
+
+ // register parameter change callback handle
+ callback_handle_ = this->add_on_set_parameters_callback(
+ std::bind(&hoverboard_driver_node::parametersCallback, this, std::placeholders::_1));
+ }
+
+ void hoverboard_driver_node::publish_vel(int wheel, double message)
+ {
+ std_msgs::msg::Float64 f;
+ f.data = message;
+ vel_pub[wheel]->publish(f);
+ }
+
+ void hoverboard_driver_node::publish_pos(int wheel, double message)
+ {
+ std_msgs::msg::Float64 f;
+ f.data = message;
+ pos_pub[wheel]->publish(f);
+ }
+
+ void hoverboard_driver_node::publish_cmd(int wheel, double message)
+ {
+ std_msgs::msg::Float64 f;
+ f.data = message;
+ cmd_pub[wheel]->publish(f);
+ }
+
+ void hoverboard_driver_node::publish_curr(int wheel, double message)
+ {
+ std_msgs::msg::Float64 f;
+ f.data = message;
+ curr_pub[wheel]->publish(f);
+ }
+
+ void hoverboard_driver_node::publish_voltage(double message)
+ {
+ std_msgs::msg::Float64 f;
+ f.data = message;
+ voltage_pub->publish(f);
+ }
+
+ void hoverboard_driver_node::publish_temp(double message)
+ {
+ std_msgs::msg::Float64 f;
+ f.data = message;
+ temp_pub->publish(f);
+ }
+
+ void hoverboard_driver_node::publish_connected(bool message)
+ {
+ std_msgs::msg::Bool f;
+ f.data = message;
+ connected_pub->publish(f);
+ }
+
+ rcl_interfaces::msg::SetParametersResult hoverboard_driver_node::parametersCallback(
+ const std::vector ¶meters)
+ {
+ rcl_interfaces::msg::SetParametersResult result;
+ result.successful = true;
+ result.reason = "success";
+ // Here update class attributes, do some actions, etc.
+ for (const auto ¶m : parameters)
+ {
+ if (param.get_name() == "p")
+ {
+ pid_config.p = param.as_double();
+ RCLCPP_INFO(get_logger(), "new value for PID P: %f", pid_config.p);
+ }
+ if (param.get_name() == "i")
+ {
+ pid_config.i = param.as_double();
+ RCLCPP_INFO(get_logger(), "new value for PID I: %f", pid_config.i);
+ }
+ if (param.get_name() == "d")
+ {
+ pid_config.d = param.as_double();
+ RCLCPP_INFO(get_logger(), "new value for PID D: %f", pid_config.d);
+ }
+ if (param.get_name() == "f")
+ {
+ pid_config.p = param.as_double();
+ RCLCPP_INFO(get_logger(), "new value for PID F: %f", pid_config.f);
+ }
+ if (param.get_name() == "i_clamp_min")
+ {
+ pid_config.i_clamp_min = param.as_double();
+ RCLCPP_INFO(get_logger(), "new value for PID I_CLAMP_MIN: %f", pid_config.i_clamp_min);
+ }
+ if (param.get_name() == "i_clamp_max")
+ {
+ pid_config.i_clamp_max = param.as_double();
+ RCLCPP_INFO(get_logger(), "new value for PID I_CLAMP_MAX: %f", pid_config.i_clamp_max);
+ }
+ if (param.get_name() == "antiwindup")
+ {
+ pid_config.antiwindup = param.as_bool();
+ RCLCPP_INFO(get_logger(), "new value for PID ANTIWINDUP: %i", pid_config.antiwindup);
+ }
+
+ // HINT: the PID configuration itself will be set by timer callback of hoverboard_driver class
+ }
+
+ return result;
+ }
+
+ hardware_interface::CallbackReturn hoverboard_driver::on_init(
+ const hardware_interface::HardwareInfo &info)
+ {
+ if (
+ hardware_interface::SystemInterface::on_init(info) !=
+ hardware_interface::CallbackReturn::SUCCESS)
+ {
+ return hardware_interface::CallbackReturn::ERROR;
+ }
+ // read parameter from hoverboard_driver.ros2_control.xacro file
+ wheel_radius = std::stod(info_.hardware_parameters["wheel_radius"]);
+ max_velocity = std::stod(info_.hardware_parameters["max_velocity"]);
+ port = info_.hardware_parameters["device"];
+ hw_positions_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN());
+ hw_velocities_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN());
+ hw_commands_.resize(info_.joints.size(), std::numeric_limits::quiet_NaN());
+
+ for (const hardware_interface::ComponentInfo &joint : info_.joints)
+ {
+ // DiffBotSystem has exactly two states and one command interface on each joint
+ if (joint.command_interfaces.size() != 1)
+ {
+ RCLCPP_FATAL(
+ rclcpp::get_logger("HoverBoardSystemHardware"),
+ "Joint '%s' has %zu command interfaces found. 1 expected.", joint.name.c_str(),
+ joint.command_interfaces.size());
+ return hardware_interface::CallbackReturn::ERROR;
+ }
+
+ if (joint.command_interfaces[0].name != hardware_interface::HW_IF_VELOCITY)
+ {
+ RCLCPP_FATAL(
+ rclcpp::get_logger("HoverBoardSystemHardware"),
+ "Joint '%s' have %s command interfaces found. '%s' expected.", joint.name.c_str(),
+ joint.command_interfaces[0].name.c_str(), hardware_interface::HW_IF_VELOCITY);
+ return hardware_interface::CallbackReturn::ERROR;
+ }
+
+ if (joint.state_interfaces.size() != 2)
+ {
+ RCLCPP_FATAL(
+ rclcpp::get_logger("HoverBoardSystemHardware"),
+ "Joint '%s' has %zu state interface. 2 expected.", joint.name.c_str(),
+ joint.state_interfaces.size());
+ return hardware_interface::CallbackReturn::ERROR;
+ }
+
+ if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION)
+ {
+ RCLCPP_FATAL(
+ rclcpp::get_logger("HoverBoardSystemHardware"),
+ "Joint '%s' have '%s' as first state interface. '%s' expected.", joint.name.c_str(),
+ joint.state_interfaces[0].name.c_str(), hardware_interface::HW_IF_POSITION);
+ return hardware_interface::CallbackReturn::ERROR;
+ }
+
+ if (joint.state_interfaces[1].name != hardware_interface::HW_IF_VELOCITY)
+ {
+ RCLCPP_FATAL(
+ rclcpp::get_logger("HoverBoardSystemHardware"),
+ "Joint '%s' have '%s' as second state interface. '%s' expected.", joint.name.c_str(),
+ joint.state_interfaces[1].name.c_str(), hardware_interface::HW_IF_VELOCITY);
+ return hardware_interface::CallbackReturn::ERROR;
+ }
+ }
+
+ hardware_publisher = std::make_shared(); // fire up the publisher node
+
+ return hardware_interface::CallbackReturn::SUCCESS;
+ }
+
+ std::vector hoverboard_driver::export_state_interfaces()
+ {
+ std::vector state_interfaces;
+ for (auto i = 0u; i < info_.joints.size(); i++)
+ {
+ state_interfaces.emplace_back(hardware_interface::StateInterface(
+ info_.joints[i].name, hardware_interface::HW_IF_POSITION, &hw_positions_[i]));
+ state_interfaces.emplace_back(hardware_interface::StateInterface(
+ info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_velocities_[i]));
+ }
+
+ return state_interfaces;
+ }
+
+ std::vector hoverboard_driver::export_command_interfaces()
+ {
+ std::vector command_interfaces;
+ for (auto i = 0u; i < info_.joints.size(); i++)
+ {
+ command_interfaces.emplace_back(hardware_interface::CommandInterface(
+ info_.joints[i].name, hardware_interface::HW_IF_VELOCITY, &hw_commands_[i]));
+ }
+
+ return command_interfaces;
+ }
+
+ hardware_interface::CallbackReturn hoverboard_driver::on_activate(
+ const rclcpp_lifecycle::State & /*previous_state*/)
+ {
+
+ RCLCPP_INFO(rclcpp::get_logger("hoverboard_driver"), "Using port %s", port.c_str());
+
+ // Convert m/s to rad/s
+ max_velocity /= wheel_radius;
+
+ low_wrap = ENCODER_LOW_WRAP_FACTOR * (ENCODER_MAX - ENCODER_MIN) + ENCODER_MIN;
+ high_wrap = ENCODER_HIGH_WRAP_FACTOR * (ENCODER_MAX - ENCODER_MIN) + ENCODER_MIN;
+ last_wheelcountR = last_wheelcountL = 0;
+ multR = multL = 0;
+
+ first_read_pass_ = true;
+
+ // Init PID controller
+ pids[0].init(hardware_publisher->pid_config.f, hardware_publisher->pid_config.p,
+ hardware_publisher->pid_config.i, hardware_publisher->pid_config.d,
+ hardware_publisher->pid_config.i_clamp_max, hardware_publisher->pid_config.i_clamp_min,
+ hardware_publisher->pid_config.antiwindup, max_velocity, -max_velocity);
+ pids[0].setOutputLimits(-max_velocity, max_velocity);
+ pids[1].init(hardware_publisher->pid_config.f, hardware_publisher->pid_config.p,
+ hardware_publisher->pid_config.i, hardware_publisher->pid_config.d,
+ hardware_publisher->pid_config.i_clamp_max, hardware_publisher->pid_config.i_clamp_min,
+ hardware_publisher->pid_config.antiwindup, max_velocity, -max_velocity);
+ pids[1].setOutputLimits(-max_velocity, max_velocity);
+
+ if ((port_fd = open(port.c_str(), O_RDWR | O_NOCTTY | O_NDELAY)) < 0)
+ {
+ RCLCPP_FATAL(rclcpp::get_logger("hoverboard_driver"), "Cannot open serial port to hoverboard");
+ exit(-1);
+ }
+
+ // CONFIGURE THE UART -- connecting to the board
+ // The flags (defined in /usr/include/termios.h - see http://pubs.opengroup.org/onlinepubs/007908799/xsh/termios.h.html):
+ struct termios options;
+ tcgetattr(port_fd, &options);
+ options.c_cflag = B115200 | CS8 | CLOCAL | CREAD; // 0 && i++ < 1024)
+ protocol_recv(time, c);
+
+ if (i > 0)
+ last_read = time;
+
+ if (r < 0 && errno != EAGAIN)
+ RCLCPP_ERROR(rclcpp::get_logger("hoverboard_driver"), "Reading from serial %s failed: %d", port.c_str(), r);
+ }
+
+ if ((time - last_read).seconds() > 1)
+ {
+ // ROS_FATAL("Timeout reading from serial %s failed", port.c_str());
+
+ // publish false when not receiving serial data
+ hardware_publisher->publish_connected(false);
+ }
+ else
+ {
+ // we must be connected - publish true
+ hardware_publisher->publish_connected(true);
+ }
+ return hardware_interface::return_type::OK;
+ }
+
+ void hoverboard_driver::protocol_recv(const rclcpp::Time &time, char byte)
+ {
+ start_frame = ((uint16_t)(byte) << 8) | (uint8_t)prev_byte;
+
+ // Read the start frame
+ if (start_frame == START_FRAME)
+ {
+ p = (char *)&msg;
+ *p++ = prev_byte;
+ *p++ = byte;
+ msg_len = 2;
+ }
+ else if (msg_len >= 2 && msg_len < sizeof(SerialFeedback))
+ {
+ // Otherwise just read the message content until the end
+ *p++ = byte;
+ msg_len++;
+ }
+
+ if (msg_len == sizeof(SerialFeedback))
+ {
+ uint16_t checksum = (uint16_t)(msg.start ^
+ msg.cmd1 ^
+ msg.cmd2 ^
+ msg.speedR_meas ^
+ msg.speedL_meas ^
+ msg.wheelR_cnt ^
+ msg.wheelL_cnt ^
+ msg.left_dc_curr ^
+ msg.right_dc_curr ^
+ msg.batVoltage ^
+ msg.boardTemp ^
+ msg.cmdLed);
+
+ if (msg.start == START_FRAME && msg.checksum == checksum)
+ {
+ hardware_publisher->publish_voltage((double)msg.batVoltage / 100.0);
+ hardware_publisher->publish_temp((double)msg.boardTemp / 10.0);
+ ;
+ hardware_publisher->publish_curr(left_wheel, (double)msg.left_dc_curr / 100.0);
+ hardware_publisher->publish_curr(right_wheel, (double)msg.right_dc_curr / 100.0);
+
+ // Convert RPM to RAD/S
+ hw_velocities_[left_wheel] = direction_correction * (abs(msg.speedL_meas) * 0.10472);
+ hw_velocities_[right_wheel] = direction_correction * (abs(msg.speedR_meas) * 0.10472);
+ hardware_publisher->publish_vel(left_wheel, hw_velocities_[left_wheel]);
+ hardware_publisher->publish_vel(right_wheel, hw_velocities_[right_wheel]);
+
+ // Process encoder values and update odometry
+ on_encoder_update(time, msg.wheelR_cnt, msg.wheelL_cnt);
+ }
+ else
+ {
+ RCLCPP_WARN(rclcpp::get_logger("hoverboard_driver"), "Hoverboard checksum mismatch: %d vs %d", msg.checksum, checksum);
+ }
+ msg_len = 0;
+ }
+ prev_byte = byte;
+ }
+
+ hardware_interface::return_type hoverboard_driver::hoverboard_driver::write(
+ const rclcpp::Time &time, const rclcpp::Duration &period)
+ {
+ if (port_fd == -1)
+ {
+ RCLCPP_ERROR(rclcpp::get_logger("hoverboard_driver"), "Attempt to write on closed serial");
+ return hardware_interface::return_type::ERROR;
+ }
+ // Inform interested parties about the commands we've got
+ hardware_publisher->publish_cmd(left_wheel, hw_commands_[left_wheel]);
+ hardware_publisher->publish_cmd(right_wheel, hw_commands_[right_wheel]);
+
+ // Set PID Parameters
+ pids[0].setParameters(hardware_publisher->pid_config.f, hardware_publisher->pid_config.p,
+ hardware_publisher->pid_config.i, hardware_publisher->pid_config.d,
+ hardware_publisher->pid_config.i_clamp_max, hardware_publisher->pid_config.i_clamp_min,
+ hardware_publisher->pid_config.antiwindup);
+ pids[1].setParameters(hardware_publisher->pid_config.f, hardware_publisher->pid_config.p,
+ hardware_publisher->pid_config.i, hardware_publisher->pid_config.d,
+ hardware_publisher->pid_config.i_clamp_max, hardware_publisher->pid_config.i_clamp_min,
+ hardware_publisher->pid_config.antiwindup);
+
+ // calculate PID values
+ double pid_outputs[2];
+ pid_outputs[0] = pids[0](hw_velocities_[left_wheel], hw_commands_[left_wheel], period);
+ pid_outputs[1] = pids[1](hw_velocities_[left_wheel], hw_commands_[right_wheel], period);
+
+ // Convert PID outputs in RAD/S to RPM
+ //double set_speed[2] = {
+ // pid_outputs[0] / 0.10472,
+ // pid_outputs[1] / 0.10472};
+
+ double set_speed[2] = {
+ hw_commands_[left_wheel] / 0.10472,
+ hw_commands_[right_wheel] / 0.10472
+ };
+
+ // Calculate steering from difference of left and right
+ const double speed = (set_speed[0] + set_speed[1]) / 2.0;
+ const double steer = (set_speed[0] - speed) * 2.0;
+
+ SerialCommand command;
+ command.start = (uint16_t)START_FRAME;
+ command.steer = (int16_t)steer;
+ command.speed = (int16_t)speed;
+ command.checksum = (uint16_t)(command.start ^ command.steer ^ command.speed);
+
+ int rc = ::write(port_fd, (const void *)&command, sizeof(command));
+ if (rc < 0)
+ {
+ RCLCPP_ERROR(rclcpp::get_logger("hoverboard_driver"), "Error writing to hoverboard serial port");
+ }
+ return hardware_interface::return_type::OK;
+ }
+
+ void hoverboard_driver::on_encoder_update(const rclcpp::Time &time, int16_t right, int16_t left)
+ {
+ double posL = 0.0, posR = 0.0;
+
+ // Calculate wheel position in ticks, factoring in encoder wraps
+ if (right < low_wrap && last_wheelcountR > high_wrap)
+ multR++;
+ else if (right > high_wrap && last_wheelcountR < low_wrap)
+ multR--;
+ posR = right + multR * (ENCODER_MAX - ENCODER_MIN);
+ last_wheelcountR = right;
+
+ if (left < low_wrap && last_wheelcountL > high_wrap)
+ multL++;
+ else if (left > high_wrap && last_wheelcountL < low_wrap)
+ multL--;
+ posL = left + multL * (ENCODER_MAX - ENCODER_MIN);
+ last_wheelcountL = left;
+
+ // When the board shuts down and restarts, wheel ticks are reset to zero so the robot can be suddently lost
+ // This section accumulates ticks even if board shuts down and is restarted
+ static double lastPosL = 0.0, lastPosR = 0.0;
+ static double lastPubPosL = 0.0, lastPubPosR = 0.0;
+ static bool nodeStartFlag = true;
+
+ // IF there has been a pause in receiving data AND the new number of ticks is close to zero, indicates a board restard
+ //(the board seems to often report 1-3 ticks on startup instead of zero)
+ // reset the last read ticks to the startup values
+ if ((time - last_read).seconds() > 0.2 && abs(posL) < 5 && abs(posR) < 5)
+ {
+ lastPosL = posL;
+ lastPosR = posR;
+ }
+ double posLDiff = 0;
+ double posRDiff = 0;
+
+ // if node is just starting keep odom at zeros
+ if (nodeStartFlag)
+ {
+ nodeStartFlag = false;
+ }
+ else
+ {
+ posLDiff = posL - lastPosL;
+ posRDiff = posR - lastPosR;
+ }
+
+ lastPubPosL += posLDiff;
+ lastPubPosR += posRDiff;
+ lastPosL = posL;
+ lastPosR = posR;
+
+ // Convert position in accumulated ticks to position in radians
+ hw_positions_[left_wheel] = 2.0 * M_PI * lastPubPosL / (double)TICKS_PER_ROTATION;
+ hw_positions_[right_wheel] = 2.0 * M_PI * lastPubPosR / (double)TICKS_PER_ROTATION;
+
+ hardware_publisher->publish_pos(left_wheel, hw_positions_[left_wheel]);
+ hardware_publisher->publish_pos(right_wheel, hw_positions_[right_wheel]);
+ }
+
+} // namespace hoverboard_driver
+
+#include "pluginlib/class_list_macros.hpp"
+PLUGINLIB_EXPORT_CLASS(
+ hoverboard_driver::hoverboard_driver, hardware_interface::SystemInterface)
diff --git a/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/config.hpp b/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/config.hpp
new file mode 100644
index 0000000..e238550
--- /dev/null
+++ b/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/config.hpp
@@ -0,0 +1,9 @@
+#pragma once
+
+
+#define ENCODER_MIN 0
+#define ENCODER_MAX 9000
+#define ENCODER_LOW_WRAP_FACTOR 0.3
+#define ENCODER_HIGH_WRAP_FACTOR 0.7
+
+#define TICKS_PER_ROTATION 90
diff --git a/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/hoverboard_driver.hpp b/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/hoverboard_driver.hpp
new file mode 100644
index 0000000..6b9867b
--- /dev/null
+++ b/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/hoverboard_driver.hpp
@@ -0,0 +1,188 @@
+// Copyright 2021 ros2_control Development Team
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef HOVERBOARD_DRIVER_HPP_
+#define HOVERBOARD_DRIVER_HPP_
+
+#include
+#include
+#include
+
+#include "hardware_interface/handle.hpp"
+#include "hardware_interface/hardware_info.hpp"
+#include "hardware_interface/system_interface.hpp"
+#include "hardware_interface/types/hardware_interface_return_values.hpp"
+#include "rclcpp/clock.hpp"
+#include "rclcpp/duration.hpp"
+#include "rclcpp/macros.hpp"
+#include "rclcpp/time.hpp"
+#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
+#include "rclcpp_lifecycle/state.hpp"
+#include "hoverboard_driver/config.hpp"
+#include "hoverboard_driver/protocol.hpp"
+#include "hoverboard_driver/pid.hpp"
+#include "rclcpp/rclcpp.hpp"
+#include "std_msgs/msg/float64.hpp"
+#include "std_msgs/msg/bool.hpp"
+#include "rcl_interfaces/msg/set_parameters_result.hpp"
+
+namespace hoverboard_driver
+{
+
+ enum
+ {
+ /// @brief left wheel
+ left_wheel,
+ /// @brief right wheel
+ right_wheel
+ };
+
+ /// @brief Helper class to get a node interface. This class is used to build publishers and dynamic parameters
+ /// for hoverboard_driver class.
+ class hoverboard_driver_node : public rclcpp::Node
+ {
+ public:
+ hoverboard_driver_node();
+ /// @brief publish velocity data for debugging
+ /// @param wheel left or right wheel
+ /// @param message value to publish
+ void publish_vel(int wheel, double message);
+
+ /// @brief publish pose data for debugging
+ /// @param wheel left or right wheel
+ /// @param message value to publish
+ void publish_pos(int wheel, double message);
+
+ /// @brief publish command data for debugging
+ /// @param wheel left or right wheel
+ /// @param message value to publish
+ void publish_cmd(int wheel, double message);
+
+ /// @brief publish battery voltage
+ /// @param message value to publish
+ void publish_voltage(double message);
+
+ /// @brief publish current (power consumption) of motor
+ /// @param wheel left or right wheel
+ /// @param message value to publish
+ void publish_curr(int wheel, double message);
+
+ /// @brief publish PCB temperature
+ /// @param message value to publish
+ void publish_temp(double message);
+
+
+ /// @brief publish state of PCB (on or off)
+ /// @param message value to publish
+ void publish_connected(bool message);
+
+ /// @brief parameter callback method.
+ /// @param parameters
+ /// @return
+ rcl_interfaces::msg::SetParametersResult parametersCallback(
+ const std::vector ¶meters);
+
+ /// @brief PID configuration structure
+ struct
+ {
+ double p;
+ double i;
+ double d;
+ double f;
+ double i_clamp_min;
+ double i_clamp_max;
+ bool antiwindup;
+ } pid_config;
+
+ private:
+ // Publishers
+ rclcpp::Publisher::SharedPtr vel_pub[2];
+ rclcpp::Publisher::SharedPtr pos_pub[2];
+ rclcpp::Publisher::SharedPtr cmd_pub[2];
+ rclcpp::Publisher::SharedPtr voltage_pub;
+ rclcpp::Publisher::SharedPtr curr_pub[2];
+ rclcpp::Publisher::SharedPtr temp_pub;
+ rclcpp::Publisher::SharedPtr connected_pub;
+
+ // Parameter Callback handle
+ OnSetParametersCallbackHandle::SharedPtr callback_handle_;
+ };
+
+ /// @brief Hardware Interface class to communicate with Hoverboard PCB
+ class hoverboard_driver : public hardware_interface::SystemInterface
+ {
+ public:
+ RCLCPP_SHARED_PTR_DEFINITIONS(hoverboard_driver);
+
+ hardware_interface::CallbackReturn on_init(
+ const hardware_interface::HardwareInfo &info) override;
+
+ std::vector export_state_interfaces() override;
+
+ std::vector export_command_interfaces() override;
+
+ hardware_interface::CallbackReturn on_activate(
+ const rclcpp_lifecycle::State &previous_state) override;
+
+ hardware_interface::CallbackReturn on_deactivate(
+ const rclcpp_lifecycle::State &previous_state) override;
+
+ hardware_interface::return_type read(
+ const rclcpp::Time &time, const rclcpp::Duration &period) override;
+
+ // HOVERBOARD_DRIVER_PUBLIC
+ hardware_interface::return_type write(
+ const rclcpp::Time &time, const rclcpp::Duration &period) override;
+
+ std::shared_ptr hardware_publisher; // make the publisher node a member
+ private:
+ // Store the command for the simulated robot
+ std::vector hw_commands_;
+ std::vector hw_positions_;
+ std::vector hw_velocities_;
+
+ void protocol_recv(const rclcpp::Time &time, char c);
+ void on_encoder_update(const rclcpp::Time &time, int16_t right, int16_t left);
+
+ double wheel_radius;
+ double max_velocity = 0.0;
+ int direction_correction = 1;
+ std::string port;
+
+ rclcpp::Time last_read;
+ bool first_read_pass_;
+ // Last known encoder values
+ int16_t last_wheelcountR;
+ int16_t last_wheelcountL;
+ // Count of full encoder wraps
+ int multR;
+ int multL;
+ // Thresholds for calculating the wrap
+ int low_wrap;
+ int high_wrap;
+
+ // Hoverboard protocol
+ int port_fd;
+ unsigned long msg_len = 0;
+ char prev_byte = 0;
+ uint16_t start_frame = 0;
+ char *p;
+ SerialFeedback msg, prev_msg;
+
+ PID pids[2];
+ };
+
+} // namespace hoverboard_driver
+
+#endif // HOVERBOARD_DRIVER_HPP_
diff --git a/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/pid.hpp b/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/pid.hpp
new file mode 100644
index 0000000..277f7f4
--- /dev/null
+++ b/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/pid.hpp
@@ -0,0 +1,131 @@
+
+#include
+#include
+#include
+
+class PID : public control_toolbox::Pid
+{
+ public:
+ /**
+ * @brief Construct a new PID object
+ *
+ * @param p The proportional gain.
+ * @param i The integral gain.
+ * @param d The derivative gain.
+ * @param i_max The max integral windup.
+ * @param i_min The min integral windup.
+ * @param out_min The min computed output.
+ * @param out_max The max computed output.
+ */
+ PID(double p=0.0, double i=0.0, double d=0.0, double i_max=0.0, double i_min=0.0, bool antiwindup=false, double out_max=0.0, double out_min=0.0);
+
+ /**
+ * @brief Initialize the
+ *
+ * @param kF The feed forward gain.
+ * @param kP The proportional gain.
+ * @param kI The integral gain.
+ * @param kD The derivative gain.
+ * @param i_max The max integral windup.
+ * @param i_min The min integral windup.
+ * @param antiwindup
+ * @param out_min The min computed output.
+ * @param out_max The max computed output.
+ */
+ void init(double f, double p, double i, double d, double i_max, double i_min, bool antiwindup, double out_max, double out_min);
+
+ /**
+ * @brief Compute PID output value from error using process value, set point and time period
+ *
+ * @param measured_value The process value measured by sensors.
+ * @param setpoint The desired target value.
+ * @param dt The delta time or period since the last call.
+ * @return double Computed PID output value.
+ */
+ double operator()(const double &measured_value, const double &setpoint, const rclcpp::Duration &dt);
+
+ /**
+ * @brief Get the FPID parameters
+ *
+ * @param f The feed forward gain.
+ * @param p The proportional gain.
+ * @param i The integral gain.
+ * @param d The derivative gain.
+ * @param i_max The max integral windup.
+ * @param i_min The min integral windup.
+ * @param antiwindup Enable or disable antiwindup check.
+ */
+ void getParameters(double &f, double &p, double &i, double &d, double &i_max, double &i_min);
+ void getParameters(double &f, double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup);
+
+ /**
+ * @brief Set the Parameters using the Gains object of control_toolbox::Pid
+ *
+ * @param f The feed forward gain.
+ * @param p The proportional gain.
+ * @param i The integral gain.
+ * @param d The derivative gain.
+ * @param i_max The max integral windup.
+ * @param i_min The min integral windup.
+ * @param antiwindup Enable or disable antiwindup check.
+ */
+ void setParameters(double f, double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
+
+ /**
+ * @brief Set the Output Limits of the PID controller
+ *
+ * @param out_min
+ * @param out_max
+ */
+ void setOutputLimits(double out_min, double out_max);
+
+ /**
+ * @brief Clam given value to upper and lower limits.
+ *
+ * @param value Input value that's possibly clamped.
+ * @param lower_limit Lower limit which the value must not exceed.
+ * @param upper_limit Upper limit which the value must not exceed.
+ * @return double Clamped value to range in between [lower_limit, upper_limit].
+ */
+ double clamp(const double& value, const double& lower_limit, const double& upper_limit);
+
+ /**
+ * @brief Get the current error.
+ *
+ * @return double The current error computed from the measured and target value.
+ */
+ inline double getError() const { return error_; };
+
+ /**
+ * @brief Start the dynamic reconfigure node and load the default values
+ * @param node - a node handle where dynamic reconfigure services will be published
+ */
+ // void initDynamicReconfig(ros::NodeHandle &node);
+
+ /**
+ * @brief Set Dynamic Reconfigure's gains to PID's values
+ */
+ //void updateDynamicReconfig();
+ //void updateDynamicReconfig(Gains gains_config);
+ //void updateDynamicReconfig(hoverboard_driver::HoverboardConfig config);
+
+ /**
+ * \brief Update the PID parameters from dynamics reconfigure
+ */
+ //void dynamicReconfigCallback(hoverboard_driver::HoverboardConfig &config, uint32_t /*level*/);
+
+ private:
+ double f_;
+ double error_;
+ double out_min_;
+ double out_max_;
+ rclcpp::Node::SharedPtr node_;
+
+ // Dynamic reconfigure
+ bool dynamic_reconfig_initialized_;
+ // typedef dynamic_reconfigure::Server DynamicReconfigServer;
+ //boost::shared_ptr param_reconfig_server_;
+ //DynamicReconfigServer::CallbackType param_reconfig_callback_;
+
+ // boost::recursive_mutex param_reconfig_mutex_;
+};
diff --git a/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/protocol.hpp b/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/protocol.hpp
new file mode 100644
index 0000000..d08e921
--- /dev/null
+++ b/Software/ROS_Driver/ROS2-driver/hardware/include/hoverboard_driver/protocol.hpp
@@ -0,0 +1,30 @@
+
+#ifndef _FOC_PROTOCOL_H
+#define _FOC_PROTOCOL_H
+
+#define START_FRAME 0xABCD
+
+typedef struct {
+ uint16_t start;
+ int16_t steer;
+ int16_t speed;
+ uint16_t checksum;
+} SerialCommand;
+
+typedef struct {
+ uint16_t start;
+ int16_t cmd1;
+ int16_t cmd2;
+ int16_t speedR_meas;
+ int16_t speedL_meas;
+ int16_t wheelR_cnt;
+ int16_t wheelL_cnt;
+ int16_t left_dc_curr;
+ int16_t right_dc_curr;
+ int16_t batVoltage;
+ int16_t boardTemp;
+ uint16_t cmdLed;
+ uint16_t checksum;
+} SerialFeedback;
+
+#endif
diff --git a/Software/ROS_Driver/ROS2-driver/hardware/pid.cpp b/Software/ROS_Driver/ROS2-driver/hardware/pid.cpp
new file mode 100644
index 0000000..c85fa90
--- /dev/null
+++ b/Software/ROS_Driver/ROS2-driver/hardware/pid.cpp
@@ -0,0 +1,107 @@
+
+#include "hoverboard_driver/pid.hpp"
+
+PID::PID(double p, double i, double d, double i_max, double i_min, bool antiwindup, double out_max, double out_min)
+ : control_toolbox::Pid()
+{
+ f_ = 0.0;
+ initPid(p, i, d, i_max, i_min, antiwindup);
+ error_ = 0.0;
+
+ out_min_ = out_min;
+ out_max_ = out_max;
+}
+
+void PID::init(double f, double p, double i, double d, double i_max, double i_min, bool antiwindup, double out_max, double out_min)
+{
+ RCLCPP_INFO(rclcpp::get_logger("hoverboard_driver"), "Initialize PID");
+ f_ = f;
+ initPid(p, i, d, i_max, i_min, antiwindup);
+ error_ = 0.0;
+
+ out_min_ = out_min;
+ out_max_ = out_max;
+
+ Gains gains = getGains();
+ RCLCPP_DEBUG_STREAM(rclcpp::get_logger("hoverboard_driver"), "Initialized PID: F=" << f << ", P=" << gains.p_gain_ << ", I=" << gains.i_gain_ << ", D=" << gains.d_gain_ << ", out_min=" << out_min_ << ", out_max=" << out_max_);
+}
+
+double PID::operator()(const double &measured_value, const double &setpoint, const rclcpp::Duration &dt)
+{
+ // Compute error terms
+ error_ = setpoint - measured_value;
+ // rclcpp::Clock clock; // NOTA: Puede mamar
+ // RCLCPP_DEBUG_STREAM_THROTTLE(
+ // node_->get_logger(), clock, 1000000000, "Error: " << error_);
+
+ // Reset the i_error in case the p_error and the setpoint is zero
+ // Otherwise there will always be a constant i_error_ that won't vanish
+ if (0.0 == setpoint && 0.0 == error_)
+ {
+ // reset() will reset
+ // p_error_last_ = 0.0;
+ // p_error_ = 0.0;
+ // i_error_ = 0.0;
+ // d_error_ = 0.0;
+ // cmd_ = 0.0;
+ reset();
+ }
+
+ // Use control_toolbox::Pid::computeCommand()
+ double output = computeCommand(error_, dt.nanoseconds());
+ // RCLCPP_DEBUG_STREAM_THROTTLE(node_->get_logger(), clock, dt.nanoseconds(),
+ // "PID computed command: " << output);
+
+ // Compute final output including feed forward term
+ output = f_ * setpoint + output;
+ //output = clamp(output, out_min_, out_max_);
+
+ return output;
+}
+
+void PID::getParameters(double &f, double &p, double &i, double &d, double &i_max, double &i_min)
+{
+ bool antiwindup;
+ getParameters(f, p, i, d, i_max, i_min, antiwindup);
+}
+
+void PID::getParameters(double &f, double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup)
+{
+ f = f_;
+ // Call getGains from control_toolbox
+ getGains(p, i, d, i_max, i_min, antiwindup);
+}
+
+void PID::setParameters(double f, double p, double i, double d, double i_max, double i_min, bool antiwindup)
+{
+ f_ = f;
+ setGains(p, i, d, i_max, i_min, antiwindup);
+
+ Gains gains = getGains();
+ RCLCPP_DEBUG_STREAM(rclcpp::get_logger("hoverboard_driver"), "Update PID Gains: F=" << f << ", P=" << gains.p_gain_ << ", I=" << gains.i_gain_ << ", D=" << gains.d_gain_ << ", out_min=" << out_min_ << ", out_max=" << out_max_);
+}
+
+void PID::setOutputLimits(double output_max, double output_min)
+{
+ out_max_ = output_max;
+ out_min_ = output_min;
+ RCLCPP_DEBUG_STREAM(rclcpp::get_logger("hoverboard_driver"), "Update PID output limits: lower=" << out_min_ << ", upper=" << out_max_);
+}
+
+
+double PID::clamp(const double& value, const double& lower_limit, const double& upper_limit)
+{
+ rclcpp::Clock clock;
+ if (value > upper_limit){
+ RCLCPP_DEBUG_STREAM_THROTTLE(
+ rclcpp::get_logger("hoverboard_driver"), clock, 1000000000,
+ "Clamp " << value << " to upper limit " << upper_limit);
+ return upper_limit;
+ }else if (value < lower_limit){
+ RCLCPP_DEBUG_STREAM_THROTTLE(
+ rclcpp::get_logger("hoverboard_driver"), clock, 1000000000,
+ "Clamp " << value << " to lower limit " << upper_limit);
+ return lower_limit;
+ }
+ return value;
+}
\ No newline at end of file
diff --git a/Software/ROS_Driver/ROS2-driver/hoverboard_driver.xml b/Software/ROS_Driver/ROS2-driver/hoverboard_driver.xml
new file mode 100644
index 0000000..0a3fe6e
--- /dev/null
+++ b/Software/ROS_Driver/ROS2-driver/hoverboard_driver.xml
@@ -0,0 +1,9 @@
+
+
+
+ The ros2_control DiffBot example using a system hardware interface-type. It uses velocity command and position state interface. The example is the starting point to implement a hardware interface for differential-drive mobile robots.
+
+
+
diff --git a/Software/ROS_Driver/ROS2-driver/package.xml b/Software/ROS_Driver/ROS2-driver/package.xml
new file mode 100644
index 0000000..11f77db
--- /dev/null
+++ b/Software/ROS_Driver/ROS2-driver/package.xml
@@ -0,0 +1,42 @@
+
+
+
+ hoverboard_driver
+ 0.0.0
+ Demo package of `ros2_control` hardware for DiffBot.
+
+ Dr.-Ing. Denis Štogl
+ Bence Magyar
+ Christoph Froehlich
+
+ Dr.-Ing. Denis Štogl
+
+ Apache-2.0
+
+ ament_cmake
+
+ hardware_interface
+ pluginlib
+ rclcpp
+ rclcpp_lifecycle
+
+
+ controller_manager
+ diff_drive_controller
+ joint_state_broadcaster
+ joint_state_publisher_gui
+ robot_state_publisher
+
+ ros2_controllers_test_nodes
+ ros2controlcli
+ ros2launch
+ rviz2
+ xacro
+ control_toolbox
+
+ ament_cmake_gtest
+
+
+ ament_cmake
+
+