ROS / Plugin

PluginDescriptionFile

Plugin Description File Reference

This page describes the XML format used for plugin description files used by the pluginlib package.

<class_libraries> tag

The class_libraries tag allows listing multiple libraries which, in turn, contain plugins within one plugin description file.

tag

The library tag defines the library in which plugin classes live. A library may contain multiple plugins of varying class types.

Attributes:

  • path : The relative path to the library from the main package directory

tag

The class tag describes a class provided by a library.

Attributes:

  • name : The lookup name of the class. Used by the pluginlib tools as an identifier for the plugin. This field is optional in pluginlib 1.9 and higher (ROS Groovy or higher)

  • type : The fully qualified class type.

  • base_class_type : The fully qualified type of the base class

  • description : A description of the class and what it does.

Examples

A simple plugin description file for a library with one class to export

<library path="lib/libplugin">
  <class name="MyPlugin" type="my_namespace::MyPlugin" base_class_type="interface_namespace::PluginInterface">
    <description>
      A description of MyPlugin
    </description>
  </class>
</library>

A plugin description file for a library with multiple plugins

<library path="lib/libplugin">
  <class name="FirstPlugin" type="my_namespace::FirstPlugin" base_class_type="interface_namespace::PluginInterface">
    <description>
      A description of FirstPlugin
    </description>
  </class>
  <class name="SecondPlugin" type="my_namespace::SecondPlugin" base_class_type="interface_namespace::PluginInterface">
    <description>
      A description of SecondPlugin
    </description>
  </class>
</library>

A plugin description for multiple libraries with plugins

<class_libraries>
  <library path="lib/libplugina">
    <class name="MyPluginA" type="my_namespacea::MyPluginA" base_class_type="interface_namespace::PluginInterface">
      <description>
        A description of MyPluginA
      </description>
    </class>
  </library>
  <library path="lib/libpluginb">
    <class name="MyPluginB" type="my_namespaceb::MyPluginB" base_class_type="interface_namespace::PluginInterface">
      <description>
        A description of MyPluginB
      </description>
    </class>
  </library>
</class_libraries>
#include <ar_hardware_interface/ar_servo_gripper_hw_interface.hpp>
#include <sstream>

namespace ar_hardware_interface {

hardware_interface::CallbackReturn ARServoGripperHWInterface::on_init(
    const hardware_interface::HardwareInfo& info) {
  RCLCPP_INFO(logger_, "Initializing hardware interface...");

  if (hardware_interface::SystemInterface::on_init(info) !=
      hardware_interface::CallbackReturn::SUCCESS) {
    return hardware_interface::CallbackReturn::ERROR;
  }

  info_ = info;

  std::string serial_port = info_.hardware_parameters.at("serial_port");
  int baud_rate = 9600;
  bool success = driver_.init(serial_port, baud_rate);
  if (!success) {
    return hardware_interface::CallbackReturn::ERROR;
  }

  return hardware_interface::CallbackReturn::SUCCESS;
}

hardware_interface::CallbackReturn ARServoGripperHWInterface::on_activate(
    const rclcpp_lifecycle::State& /*previous_state*/) {
  RCLCPP_INFO(logger_, "Activating hardware interface...");

  // initialize gripper position
  int pos_deg;
  bool success = driver_.getPosition(pos_deg);
  if (!success) {
    return hardware_interface::CallbackReturn::ERROR;
  }
  position_ = angular_to_linear_pos(pos_deg);
  return hardware_interface::CallbackReturn::SUCCESS;
}

hardware_interface::CallbackReturn ARServoGripperHWInterface::on_deactivate(
    const rclcpp_lifecycle::State& /*previous_state*/) {
  RCLCPP_INFO(logger_, "Deactivating hardware interface...");
  return hardware_interface::CallbackReturn::SUCCESS;
}

std::vector<hardware_interface::StateInterface>
ARServoGripperHWInterface::export_state_interfaces() {
  std::vector<hardware_interface::StateInterface> state_interfaces;

  RCLCPP_INFO(logger_, "Debug: Exporting state interfaces for joint %s",
              info_.joints[0].name.c_str());
  for (size_t i = 0; i < info_.joints.size(); ++i) {
    state_interfaces.emplace_back(info_.joints[i].name, "position", &position_);
    state_interfaces.emplace_back(info_.joints[i].name, "velocity", &velocity_);
  }
  return state_interfaces;
}

std::vector<hardware_interface::CommandInterface>
ARServoGripperHWInterface::export_command_interfaces() {
  std::vector<hardware_interface::CommandInterface> command_interfaces;
  for (size_t i = 0; i < info_.joints.size(); ++i) {
    command_interfaces.emplace_back(info_.joints[i].name, "position",
                                    &position_command_);
  }
  return command_interfaces;
}

hardware_interface::return_type ARServoGripperHWInterface::read(
    const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) {
  int pos_deg;
  bool success = driver_.getPosition(pos_deg);
  if (!success) {
    return hardware_interface::return_type::ERROR;
  }
  position_ = angular_to_linear_pos(pos_deg);
  std::string logInfo = "Gripper Pos: " + std::to_string(position_);
  RCLCPP_DEBUG_THROTTLE(logger_, clock_, 500, logInfo.c_str());
  return hardware_interface::return_type::OK;
}

hardware_interface::return_type ARServoGripperHWInterface::write(
    const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) {
  int pos_deg = linear_to_angular_pos(position_command_);
  std::string logInfo = "Gripper Cmd: " + std::to_string(position_command_);
  RCLCPP_DEBUG_THROTTLE(logger_, clock_, 500, logInfo.c_str());
  bool success = driver_.writePosition(pos_deg);
  if (!success) {
    return hardware_interface::return_type::ERROR;
  }
  return hardware_interface::return_type::OK;
}

}  // namespace ar_hardware_interface

#include "pluginlib/class_list_macros.hpp"

PLUGINLIB_EXPORT_CLASS(ar_hardware_interface::ARServoGripperHWInterface,
                       hardware_interface::SystemInterface)

  • 18
    点赞
  • 17
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值