Robot Operating System——深度解析自动隐式加载动态库的运行模式

《Robot Operating System——深度解析手动加载动态库的运行模式》一文中,我们分析了如何通过dlopen形式加载动态库,从而让其中的Node节点在进程中运行的底层原理。本文我们将演示和解析隐式加载动态库的方式。

相较于手工加载动态库,隐式加载会在程序运行时自动加载动态库,而不需要我们手动调用dlopen来打开指定的库路径。

编译链接

在ROS2的例子中,composition/src/dlopen_composition.cpp是手工加载动态库;composition/src/linktime_composition.cpp是隐式加载动态库。它们在编译链接时的指令是不同的。

add_executable(dlopen_composition
  src/dlopen_composition.cpp)
ament_target_dependencies(dlopen_composition
  "class_loader"
  "rclcpp"
  "rclcpp_components")

add_executable(linktime_composition
  src/linktime_composition.cpp)
set(libs
  talker_component
  listener_component
  server_component
  client_component)
if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
  set(libs
    "-Wl,--no-as-needed"
    ${libs}
    "-Wl,--as-needed")
endif()
target_link_libraries(linktime_composition ${libs})
ament_target_dependencies(linktime_composition
  "class_loader"
  "rclcpp"
  "rclcpp_components")

dlopen_composition的编译链接很简单,不牵扯诸如talker_component这些动态库;但是linktime_composition编译时,要求将talker_component、listener_component、server_component和client_component这些动态库通过-Wl,--no-as-needed链接命令链接到linktime_composition这个可执行文件中。需要注意的是,这并不是说让这4个库的全部代码都链接进来,而是只是让linktime_composition在启动时自动加载这些动态库。

如果后面有时间,我会开一个专题专门研究和讲解ELF文件格式和引用,来讲解这种隐式加载的底层原理。大家可以先行参考《PE文件和COFF文件格式分析——导出表的应用——通过导出表隐性加载DLL》这篇文章,了解Windows上可自行程序/动态库是如何隐式加载动态库的。

我们可以看下linktime_composition的链接指令

/usr/bin/c++ CMakeFiles/linktime_composition.dir/src/linktime_composition.cpp.o -o linktime_composition -Wl,-rpath,/home/fangliang/github/ros2/demos/composition/build/composition:/opt/ros/jazzy/lib: -Wl,–no-as-needed libtalker_component.so liblistener_component.so libserver_component.so libclient_component.so -Wl,–as-needed /opt/ros/jazzy/lib/libcomponent_manager.so /opt/ros/jazzy/lib/libstd_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/libstd_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/libstd_msgs__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libstd_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/libstd_msgs__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/libstd_msgs__rosidl_generator_py.so /opt/ros/jazzy/lib/libstd_msgs__rosidl_typesupport_c.so /opt/ros/jazzy/lib/libstd_msgs__rosidl_generator_c.so /opt/ros/jazzy/lib/libclass_loader.so /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.1.0 /opt/ros/jazzy/lib/librclcpp.so /opt/ros/jazzy/lib/liblibstatistics_collector.so /opt/ros/jazzy/lib/librcl.so /opt/ros/jazzy/lib/librmw_implementation.so /opt/ros/jazzy/lib/libtype_description_interfaces__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/libtype_description_interfaces__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libtype_description_interfaces__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/libtype_description_interfaces__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/libtype_description_interfaces__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/libtype_description_interfaces__rosidl_generator_py.so /opt/ros/jazzy/lib/libtype_description_interfaces__rosidl_typesupport_c.so /opt/ros/jazzy/lib/libtype_description_interfaces__rosidl_generator_c.so /opt/ros/jazzy/lib/librcl_yaml_param_parser.so /opt/ros/jazzy/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/librosgraph_msgs__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/librosgraph_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/librosgraph_msgs__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/librosgraph_msgs__rosidl_generator_py.so /opt/ros/jazzy/lib/librosgraph_msgs__rosidl_typesupport_c.so /opt/ros/jazzy/lib/librosgraph_msgs__rosidl_generator_c.so /opt/ros/jazzy/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/libstatistics_msgs__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libstatistics_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/libstatistics_msgs__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/libstatistics_msgs__rosidl_generator_py.so /opt/ros/jazzy/lib/libstatistics_msgs__rosidl_typesupport_c.so /opt/ros/jazzy/lib/libstatistics_msgs__rosidl_generator_c.so /opt/ros/jazzy/lib/libtracetools.so -llttng-ust -llttng-ust-common -rdynamic -ldl /opt/ros/jazzy/lib/librcl_logging_interface.so /opt/ros/jazzy/lib/libcomposition_interfaces__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/libcomposition_interfaces__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libcomposition_interfaces__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/libcomposition_interfaces__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/libcomposition_interfaces__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/libcomposition_interfaces__rosidl_generator_py.so /opt/ros/jazzy/lib/librcl_interfaces__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/librcl_interfaces__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/librcl_interfaces__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/librcl_interfaces__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/librcl_interfaces__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/librcl_interfaces__rosidl_generator_py.so /opt/ros/jazzy/lib/libcomposition_interfaces__rosidl_typesupport_c.so /opt/ros/jazzy/lib/librcl_interfaces__rosidl_typesupport_c.so /opt/ros/jazzy/lib/libcomposition_interfaces__rosidl_generator_c.so /opt/ros/jazzy/lib/librcl_interfaces__rosidl_generator_c.so /opt/ros/jazzy/lib/libexample_interfaces__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/libexample_interfaces__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libexample_interfaces__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/libexample_interfaces__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/libexample_interfaces__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/libexample_interfaces__rosidl_generator_py.so /opt/ros/jazzy/lib/libexample_interfaces__rosidl_typesupport_c.so /opt/ros/jazzy/lib/libexample_interfaces__rosidl_generator_c.so /opt/ros/jazzy/lib/libaction_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/libaction_msgs__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libaction_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/libaction_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/libaction_msgs__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/libservice_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/libunique_identifier_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/libservice_msgs__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libunique_identifier_msgs__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libaction_msgs__rosidl_typesupport_c.so /opt/ros/jazzy/lib/libaction_msgs__rosidl_generator_c.so /opt/ros/jazzy/lib/libservice_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/libunique_identifier_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/libservice_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/libunique_identifier_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/libservice_msgs__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/libunique_identifier_msgs__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/librosidl_typesupport_fastrtps_c.so /opt/ros/jazzy/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/librosidl_typesupport_fastrtps_cpp.so /opt/ros/jazzy/lib/librmw.so /opt/ros/jazzy/lib/librosidl_dynamic_typesupport.so /opt/ros/jazzy/lib/libfastcdr.so.2.2.2 /opt/ros/jazzy/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/librosidl_typesupport_introspection_cpp.so /opt/ros/jazzy/lib/librosidl_typesupport_introspection_c.so /opt/ros/jazzy/lib/libbuiltin_interfaces__rosidl_typesupport_cpp.so /opt/ros/jazzy/lib/librosidl_typesupport_cpp.so /opt/ros/jazzy/lib/libbuiltin_interfaces__rosidl_generator_py.so /opt/ros/jazzy/lib/libservice_msgs__rosidl_typesupport_c.so /opt/ros/jazzy/lib/libbuiltin_interfaces__rosidl_typesupport_c.so /opt/ros/jazzy/lib/libservice_msgs__rosidl_generator_c.so /opt/ros/jazzy/lib/libbuiltin_interfaces__rosidl_generator_c.so /opt/ros/jazzy/lib/libunique_identifier_msgs__rosidl_typesupport_c.so /opt/ros/jazzy/lib/libunique_identifier_msgs__rosidl_generator_c.so /opt/ros/jazzy/lib/librosidl_typesupport_c.so /opt/ros/jazzy/lib/librcpputils.so /opt/ros/jazzy/lib/librosidl_runtime_c.so /opt/ros/jazzy/lib/librcutils.so -ldl -Wl,-rpath-link,/opt/ros/jazzy/lib

代码层面

上层代码

在上层代码层面,隐式加载动态库的方式和手动加载动态库的方式基本没有区别。仅有的区别是:手工加载动态库需要在创建class_loader::ClassLoader时传入动态库的地址;而隐式加载动态库只需要传入一个空字符串。

  std::vector<std::string> libraries = {
    // all classes from libraries linked by the linker (rather then dlopen)
    // are registered under the library_path ""
    "",
  };
  for (auto library : libraries) {
    RCLCPP_INFO(logger, "Load library %s", library.c_str());
    auto loader = std::make_unique<class_loader::ClassLoader>(library);

完整代码(composition/src/linktime_composition.cpp)如下。

// Copyright 2016 Open Source Robotics Foundation, Inc.
//
// 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 <memory>
#include <string>
#include <vector>
#include <utility>

#include "class_loader/class_loader.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/node_factory.hpp"


#define LINKTIME_COMPOSITION_LOGGER_NAME "linktime_composition"

int main(int argc, char * argv[])
{
  // Force flush of the stdout buffer.
  setvbuf(stdout, NULL, _IONBF, BUFSIZ);

  rclcpp::init(argc, argv);
  rclcpp::Logger logger = rclcpp::get_logger(LINKTIME_COMPOSITION_LOGGER_NAME);
  rclcpp::executors::SingleThreadedExecutor exec;
  rclcpp::NodeOptions options;
  std::vector<std::unique_ptr<class_loader::ClassLoader>> loaders;
  std::vector<rclcpp_components::NodeInstanceWrapper> node_wrappers;

  std::vector<std::string> libraries = {
    // all classes from libraries linked by the linker (rather then dlopen)
    // are registered under the library_path ""
    "",
  };
  for (auto library : libraries) {
    RCLCPP_INFO(logger, "Load library %s", library.c_str());
    auto loader = std::make_unique<class_loader::ClassLoader>(library);
    auto classes = loader->getAvailableClasses<rclcpp_components::NodeFactory>();
    for (auto clazz : classes) {
      RCLCPP_INFO(logger, "Instantiate class %s", clazz.c_str());
      auto node_factory = loader->createInstance<rclcpp_components::NodeFactory>(clazz);
      auto wrapper = node_factory->create_node_instance(options);
      auto node = wrapper.get_node_base_interface();
      node_wrappers.push_back(wrapper);
      exec.add_node(node);
    }
    loaders.push_back(std::move(loader));
  }

  exec.spin();

  for (auto wrapper : node_wrappers) {
    exec.remove_node(wrapper.get_node_base_interface());
  }
  node_wrappers.clear();

  rclcpp::shutdown();

  return 0;
}

底层代码

我们通过对编译链接的分析,已经了解了talker_component、listener_component、server_component和client_component这些动态库会自动加载到进程中。这样它们通过RCLCPP_COMPONENTS_REGISTER_NODE声明的静态变量也会自动初始化,从而让各个Node的工厂类对象被注册到一个静态Map结构中。

现在我们唯一需要解释的问题,就是:为什么可以从空字符串(“”)地址获取到所有Node工厂类的名称。

我们从下面代码开始着手分析

    auto loader = std::make_unique<class_loader::ClassLoader>(library);

class_loader::ClassLoader的构造函数如下。它的底层会调用class_loader::impl::loadLibrary。

ClassLoader::ClassLoader(const std::string & library_path, bool ondemand_load_unload)
: ondemand_load_unload_(ondemand_load_unload),
  library_path_(library_path),
  load_ref_count_(0),
  plugin_ref_count_(0)
{
  CONSOLE_BRIDGE_logDebug(
    "class_loader.ClassLoader: "
    "Constructing new ClassLoader (%p) bound to library %s.",
    this, library_path.c_str());
  if (!isOnDemandLoadUnloadEnabled()) {
    loadLibrary();
  }
}

void ClassLoader::loadLibrary()
{
  boost::recursive_mutex::scoped_lock lock(load_ref_count_mutex_);
  load_ref_count_ = load_ref_count_ + 1;
  class_loader::impl::loadLibrary(getLibraryPath(), this);
}

loadLibrary的底层需要一个锁来保持同步。因为后续逻辑需要修改当前进程正在处理的loader(对应于动态库文件)以及正在处理的动态库路径,这两个变量牵扯到自动注册到进程中的Node工厂对象的从属关系:它从属于哪个loader。

void loadLibrary(const std::string & library_path, ClassLoader * loader)
{
  static boost::recursive_mutex loader_mutex;
  CONSOLE_BRIDGE_logDebug(
    "class_loader.impl: "
    "Attempting to load library %s on behalf of ClassLoader handle %p...\n",
    library_path.c_str(), reinterpret_cast<void *>(loader));
  boost::recursive_mutex::scoped_lock loader_lock(loader_mutex);

下面这段逻辑中,setCurrentlyActiveClassLoader就是用来设置当前正在处理的loader是哪个,以及路径是哪个。上述锁保护的就是这两个变量。

  // If it's already open, just update existing metaobjects to have an additional owner.
  if (isLibraryLoadedByAnybody(library_path)) {
    boost::recursive_mutex::scoped_lock lock(getPluginBaseToFactoryMapMapMutex());
    CONSOLE_BRIDGE_logDebug("%s",
      "class_loader.impl: "
      "Library already in memory, but binding existing MetaObjects to loader if necesesary.\n");
    addClassLoaderOwnerForAllExistingMetaObjectsForLibrary(library_path, loader);
    return;
  }

  Poco::SharedLibrary * library_handle = nullptr;

  {
    try {
      setCurrentlyActiveClassLoader(loader);
      setCurrentlyLoadingLibraryName(library_path);
      library_handle = new Poco::SharedLibrary(library_path);
    } catch (const Poco::LibraryLoadException & e) {
      setCurrentlyLoadingLibraryName("");
      setCurrentlyActiveClassLoader(nullptr);
      throw class_loader::LibraryLoadException(
              "Could not load library (Poco exception = " + std::string(e.message()) + ")");
    } catch (const Poco::LibraryAlreadyLoadedException & e) {
      setCurrentlyLoadingLibraryName("");
      setCurrentlyActiveClassLoader(nullptr);
      throw class_loader::LibraryLoadException(
              "Library already loaded (Poco exception = " + std::string(e.message()) + ")");
    } catch (const Poco::NotFoundException & e) {
      setCurrentlyLoadingLibraryName("");
      setCurrentlyActiveClassLoader(nullptr);
      throw class_loader::LibraryLoadException(
              "Library not found (Poco exception = " + std::string(e.message()) + ")");
    }

    setCurrentlyLoadingLibraryName("");
    setCurrentlyActiveClassLoader(nullptr);
  }

我们可以看到,对于需要加载的动态库,会调用Poco::SharedLibrary(library_path);来加载。它的底层就是调用dlopen。

// github/pocoproject/poco-poco-1.3.6/Foundation/src/SharedLibrary.cpp
SharedLibrary::SharedLibrary(const std::string& path)
{
	loadImpl(path);
}
// /github/pocoproject/poco-poco-1.3.6/Foundation/src/SharedLibrary_UNIX.cpp
void SharedLibraryImpl::loadImpl(const std::string& path)
{
	FastMutex::ScopedLock lock(_mutex);

	if (_handle) throw LibraryAlreadyLoadedException(path);
	_handle = dlopen(path.c_str(), RTLD_LAZY | RTLD_GLOBAL);
	if (!_handle)
	{
		const char* err = dlerror();
		throw LibraryLoadException(err ? std::string(err) : path);
	}
	_path = path;
}

dlopen会加载动态库,从而让动态库中的静态变量自动初始化,进而触发class_loader::impl::registerPlugin注册Node的工厂类对象。

#define CLASS_LOADER_REGISTER_CLASS_INTERNAL_WITH_MESSAGE(Derived, Base, UniqueID, Message) \
  namespace \
  { \
  struct ProxyExec ## UniqueID \
  { \
    typedef  Derived _derived; \
    typedef  Base _base; \
    ProxyExec ## UniqueID() \
    { \
      if (!std::string(Message).empty()) { \
        CONSOLE_BRIDGE_logInform("%s", Message);} \
      class_loader::impl::registerPlugin<_derived, _base>(#Derived, #Base); \
    } \
  }; \
  static ProxyExec ## UniqueID g_register_plugin_ ## UniqueID; \
  }  // namespace

在registerPlugin方法中有如下几行代码。它们会将新创建的Node工厂对象和当前动态库的loader以及路径绑定。需要注意的是,这个过程也是在上述锁的保护中,从而导致Node工厂类和loader等的映射是正确的。

  // Create factory
  impl::AbstractMetaObject<Base> * new_factory =
    new impl::MetaObject<Derived, Base>(class_name, base_class_name);
  new_factory->addOwningClassLoader(getCurrentlyActiveClassLoader());
  new_factory->setAssociatedLibraryPath(getCurrentlyLoadingLibraryName());

等到库加载完,它的静态变量初始化结束,loadLibrary会将当前loader变成nullptr,当前路径变成空字符串。

    setCurrentlyLoadingLibraryName("");
    setCurrentlyActiveClassLoader(nullptr);

回到我们通过隐式加载的动态库。它们不是通过上述流程加载到进程中的,所以它们的CurrentlyLoadingLibraryName是空字符串(“”);它们的CurrentlyActiveClassLoader是nullptr。
这样这些动态库的Node工厂类对象的OwningClassLoader是nullptr,AssociatedLibraryPath是空字符串(“”)。

所以下面代码中的loader并不是这些Node工厂类对象的OwningClassLoader。那么它为什么可以通过getAvailableClasses获取这些隐式加载注册的Node工厂类名呢?

  std::vector<std::string> libraries = {
    // all classes from libraries linked by the linker (rather then dlopen)
    // are registered under the library_path ""
    "",
  };
  for (auto library : libraries) {
    RCLCPP_INFO(logger, "Load library %s", library.c_str());
    auto loader = std::make_unique<class_loader::ClassLoader>(library);
    auto classes = loader->getAvailableClasses<rclcpp_components::NodeFactory>();

我们要分析getAvailableClasses的实现。

  /**
   * @brief  Indicates which classes (i.e. class_loader) that can be loaded by this object
   * @return vector of strings indicating names of instantiable classes derived from <Base>
   */
  template<class Base>
  std::vector<std::string> getAvailableClasses()
  {
    return class_loader::impl::getAvailableClasses<Base>(this);
  }

getAvailableClasses底层调用的class_loader::impl::getAvailableClasses方法会将Owner为nullptr的Node工厂类对象也返回出去。所以隐式加载动态库注册进来的类名就都找到了。

/**
 * @brief This function returns all the available class_loader in the plugin system that are derived from Base and within scope of the passed ClassLoader.
 * @param loader - The pointer to the ClassLoader whose scope we are within,
 * @return A vector of strings where each string is a plugin we can create
 */
template<typename Base>
std::vector<std::string> getAvailableClasses(ClassLoader * loader)
{
  boost::recursive_mutex::scoped_lock lock(getPluginBaseToFactoryMapMapMutex());

  FactoryMap & factory_map = getFactoryMapForBaseClass<Base>();
  std::vector<std::string> classes;
  std::vector<std::string> classes_with_no_owner;

  for (auto & it : factory_map) {
    AbstractMetaObjectBase * factory = it.second;
    if (factory->isOwnedBy(loader)) {
      classes.push_back(it.first);
    } else if (factory->isOwnedBy(nullptr)) {
      classes_with_no_owner.push_back(it.first);
    }
  }

  // Added classes not associated with a class loader (Which can happen through
  // an unexpected dlopen() to the library)
  classes.insert(classes.end(), classes_with_no_owner.begin(), classes_with_no_owner.end());
  return classes;
}

如果我们就理解了为什么我们可以通过空字符串(“”)找到所有隐式加载进来的Node工厂注册类了。

总结

  • 隐式加载的动态库的Node工厂类的OwnerLoader是nullptr;
  • getAvailableClasses会将所有OwnerLoader是nullptr的类名返回;
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

breaksoftware

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值