在無人機集群項目的算法開發中,推選長機作為集群的動態中心,往往承擔著集群管理、通訊中繼等重要功能。由于通訊鏈路的有限性和任務的實時性需要,需要保證動態長機時刻工作正常,并在異常情況下快速切換新長機。
本文主要分享基于braft的長機推選算法。在 ROS2 系統中基于 braft 設計無人機集群的長機推選算法需要結合分布式共識算法和 ROS2 的通信機制。以下是實現該算法的詳細步驟。
1 理解 braft 與長機推選
braft
百度開源的分布式一致性算法庫,基于 Raft 協議實現,提供領導者選舉、日志復制和安全性保障。
長機推選
在無人機集群中動態選擇一個 Leader(長機)負責決策,其他無人機作為 Follower(僚機)執行命令。
2. ROS2 與 braft 集成架構
3. 核心實現步驟
步驟 1:創建 ROS2 工作空間和包
mkdir -p ~/drone_ws/src
cd ~/drone_ws/src
ros2 pkg create --build-type ament_cmake drone_leader_election --dependencies rclcpp
cd ~/drone_ws
colcon build --packages-select drone_leader_election
source install/setup.bash
步驟 2:集成 braft 庫
在CMakeLists.txt中添加 braft 依賴:
find_package(braft REQUIRED)add_executable(drone_leader_node src/drone_leader_node.cpp)
target_link_libraries(drone_leader_node${rclcpp_LIBRARIES}braft
)
步驟 3:實現長機推選節點
#include <rclcpp/rclcpp.hpp>
#include <braft/raft.h>
#include <braft/node.h>
#include <braft/protobuf_file.h>
#include <drone_msgs/msg/leader_status.hpp>
#include <drone_msgs/msg/drone_command.hpp>// 定義狀態機
class DroneStateMachine : public braft::StateMachine {
public:// Raft狀態變化回調void on_leader_start(int64_t term) override {RCLCPP_INFO(rclcpp::get_logger("drone_state_machine"), "Become leader on term %ld, I'm the master drone now!", term);is_leader_ = true;publish_leader_status(true);}void on_leader_stop(const butil::Status& status) override {RCLCPP_INFO(rclcpp::get_logger("drone_state_machine"), "Lost leadership: %s, become a follower", status.to_string().c_str());is_leader_ = false;publish_leader_status(false);}// 其他必要實現...private:bool is_leader_ = false;rclcpp::Publisher<drone_msgs::msg::LeaderStatus>::SharedPtr leader_pub_;void publish_leader_status(bool is_leader) {auto msg = std::make_unique<drone_msgs::msg::LeaderStatus>();msg->is_leader = is_leader;msg->drone_id = get_my_drone_id(); // 自定義函數獲取本機IDleader_pub_->publish(std::move(msg));}
};// 主節點類
class DroneLeaderNode : public rclcpp::Node {
public:DroneLeaderNode() : Node("drone_leader_node") {// 初始化braft配置init_braft();// 創建ROS2發布者和訂閱者leader_status_pub_ = this->create_publisher<drone_msgs::msg::LeaderStatus>("leader_status", 10);command_sub_ = this->create_subscription<drone_msgs::msg::DroneCommand>("drone_command", 10, [this](const drone_msgs::msg::DroneCommand::SharedPtr msg) {if (state_machine_->is_leader()) {// 長機處理命令process_command(*msg);} else {// 僚機轉發給長機forward_to_leader(*msg);}});}private:void init_braft() {// 配置braft節點braft::NodeOptions node_options;node_options.initial_conf.parse_from("127.0.0.1:8001,127.0.0.1:8002,127.0.0.1:8003"); // 集群地址// 創建狀態機state_machine_ = std::make_shared<DroneStateMachine>();node_options.fsm = state_machine_.get();// 啟動braft節點std::string node_id = "drone_" + std::to_string(get_my_drone_id());std::string ip_port = "127.0.0.1:" + std::to_string(8001 + get_my_drone_id());braft::NodeId node_id_obj(node_id, ip_port);node_ = std::make_unique<braft::Node>(node_id_obj);butil::Status status = node_->init(node_options);if (!status.ok()) {RCLCPP_ERROR(this->get_logger(), "Failed to initialize braft node: %s", status.to_string().c_str());}}std::shared_ptr<DroneStateMachine> state_machine_;std::unique_ptr<braft::Node> node_;rclcpp::Publisher<drone_msgs::msg::LeaderStatus>::SharedPtr leader_status_pub_;rclcpp::Subscription<drone_msgs::msg::DroneCommand>::SharedPtr command_sub_;
};int main(int argc, char** argv) {rclcpp::init(argc, argv);auto node = std::make_shared<DroneLeaderNode>();rclcpp::spin(node);rclcpp::shutdown();return 0;
}
步驟 4:定義消息接口
創建 ROS2 消息定義文件:
# 在drone_leader_election包中創建msg目錄
mkdir -p ~/drone_ws/src/drone_leader_election/msg
touch ~/drone_ws/src/drone_leader_election/msg/LeaderStatus.msg
touch ~/drone_ws/src/drone_leader_election/msg/DroneCommand.msg
步驟 5:配置 CMakeLists.txt 和 package.xml
在CMakeLists.txt中添加消息生成規則:
find_package(rosidl_default_generators REQUIRED)rosidl_generate_interfaces(${PROJECT_NAME}"msg/LeaderStatus.msg""msg/DroneCommand.msg"
)ament_export_dependencies(rosidl_default_runtime)
4. 算法工作流程
初始化階段:
所有無人機節點啟動 braft 并加入集群。
braft 自動選舉出 Leader(長機)。
運行階段:
長機通過 ROS2 發布LeaderStatus消息。
集群命令由長機接收并處理,僚機轉發命令給長機。
braft 保證即使長機故障,也能快速選舉新的長機。
故障處理:
當長機離線時,braft 自動觸發重新選舉。
新長機接管控制權,確保集群連續性。
5. 部署與測試
為每臺無人機配置不同的節點 ID 和端口。
啟動所有無人機節點,觀察日志確認選舉結果。
使用rqt_graph可視化節點通信。
通過發送命令測試長機響應和僚機轉發功能。
文中提過的機間通訊可以通過話題通訊,也可以在機間采用gRPC或bRPC進行機間信息的交互,其中交互的日志信息不僅實現了長機狀態的判斷,還實現了數據共享,在長機切換后仍然保留任務管理信息,使得集群任務能夠絲滑繼續,從而保證了無人機集群任務執行的魯棒性。
本期無人機自由開發坊關于無人機集群動態長機推舉的分享,更多討論可加入無人機自由開發群(過期可加UavFree95)。