ros-control


概述

ROS(Robot Operating System)是一个用于机器人开发的开源框架,其提供了一些常用的机器人开发工具、库和约定,可以快速实现机器人的搭建。而ROS Control作为ROS的一大核心软件包,是学习ROS的一大难点,其中的一些细节和核心问题很容易被忽略。本文就想通过分享我在学习中的一些理解,希望对各位看客有所帮助.


一、ROS Control

学过控制理论的伙伴应该都知道控制的核心:稳、准、快,任何一个性能优异的机器人对象都离不开控制系统。常见的机器人控制系统组成如下图所示:
控制系统组成

可以看到,控制系统充当一个中间角色,通过接受上层用户的输入指令(target)和状态反馈指令(state),再经过控制算法计算出控制指令后下发给电机驱动系统,由驱动器进行放大后输出驱动电压使电机带动执行机构工作.

在了解了什么是控制之后我们就进入本节的主题:什么是ROS Control ?

正如前面所说,ROS Control 是ROS的一组软件包,其包括controller interface、controller manager、transmissions、hardware_interface 和 control toolbox 。对于transmissions 和 control toolbox,本文不做过多介绍,可参考其他文章>click transmissions<>click control toolbox<。我们先看一下ROS Control中的数据流向,如下图所示(核心图):
gazebo_ros_control

图链接:https://github.com/ros-controls/ros_control/blob/melodic-devel/ros_control/documentation/gazebo_ros_control.pdf

首先是控制器的输入,一个是来自于机器人的状态反馈量,另一个来自ROS上层的输入,该输入可以通过ROS Topic话题订阅,或者是通过ROS Server或ROS Action获取;控制器则负责利用输入数据计算出关节的控制命令,可以是PID控制器,当然也可以进行自定义,后续会加以说明;最后通过hardware_interface就能实现对机器人的控制.

所以当我们使用标准的接口进行控制时,工作就变得简单起来。从图中不难看出,Controller计算出来的控制指令将通过hardware_interface接口与RobotHW进行交互,而我们则通过重写hardware_interface中的read()函数和write()函数就可以实现对大部分类型的机器人进行控制。其中hardware_interface::RobotHW::write()可以通过controller进行设置command,且通过通讯协议将cmd值下发到硬件控制器上;而hardware_interface::RobotHW::read()则可以获取机器人的资源(关节状态,传感器反馈,电机状态),通过解析传感器返回的数据.

看上去似乎是很简单,其实确实不是很难。当然,这一定程度取决于你想要达到的控制效果(核心工作就是控制器的编写和hardware_interface的重实现)。另外,我们常做的ROS和Gazebo联合仿真,其实就是在干这么一件事:配置机器人的Gazebo参数 (transmissions和hardwareInterface),配置控制器的参数(type),编写启动节点,完事(^_^)。但其中很多重要的步骤都是ROS和Gazebo插件帮我们实现了.

另外简单介绍一些ROS提供的标准控制器接口(controller interface):

  1. JointCommandInterface: 该Hardware Interface包含常用的三种关节控制器接口, EffortJointInterfacePositionJointInterface VelocityJointInterface.
    EffortJointInterface: 该接口提供了5类标准的控制器(output effort command).
    JointEffortController:P增益输出.(input effort command)
    JointPositionController:PID loop计算输出.(input position command)
    JointVelocityController:PID loop计算输出(input velocity command)
    PositionJointInterface: 该接口提供了2类控制器(output position command).
    JointPositionController:(input position command)
    JointGroupPositionController:(input a set of position command)
    VelocityJointInterface: 该接口提供了3类控制器(output velocity command)
    JointPositionController:PID loop计算(input position command)
    JointVelocityController:P增益增益(input velocity command)
    JointGroupVelocityControlle:(same as JointVelocityController)

  2. JointStateInterface: 提供了一个状态控制器
    JointStateController:发布/joint_states话题

详细见连接: https://github.com/ros-controls/ros_controllers/tree/melodic-devel/effort_controllers/include/effort_controllers
http://wiki.ros.org/ros_control#Controllers

注意:无论控制器接收还是发布话题,均需要注意控制器所在的命名空间,控制器接收的指令cmd通常以 /namespace/controller-name/command的话题进行接收

上面差不多介绍了ROS Control 的一个大概工作流程以及其提供的标准接口,下面就探讨一下hardware_interface和controller_interface,到底需要完善那些工作才能实现对自己的机器人控制。先看一张图:

机器人接口与控制器
从上图可以看出,想要控制器真实的机器人,就得完善机器人的硬件接口,即图中的RobotHW;同时我们还可以知道自定义的接口不仅可以使用标准的控制器接口,用户也可以实现自定义的控制器接口,从而满足自己预期的控制效果.

以一个两关节的机器人为例进行说明,并假设两个关节一个采用力矩控制器,一个选择位置控制器.

编写 <MyRobot_hardware_interface.h>

#include <hardware_interface/joint_command_interface.h>
#include <hardware_interface/joint_state_interface.h>
#include <hardware_interface/robot_hw.h>
class MyRobot : public hardware_interface::RobotHW
{
public:
MyRobot() { 
	// 可以在构造函数或是init()函数里面初始化机器人资源和接口注册
	// 比如从URDF文件中解析出关节名称和接口 
}
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) {
    // 创建关节状态句柄JointStateHandle(只读)
    hardware_interface::JointStateHandle state_handle_a("jointA", &pos[0], &vel[0], &eff[0]);
    // 将关节状态句柄连接到关节状态接口
    jnt_state_interface.registerHandle(state_handle_a);
    
    hardware_interface::JointStateHandle state_handle_b("jointB", &pos[1], &vel[1], &eff[1]);
    jnt_state_interface.registerHandle(state_handle_b);
	// 将JointStateInterface注册到hardware_interface::RobotHW
    registerInterface(&jnt_state_interface);
   
    // 创建关节句柄JointHandle(可读可写,保留写权限使得其可以与hardware_interface进行交互),与上面类似
    hardware_interface::JointHandle pos_handle_a(jnt_state_interface.getHandle("jointA"), &cmd[0]);
    jnt_pos_interface.registerHandle(pos_handle_a);
    hardware_interface::JointHandle pos_handle_b(jnt_state_interface.getHandle("jointB"), &cmd[1]);
    jnt_eff_interface.registerHandle(pos_handle_b);
    // 向hardware_interface::RobotHW注册包含读/写的关节的JointPositionInterface
    registerInterface(&jnt_pos_interface);
    registerInterface(&jnt_eff_interface);
    return true;
}
void read(const ros::Time &time, const ros::Duration &period){}
void write(const ros::Time &time, const ros::Duration &period){}
  
private:
  // JointStateInterface提供:在不与其他控制器冲突的情况下可以读取关节值
  hardware_interface::JointStateInterface jnt_state_interface;
  // PositionJointInterface继承自JointCommandInterface,且用来读取和设置关节位置
  // 若只是读取关节位置,使用JointStateInterface进行读取避免冲突
  hardware_interface::PositionJointInterface jnt_pos_interface;
  hardware_interface::EffortJointInterface jnt_eff_interface;
 
  // cmd[] 用来存储控制器指令(用户发送的command),通过hardware_interface::
  // RobotHW::write() 方法写入机器人硬件资源
  double cmd[2];
  // pos[]、vel[]、eff[]用于存储sensor data
  double pos[2];
  double vel[2];
  double eff[2];
};

上述头文件定义的核心是:

registerInterface(&jnt_state_interface);

该函数使得控制器管理器(Controller Manager)和管理器中的控制器可以访问自定义的机器人状态并能对其发送命令;当控制器管理器运行时,控制器就可以从自定义机器人的硬件接口的pos[]、vel[]、和eff[]中读取数据,且控制器也可以将command指令写入cmd[]变量;从而RobotHW就可以通过read()和write()函数与用户机器人交互.

可能有的peer还是不清楚这个hardware_interface到底在干了个什么事,那再看一张图可能就明白了.

hardware__interface这下应该很清楚了,hardware_interface就相当于一个桥梁,连接Controller和RobotHW,即开头所示的核心图一般。所以现在我们就应该知道在hardware_interface中到底要干什么,除了重写read()和write()函数之外,还有一个重要工作就是将控制器资源与机器人资源进行连接(部分共享)。这样我们就可以通过ROS上层提供的接口去控制机器人。

给出一个简单的实现 <MyRobot_hardware_interface.cpp>

#include <ros/ros.h>
#include <MyRobot_hardware_interface.h>
#include <controller_manager/controller_manager.h>

void MyRobot::read(const ros::Time &time, const ros::Duration &period){}
void MyRobot::write(const ros::Time &time, const ros::Duration &period){}

int main(int argc, char **argv)
{
    // 初始化ROS节点
    ros::init(argc, argv, "my_robot");
    
    // 创建机器人实例,以便可以获取可用资源
    MyRobot::MyRobot robot;
    // 创建一个控制器管理器实例,并将机器人对象指针作为参数传入,以便其可以处理机器人资源
    controller_manager::ControllerManager cm(&robot);
    
    // 设置一个线程用于接收ROS服务
    ros:AsyncSpinner spinner(1);
    spinner.start();
    
    // 设置控制循环
    ros::Time prev_time = ros::Time::now();
    ros::Rate rate(10.0); // 10 Hz rate
    
    while (ros::ok())
    {
        // 计算控制周期
        const ros::Time     time   = ros:Time::now();
        const ros::Duration period = time - prev_time;
        prev_time = time;
        
        // 执行实际控制循环
        robot.read(time, period);
        cm.update(time, period);
        root.write(time,period);
        
        // 以上按照指定频率不断重复
        rate.sleep();
    }
    return 0;
}

这里的read()和write()函数并没有具体实现,需结合实际机器人硬件编写,通常可以进行以下封装:

void MyRobot::read(const ros::Time &time, const ros::Duration &period)
{
	/* TUDO 
	实现与机器人的通讯(I2C/CAN/ros_serial/ros_industrial),将机器人的状态值存储到pos[]、vel[]、eff[]
	*/
}
void MyRobot::write(const ros::Time &time, const ros::Duration &period)
{
	/* TUDO 
	对输出值进行安全限制;
	将cmd通过协议(I2C/CAN/ros_serial/ros_industrial)写入机器人
	*/
}

这样就简单地实现了hardware_interface接口,你可以根据上述代码编写你自己的机器人接口,也可以通过>here<进行检查.

至此,我们已经了解了controller interface、controller manager 和 hardware_interface,并实现了hardware_interface的编写,接下来再完善一些配置文件就可以控制机器人运动.

首先是controllers.yaml文件:(配置真实机器人的控制器参数)

MyRobot:					# 控制器命名空间,注意其他文件中的对应关系,否则可能会无法加载控制器
    # Publish all joint states
    joint_state_controller:														# 控制器名称
      type: joint_state_controller/JointStateController
      publish_rate: 50																# 发布话题频率
    
    JointB_EffortController:                                               			# 控制器名称
      type: effort_controllers/JointPositionController         # 配置要与hardface_interface中进行对应,因为是
      joint: JointB                                                                # 关节名称
      pid: {p: 100.0, i: 10.0, d: 1.0}                                    # PID values
    
    JointA_PositionController:
      type: position_controllers/JointPositionController    # 根据需要的控制器类型进行配置
      joint: JointA
      # 因为输入输出都是位置量,所以没定义PID参数

此外,如果你的机器人关节限制的话,还需要添加一个joint_limts.yaml文件用来约束机器人,文章出于简单并没有考虑关节限制,但这是必要的,这对你在控制机器人时的求解上就可以体现.

现在我们就可以编写启动文件来加载这些参数和节点,如MyRobot_control.launch

<launch>
    <!-- launch a empty world -->
    <arg name="paused" default="false"/>
    <arg name="use_sim_time" default="true"/>
    <arg name="gui" default="true"/>
    <arg name="headless" default="false"/>
    <arg name="debug" default="false"/>

    <include file="$(find gazebo_ros)/launch/empty_world.launch">
        <arg name="debug" value="$(arg debug)" />
        <arg name="gui" value="$(arg gui)" />
        <arg name="paused" value="$(arg paused)"/>
        <arg name="use_sim_time" value="$(arg use_sim_time)"/>
        <arg name="headless" value="$(arg headless)"/>
    </include>
    
    <!-- Load the URDF into the ROS Parameter Server -->
    <param name="robot_description" textfile="$(find Your_Robot_description_Pkg)/urdf/Your_Robot.urdf"/>
    <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
        args="-urdf -model Your_Robot -param robot_description  -x 0 -y 0 -z 2.0 -R 0 -P 0 -Y 0"/>

	<!-- Load joint controller configurations from YAML file to parameter server -->
	<rosparam file="$(find YOUR_PACKAGE_NAME)/config/controllers.yaml" command="load"/>

	<!-- 启动hardware_interface节点 --->
	<node name="MyRobotHardwareInterface" pkg="YOUR_PACKAGE_NAME" type="MyRobot_hardware_inerface_node" output="screen"/>

    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"
          respawn="false" output="screen">
          <remap from="/joint_states" to="/Your_Robot_Namespace/joint_states"/>
    </node>
    <!-- 将话题重映射到控制器命名空间下 -->
    
 	 <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen"
        args="
            /MyRobot/joint_state_controller
            /MyRobot/JointA_PositionController
            /MyRobot/JointB_EffortController" /> 
	<!-- 注意这里带上了命名空间的,一个保险的方法就是将机器人的资源都放在同一个命名空间下 -->
	
</launch>

上面代码比较容易理解,但对于controller_manager,我再简单说明一下。在上面的启动文件中,controllers 通过一个spawner(python 脚本)加载到了controller_manager中。之前说过,控制器管理器是可以访问机器人资源的,所以当我们将控制器加载到管理器中后,该控制器就可以与机器人进行交互,也就是我们可以通过控制器这一接口对机器人进行控制.

此外,除了像上面这样通过节点进行启动外,还可以通过终端使用ROS Service进行手动管理(加载、启动、停止等),详细说明见连接>controller_manager<


二、总结

通过这篇文章,我们认识了ROS Control,并着重介绍了其中的controller_manager、hardware_interface和controller_interface。对于controller_interface,我们介绍了一些常用的控制器接口;其次是hardware_interface的功能,其作用是将RobotHW和Controller进行连接和绑定,使得我们可以通过ROS提供的上层接口对机器人进行控制(比如 topic 话题);最后我们还给出了如何去编写hardware_interface的示例,大家可以去自行尝试,可以在评论区进行交流。
给一个仿真的图示:(使用的是gazebo_ros_control插件)

在这里插入图片描述

至此,我的第一篇文章就完结了,希望能能对大家带来一些新的理解.


主要参考:
http://wiki.ros.org/
https://github.com/ros-controls

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值