Ros2 实时编程实践第二章 -- ros2 lifecycle node

1 前言和资料

pendulum demo design 提到了其关键节点使用了 ros2 的 lifecycle node 机制来满足实时性要求,RealtimeROS2 里也提到了 lifecycle node 可用于实时编程。本文我们将专题研究 ros2 的 lifecycle node。
本文参考资料如下:
(1)lifecycle
(2)node_lifecycle
(3)Pendulum demo design

2 正文

2.1 lifecycle node 设计详解

(1)lifecycle node 引入:通常情况下,一个 C++ 实时性程序应具有三段式:
初始化阶段(非实时):申请堆内存,创建并启动线程等。
运行阶段(实时):正常运行阶段,一般是循环体实现,要求具有实时性。
销毁阶段(非实时):释放堆内存,回收线程。
为了标准化这个流程,ros2 提供了 lifecycle node,其强制要求节点必须按照预定义的状态机进行状态转换,确保正常运行前,完成所有实例化。除此之外,lifecycle node 还支持在线暂停和激活节点。
(2)rclcpp_lifecycle::LifecycleNode 类:通常 ros2 的节点类需要继承 rclcpp::Node 基类,而实现 lifecycle node,则要求节点必须继承 rclcpp_lifecycle::LifecycleNode 类,下一节会有样例。
(3)lifecycle node 状态转换分析:下面这张图就是状态转换全貌,读懂他就懂 lifecycle 了。
在这里插入图片描述
四个基础状态(蓝色):

unconfigured(ID 为 1):节点刚被构造出来时的初始状态。
inactive(ID 为 2):节点已经完成初始化,并准备进入运行时的状态。在该状态下,节点不会参与任何计算或者发布/订阅操作。
active(ID 为 3):节点的运行时状态,必须满足一定的实时性要求。
finalized(ID 为 4):节点即将关闭时的状态,也是最后一个状态,此时节点无法重新启动。

六个过渡状态(黄色):

configuring:当节点从 unconfigured 转为 inactive 时,经过的中间状态,此时会执行 on_configure() 回调函数,下节有样例。
			对应的状态转换类型为 configure(ID 为 1)。
cleaningup:当节点从 inactive 转回 unconfigured 时,经过的中间状态,此时会执行 on_cleanup() 回调函数。
			对应的状态转换类型为 cleanup(ID 为 2)。
activating:当节点从 inactive 转为 active 时,经过的中间状态,此时会执行 on_activate() 回调函数。
			对应的状态转换类型为 activate(ID 为 3)。
deactivating:当节点从 active 转回 inactive 时,经过的中间状态,此时会执行 on_deactivate() 回调函数。
			对应的状态转换类型为 deactivate(ID 为 4)。
shuttingdown:节点从 unconfigured ,inactive 和 active 都可以转为 finalized,并经过 shuttingdown 中间状态,此时会执行 on_shutdown() 回调函数。
			对应的状态转换类型为 shutdown(ID 为 5,6,7,分别对应源状态 unconfigured ,inactive 和 active)。
errorprocessing:前面五个过渡状态和 active 基础状态都有可能发生错误并抛出,而这里就是处理错误的中间状态,此时会执行 on_error() 回调函数。
				处理成功,会转回 unconfigured 初始状态;处理失败,会进入 finalized 结束状态。

(4)lifecycle node 如何有利于实现实时编程:
第一,把实时代码与非实时代码明确分离开,即只有节点处于 active 状态时的运行函数才是实时代码,其他各种回调函数都是非实时代码。
第二,对 ros 节点提供了更精细的控制能力,包括确保正确的启动顺序,在线启停节点等。
第三,标准化了节点的生命周期管理。
(5)lifecycle node 还提供了命令行操作,这里解释命令,下节有样例。

# 查看正确活跃的 lifecycle 节点
ros2 lifecycle node
# 获取 lifecycle 节点的当前基础状态
ros2 lifecycle get {节点名}
# 获取 lifecyclde 节点当前可进行的状态转换
ros2 lifecycle list {节点名}
# 触发 lifecycle 节点进行状态转换
ros2 lifecycle set {节点名} {状态转换类型}

2.2 lifecycle_demo 实现

(1)lifecycle_demo 设计:本样例共设计了三个节点,细节如下。
lifecycle_talker :是 lifecycle node,并负责发布消息;
lifecycle_listener:是普通节点,负责订阅消息和上游 lifecycle_talker 的状态转换信息;
lifecycle_service_client:也是普通节点,利用 lifecycle node 提供的 service 服务,触发 lifecycle_talker 进行状态转换。
(2)创建 lifecycle_demo 软件包以及相关文件

cd ~/colcon_ws/src
ros2 pkg create --build-type ament_cmake --license Apache-2.0 lifecycle_demo --dependencies lifecycle_msgs rclcpp rclcpp_lifecycle std_msgs
cd lifecycle_demo
mkdir launch
touch src/lifecycle_talker.cpp src/lifecycle_listener.cpp src/lifecycle_service_client.cpp
touch launch/lifecycle_demo_launch.py

(3)lifecycle_talker.cpp

#include <chrono>
#include <memory>
#include <string>
#include <thread>
#include <utility>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"

#include "std_msgs/msg/string.hpp"

class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode {
public:
    // 通常情况下,不推荐在构造函数内进行资源申请,有可能失败,但又无法获取返回值
    // 如果这里是普通的 node,初始化部分应放在单独的 init 函数中,并根据返回值判断是否初始化成功
    explicit LifecycleTalker(const std::string& node_name, bool is_intra_process = false) : 
                            rclcpp_lifecycle::LifecycleNode(node_name, 
                            rclcpp::NodeOptions().use_intra_process_comms(is_intra_process)) {
        RCLCPP_INFO(this->get_logger(), "LifecycleTalker constructor is called");
    }

    // 这是 configuring 过渡状态的回调函数,用于初始化节点,完成后将从 unconfigured 进入 inactive 状态
    // 这里将完成程序的初始化,申请各种资源,创建发布器和定时器
    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
        const rclcpp_lifecycle::State& pre_state) {
        pub_str_ = this->create_publisher<std_msgs::msg::String>("lifecycle_chatter", 10);
        lc_timer_ = this->create_wall_timer(std::chrono::seconds(1), [this]() {return this->publish();});
        count_ = 0;

        RCLCPP_INFO(this->get_logger(), 
            "LifecycleTalker on_configure is called for initial, pre state is %s", pre_state.label().c_str());

        return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
    }

    // 这是定时器的回调函数,也是节点处于 active 状态时的主要工作函数,应满足实时性要求,因此不应该有 log,而应是一个纯粹的工作函数。
    void publish() {
        auto str_msg = std::make_unique<std_msgs::msg::String>();
        str_msg->data = "lifecycle say hello " + std::to_string(count_++);

        if (true == pub_str_->is_activated()) {
            RCLCPP_INFO(this->get_logger(), "LifecycleTalker publish: %s", str_msg->data.c_str());
        } else {
            RCLCPP_INFO(this->get_logger(), "LifecycleTalker is deactivated");
        }

        // 如果节点不处于 active 状态,即使调用了 publish ,也不会发布消息,lifecycle_listener 的 log 会证明这一点
        // 这是 lifecycle node 非常巧妙的一个设计,可以实现在线启动和关停节点
        pub_str_->publish(std::move(str_msg));
    }

    // 这是 activating 过渡状态的回调函数,完成后将从 inactive 进入 active 状态
    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(
        const rclcpp_lifecycle::State& pre_state) {
        LifecycleNode::on_activate(pre_state);

        RCLCPP_INFO(this->get_logger(), 
            "LifecycleTalker on_activate is called, pre state is %s", pre_state.label().c_str());

        std::this_thread::sleep_for(std::chrono::seconds(2));

        return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
    }

    // 这是 deactivating 过渡状态的回调函数,完成后将从 active 返回 inactive 状态
    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(
        const rclcpp_lifecycle::State& pre_state) {
        LifecycleNode::on_deactivate(pre_state);

        RCLCPP_INFO(this->get_logger(), 
            "LifecycleTalker on_deactivate is called, pre state is %s", pre_state.label().c_str());

        return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
    }    

    // 这是 cleaning 过渡状态的回调函数,完成后将从 inactive 返回 unconfigured 状态
    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(
        const rclcpp_lifecycle::State& pre_state) {
        // 释放资源,清空智能指针
        pub_str_.reset();
        lc_timer_.reset();

        RCLCPP_INFO(this->get_logger(), 
            "LifecycleTalker on_cleanup is called, pre state is %s", pre_state.label().c_str());

        return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
    }  

    // 这是 shuttingdown 过渡状态的回调函数,完成后将进入 finalized 状态
    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(
        const rclcpp_lifecycle::State& pre_state) {
        // 释放资源,清空智能指针
        pub_str_.reset();
        lc_timer_.reset();

        RCLCPP_INFO(this->get_logger(), 
            "LifecycleTalker on_shutdown is called, pre state is %s", pre_state.label().c_str());

        return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
    }  

private:
    std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::String>> pub_str_;
    std::shared_ptr<rclcpp::TimerBase> lc_timer_;
    size_t count_;
};

int main(int argc, char* argv[]) {
    rclcpp::init(argc, argv);
    // 单线程执行器,用于 lifecycle_talker 执行,其在单个线程顺序地执行所有回调函数,
    // 满足 lifecycle node 对状态转换必须严格按照顺序执行的要求
    rclcpp::executors::SingleThreadedExecutor exe;
    std::shared_ptr<LifecycleTalker> lc_talker = std::make_shared<LifecycleTalker>("lifecycle_talker");
    exe.add_node(lc_talker->get_node_base_interface());
    exe.spin();
    rclcpp::shutdown();
    return 0;
}

(4)lifecycle_listener.cpp

#include <functional>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

#include "lifecycle_msgs/msg/transition_event.hpp"

class LifecycleListener : public rclcpp::Node {
public:
    explicit LifecycleListener(const std::string& node_name) : Node(node_name) {
        // 上下游约定的 topic 名为 lifecycle_chatter
        sub_str_ = this->create_subscription<std_msgs::msg::String>(
            "lifecycle_chatter", 10, 
            [this](std_msgs::msg::String::ConstSharedPtr msg) {return this->str_cb(msg);});

        // 上游 lifecycle 节点名为 lifecycle_talker,因此他一定会附赠一个 lifecycle_talker/transition_event topic
        // 下游订阅这个 topic,可以获取到 lifecycle_talker 节点的状态变化信息
        sub_transition_ = this->create_subscription<lifecycle_msgs::msg::TransitionEvent>(
            "lifecycle_talker/transition_event", 10,
            [this](lifecycle_msgs::msg::TransitionEvent::ConstSharedPtr msg) {return this->trans_cb(msg);});

        RCLCPP_INFO(this->get_logger(), "LifecycleListener constructor is called");
    }

    void str_cb(std_msgs::msg::String::ConstSharedPtr str_msg) {
        RCLCPP_INFO(this->get_logger(), "str_cb: %s", str_msg->data.c_str());
    }

    void trans_cb(lifecycle_msgs::msg::TransitionEvent::ConstSharedPtr state_msg) {
        RCLCPP_INFO(this->get_logger(), "trans_cb: transition from %s to %s", 
            state_msg->start_state.label.c_str(), state_msg->goal_state.label.c_str());
    }


private:
    std::shared_ptr<rclcpp::Subscription<std_msgs::msg::String>> sub_str_;
    std::shared_ptr<rclcpp::Subscription<lifecycle_msgs::msg::TransitionEvent>> sub_transition_;
};

int main(int argc, char* argv[]) {
    rclcpp::init(argc, argv);
    rclcpp::spin(std::make_shared<LifecycleListener>("lifecycle_listener"));
    rclcpp::shutdown();
}

(5)lifecycle_service_client.cpp

#include <chrono>
#include <future>
#include <memory>
#include <string>
#include <thread>

#include "rclcpp/rclcpp.hpp"

#include "lifecycle_msgs/msg/state.hpp"
#include "lifecycle_msgs/msg/transition.hpp"
#include "lifecycle_msgs/srv/change_state.hpp"
#include "lifecycle_msgs/srv/get_state.hpp"

class LifecycleServiceClient : public rclcpp::Node {
public:
    explicit LifecycleServiceClient(const std::string & node_name) : Node(node_name) {
        RCLCPP_INFO(this->get_logger(), "LifecycleServiceClient constructor is called");
    }

    void init() {
        // client_get_state_topic 为 lifecycle_talker/get_state
        // client_change_state_topic 为 lifecycle_talker/change_state
        // 上游 lifecycle 节点名为 lifecycle_talker,因此他一定会附赠 lifecycle_talker/get_state 和 lifecycle_talker/change_state service
        // 触发器通过这两个 service ,可以驱动 lifecycle_talker 节点的状态变化
        client_get_state_ = this->create_client<lifecycle_msgs::srv::GetState>(client_get_state_topic);
        client_change_state_ = this->create_client<lifecycle_msgs::srv::ChangeState>(client_change_state_topic);
    }

    uint32_t get_state(std::chrono::seconds timeout = std::chrono::seconds(3)) {
        std::shared_ptr<lifecycle_msgs::srv::GetState::Request> get_state_req = 
            std::make_shared<lifecycle_msgs::srv::GetState::Request>();
        
        if (false == client_get_state_->wait_for_service(timeout)) {
            RCLCPP_ERROR(this->get_logger(), "service %s is not available", client_get_state_->get_service_name());
            // PRIMARY_STATE_UNKNOWN 为 0,表示未知状态
            return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
        }

        auto future_result = client_get_state_->async_send_request(get_state_req);
        if (rclcpp::spin_until_future_complete(this->get_node_base_interface(), future_result) == 
                                                        rclcpp::FutureReturnCode::SUCCESS) {
            // future_result 只能被调用一次,调用后会发生值转移,再次调用属于未定义行为
            // 因此这里缓存了 future_result 的值,免去二次调用
            auto tmp_result = future_result.get();
            RCLCPP_INFO(this->get_logger(), "node [%s] in state: %s", lifecycle_node.c_str(), 
                                                    tmp_result->current_state.label.c_str());
            return tmp_result->current_state.id;
        } else {
            RCLCPP_ERROR(this->get_logger(), "failed to call service %s", client_get_state_->get_service_name());
            return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
        }
    }

    bool change_state(std::uint8_t transition_id, std::chrono::seconds timeout = std::chrono::seconds(3)) {
        std::shared_ptr<lifecycle_msgs::srv::ChangeState::Request> change_state_req = 
            std::make_shared<lifecycle_msgs::srv::ChangeState::Request>();
        change_state_req->transition.id = transition_id;

        if (false == client_change_state_->wait_for_service(timeout)) {
            RCLCPP_ERROR(this->get_logger(), "service %s is not available", client_change_state_->get_service_name());
            return false;
        }

        auto future_result = client_change_state_->async_send_request(change_state_req);
        if (rclcpp::spin_until_future_complete(this->get_node_base_interface(), future_result) ==
                                                        rclcpp::FutureReturnCode::SUCCESS) {
            RCLCPP_INFO(this->get_logger(), "node [%s] transition %d is successful", lifecycle_node.c_str(), transition_id);
            return true;
        } else {
            RCLCPP_ERROR(this->get_logger(), "failed to call service %s, transition %d is failed", 
                                                client_change_state_->get_service_name(), transition_id);
            return false;
        }
    }

private:
    const std::string lifecycle_node = "lifecycle_talker";
    const std::string client_get_state_topic = "lifecycle_talker/get_state";
    const std::string client_change_state_topic = "lifecycle_talker/change_state";

    std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::GetState>> client_get_state_;
    std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::ChangeState>> client_change_state_;
};

// 按照 lifecycle node 的状态转换顺序,
// 依次触发 configure, activate, deactivate, activate, deactivate, cleanup, shutdown 状态转换
void trigger_change(std::shared_ptr<LifecycleServiceClient>& lc_client) {
    rclcpp::WallRate time_between_state_change(0.2);   // 0.2hz
    
    using Transition = lifecycle_msgs::msg::Transition;
    using State = lifecycle_msgs::msg::State;

    // configure 状态转换
    // 完成后,lifecycle_talker 节点将从 unconfigured 状态转换到 inactive 状态
    {
        if (false == lc_client->change_state(Transition::TRANSITION_CONFIGURE)) {
            RCLCPP_ERROR(lc_client->get_logger(), "failed to trigger state: configure");
            return;
        }

        if (State::PRIMARY_STATE_UNKNOWN == lc_client->get_state()) {
            RCLCPP_INFO(lc_client->get_logger(), "failed to get state in configure");
            return;
        }
    }

    // activate 状态转换
    // 完成后,lifecycle_talker 节点将从 inactive 状态转换到 active 状态
    {
        time_between_state_change.sleep();
        if (false == rclcpp::ok()) {
            return;
        }

        if (false == lc_client->change_state(Transition::TRANSITION_ACTIVATE)) {
            RCLCPP_ERROR(lc_client->get_logger(), "failed to trigger state: activate");
            return;
        }
        if (State::PRIMARY_STATE_UNKNOWN == lc_client->get_state()) {
            return;
        }
    }

    // deactivate 状态转换
    // 完成后,lifecycle_talker 节点将从 active 状态转回到 inactive 状态
    {
        time_between_state_change.sleep();
        if (false == rclcpp::ok()) {
            return;
        }

        if (false == lc_client->change_state(Transition::TRANSITION_DEACTIVATE)) {
            RCLCPP_ERROR(lc_client->get_logger(), "failed to trigger state: deactivate");
            return;
        }
        if (State::PRIMARY_STATE_UNKNOWN == lc_client->get_state()) {
            return;
        }
    }

    // activate it again
    {
        time_between_state_change.sleep();
        if (false == rclcpp::ok()) {
            return;
        }

        if (false == lc_client->change_state(Transition::TRANSITION_ACTIVATE)) {
            RCLCPP_ERROR(lc_client->get_logger(), "failed to trigger state: activate");
            return;
        }
        if (State::PRIMARY_STATE_UNKNOWN == lc_client->get_state()) {
            return;
        }
    }

    // deactivate it again
    {
        time_between_state_change.sleep();
        if (false == rclcpp::ok()) {
            return;
        }

        if (false == lc_client->change_state(Transition::TRANSITION_DEACTIVATE)) {
            RCLCPP_ERROR(lc_client->get_logger(), "failed to trigger state: deactivate");
            return;
        }
        if (State::PRIMARY_STATE_UNKNOWN == lc_client->get_state()) {
            return;
        }
    }

    // cleanup 状态转换
    // 完成后,lifecycle_talker 节点将从 inactive 状态转回到 unconfigured 状态
    {
        time_between_state_change.sleep();
        if (false == rclcpp::ok()) {
            return;
        }

        if (false == lc_client->change_state(Transition::TRANSITION_CLEANUP)) {
            RCLCPP_ERROR(lc_client->get_logger(), "failed to trigger state: cleanup");
            return;
        }
        if (State::PRIMARY_STATE_UNKNOWN == lc_client->get_state()) {
            return;
        }
    }

    // shutdown 状态转换
    // 完成后,lifecycle_talker 节点将从 unconfigured 状态转回到 finalized 状态
    {
        time_between_state_change.sleep();
        if (false == rclcpp::ok()) {
            return;
        }

        if (false == lc_client->change_state(Transition::TRANSITION_UNCONFIGURED_SHUTDOWN)) {
            RCLCPP_ERROR(lc_client->get_logger(), "failed to trigger state: shutdown");
            return;
        }
        if (State::PRIMARY_STATE_UNKNOWN == lc_client->get_state()) {
            return;
        }
    }
}

int main(int argc, char * argv[]) {
    rclcpp::init(argc, argv);
    std::shared_ptr<LifecycleServiceClient> lc_client = std::make_shared<LifecycleServiceClient>("lifecycle_service_client");
    lc_client->init();
    trigger_change(lc_client);
    rclcpp::shutdown();
    return 0;
}

(6)lifecycle_demo_launch.py

from launch import LaunchDescription
from launch.actions import Shutdown
from launch_ros.actions import LifecycleNode
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
        LifecycleNode(
            package="lifecycle_demo", 
            executable="lifecycle_talker",
            name="lifecycle_talker",
            namespace="cpp",
            output="screen"
        ),
        Node(
            package="lifecycle_demo",
            executable="lifecycle_listener",
            name="lifecycle_listener",
            namespace="cpp",
            output="screen"
        ),
        Node(
            package="lifecycle_demo",
            executable="lifecycle_service_client",
            name="lifecycle_service_client",
            namespace="cpp",
            output="screen",
            on_exit=Shutdown()
        )
    ])

(7)CMakeLists.txt

cmake_minimum_required(VERSION 3.8)
project(lifecycle_demo)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(std_msgs REQUIRED)

add_executable(lifecycle_talker src/lifecycle_talker.cpp)
ament_target_dependencies(lifecycle_talker lifecycle_msgs rclcpp rclcpp_lifecycle std_msgs)

add_executable(lifecycle_listener src/lifecycle_listener.cpp)
ament_target_dependencies(lifecycle_listener lifecycle_msgs rclcpp std_msgs)

add_executable(lifecycle_service_client src/lifecycle_service_client.cpp)
ament_target_dependencies(lifecycle_service_client lifecycle_msgs rclcpp)


install(TARGETS
  lifecycle_talker
  lifecycle_listener
  lifecycle_service_client
  DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY
  launch
  DESTINATION share/${PROJECT_NAME}
)
ament_package()

(8)编译并运行

cd ~/colcon_ws/src
colcon build --packages-select lifecycle_demo
source install/local_setup.bash
# 分成三个窗口运行,单独看运行 log 比较清晰(每个都别忘设置环境变量)
ros2 run lifecycle_demo lifecycle_talker
ros2 run lifecycle_demo lifecycle_listener
ros2 run lifecycle_demo lifecycle_service_client
# 使用 launch 文件运行
ros2 launch lifecycle_demo lifecycle_demo_launch.py
# 也可以关闭 lifecycle_service_client,测试命令行触发 lifecycle_talker 进行状态转换
ros2 lifecycle node
ros2 lifecycle get /lifecycle_talker 
ros2 lifecycle list /lifecycle_talker 
ros2 lifecycle set /lifecycle_talker shutdown

下图是使用 launch 文件运行时的一部分 log,其他方式,希望读者自己测试。
在这里插入图片描述

3 总结

本文代码托管在本人的 github 上:lifecycle_demo

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值