<ROS> Gazebo Ros Control 及 Controller运用

本文详细介绍了如何在Gazebo中使用ROS Control进行机器人控制,包括Default Robot HW SIM、Gazebo ROS Control Plugin的使用,以及position_controllers/JointPositionController、JointGroupPositionController和joint_state_controller的配置和应用,旨在帮助读者理解ROS在仿真环境中的控制器操作。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

1. 写在前面

第一篇 – 机器人描述: http://blog.csdn.net/sunbibei/article/details/52297524
第二篇 – TRANSMISSION: http://blog.csdn.net/sunbibei/article/details/53287975

在我上一篇博客上, 我们引入了UR5BH机器人, 另外, 对其描述文件中的transmission进行了解析, 其中摘录了如下文件:

<gazebo>
  <plugin filename="libgazebo_ros_control.so" name="ros_control">
    <!--robotNamespace>/</robotNamespace-->
    <!--robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType-->
  </plugin>
</gazebo>
... ...
<transmission name="shoulder_pan_trans">
  <type>transmission_interface/SimpleTransmission</type>
  <joint name="shoulder_pan_joint">
    <hardwareInterface>PositionJointInterface</hardwareInterface>
  </joint>
  <actuator name="shoulder_pan_motor">
    <mechanicalReduction>1</mechanicalReduction>
  </actuator>
</transmission>
... ...
<transmission name="bh_j32_transmission">
  <type>transmission_interface/SimpleTransmission</type>
  <joint name="bh_j32_joint"/>
  <actuator name="bh_j32">
    <hardwareInterface>PositionJointInterface</hardwareInterface>
    <mechanicalReduction>1</mechanicalReduction>
    <motorTorqueConstant>1</motorTorqueConstant>
  </actuator>
</transmission>

在这段描述中, 除了transmission之外, 另一个引入的, 就是gazebo_ros_control. 本篇作为第三篇, 主要和大家分享一些关于gazebo_ros_control相关的内容。

2. Gazebo ROS Control

在前一篇的基础上, 实际上我们已经能够开始配置MoveIt!来进行机器人控制了。 但是, 为了更进一步的让事情更加清晰, 我们还是耐下心再探讨一下gazebo_ros_control。 包布局如下图所示:


这里写图片描述

打开package.xml文件, 除了一些依赖包的定义外, 一个比较关键的地方是在export块中, 摘录如下:

... ...
<export>
    <gazebo_ros_control plugin="${prefix}/robot_hw_sim_plugins.xml"/>
</export>
... ...

了解pluginlib的同学肯定知道, 这是将plugin的定义文件导入的步骤。 不熟悉的同学, 可以参考1, 或者 参考2 进行了解。

导入的文件在文件系统中可以看到, 摘录如下:

<library path="lib/libdefault_robot_hw_sim">
  <class
    name="gazebo_ros_control/DefaultRobotHWSim"
    type="gazebo_ros_control::DefaultRobotHWSim"
    base_class_type="gazebo_ros_control::RobotHWSim">
    <description>
      A default robot simulation interface which constructs joint handles from an SDF/URDF.
    </description>
  </class>
</library>

可以看到, 该文件中定义了一个plugin, 就是gazebo_ros_control::DefaultRobotHWSim, 该plugin可以动态的被加载进来。再查看该包的CMakeLists.txt, 可以看到下述内容:

## 2.1. Libraries
add_library(${PROJECT_NAME} src/gazebo_ros_control_plugin.cpp)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES})

add_library(default_robot_hw_sim src/default_robot_hw_sim.cpp)
target_link_libraries(default_robot_hw_sim ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES})

该包总共会生成两个库, 第一个库是gazebo_ros_control, 第二个库是default_robot_hw_sim, 分别都只有一个文件。 下面我们分别来分析这两个库的源码以及所对应完成的任务。

3. Default Robot HW SIM

default_robot_hw_sim.cpp中, 定义了类DefaultRobotHWSim, 该类继承于gazebo_ros_control::RobotHWSim, 父类定义摘录如下:

namespace gazebo_ros_control {

  // Struct for passing loaded joint data
  struct JointData 
  {
    std::string name_;
    std::string hardware_interface_;

    JointData(const std::string& name, const std::string& hardware_interface) :
      name_(name),
      hardware_interface_(hardware_interface)
    {}
  };

  class RobotHWSim : public hardware_interface::RobotHW 
  {
  public:
    virtual ~RobotHWSim() { }
    virtual bool initSim(
        const std::string& robot_namespace,
        ros::NodeHandle model_nh, 
        gazebo::physics::ModelPtr parent_model,
        const urdf::Model *const urdf_model, // 留意该指针有两个const
        // TransmissionInfo的内容在前一篇博客中有介绍
        std::vector<transmission_interface::TransmissionInfo> transmissions) = 0;
    virtual void readSim(ros::Time time, ros::Duration period) = 0;
    virtual void writeSim(ros::Time time, ros::Duration period) = 0;

    virtual void eStopActive(const bool active) {}
  };
}

该类定义了gazebo plugin版本的RobotHWRobotHW定义于ros control包中, 定义了与实际机器人通讯的基本接口, 在编写实际机器人的ros control体系时, 该类是用户必须实现的类。 主要重载read(), write(), preparewitch() 以及doSwitch()四个接口。 在RobotHW中, 这四个函数都有默认实现(默认实现是空, 什么都不做), 都不是纯虚函数。 一般而言, 重载读写函数即可正常工作了。 这个地方, 只是将接口换了个名字, 并且, 几个纯虚函数都必须在子类中进行实现。

DefaultRobotHWSim的定义摘录如下:

namespace gazebo_ros_control
{

class DefaultRobotHWSim : public gazebo_ros_control::RobotHWSim
{
public:

  // 四个纯需函数必须在子类中进行实现。
  <
<robot name="mycar" xmlns:xacro="http://www.ros.org/wiki/xacro"> <!-- 定义参数 --> <xacro:property name="base_radius" value="0.16"/> <xacro:property name="base_length" value="0.14"/> <xacro:property name="wheel_radius" value="0.0325"/> <xacro:property name="wheel_separation" value="0.2"/> <xacro:property name="base_mass" value="4"/> <xacro:property name="wheel_length" value="0.015"/> <xacro:property name="wheel_mass" value="0.04"/> <xacro:property name="front_wheel_radius" value="0.0075"/> <xacro:property name="front_wheel_mass" value="0.0075"/> <xacro:property name="back_wheel_mass" value="0.0075"/> <xacro:property name="radar_size" value="0.02"/> <xacro:property name="radar_mass" value="0.002"/> <!-- 惯性矩阵宏 --> <xacro:macro name="cylinder_inertia" params="mass radius length"> <inertia ixx="${mass*(3*radius*radius + length*length)/12}" ixy="0" ixz="0" iyy="${mass*(3*radius*radius + length*length)/12}" iyz="0" izz="${mass*radius*radius/2}"/> </xacro:macro> <xacro:macro name="sphere_inertia" params="mass radius"> <inertia ixx="${2*mass*radius*radius/5}" ixy="0" ixz="0" iyy="${2*mass*radius*radius/5}" iyz="0" izz="${2*mass*radius*radius/5}"/> </xacro:macro> <xacro:macro name="box_inertia" params="mass x y z"> <inertia ixx="${mass*(y*y + z*z)/12}" ixy="0" ixz="0" iyy="${mass*(x*x + z*z)/12}" iyz="0" izz="${mass*(x*x + y*y)/12}"/> </xacro:macro> <!-- 基础链接 --> <link name="base_footprint"> <visual> <geometry> <sphere radius="0.001"/> </geometry> </visual> </link> <link name="base_link"> <visual> <geometry> <cylinder radius="${base_radius}" length="${base_length}"/> </geometry> <material name="yellow"> <color rgba="0.8 0.8 0 0.5"/> </material> </visual> <collision> <geometry> <cylinder radius="${base_radius}" length="${base_length}"/> </geometry> </collision> <inertial> <mass value="${base_mass}"/> <xacro:cylinder_inertia mass="${base_mass}" radius="${base_radius}" length="${base_length}"/> </inertial> </link> <joint name="link2footprint" type="fixed"> <parent link="base_footprint"/> <child link="base_link"/> <origin xyz="0 0 0.085" rpy="0 0 0"/> </joint> <!-- 驱动轮 --> <xacro:macro name="wheel" params="prefix x y"> <link name="${prefix}_wheel"> <visual> <geometry> <cylinder radius="${wheel_radius}" length="${wheel_length}"/> </geometry> <origin xyz="0 0 0" rpy="1.5708 0 0"/> <material name="black"/> </visual> <collision> <geometry> <cylinder radius="${wheel_radius}" length="${wheel_length}"/> </geometry> <origin xyz="0 0 0" rpy="1.5708 0 0"/> </collision> <inertial> <mass value="${wheel_mass}"/> <xacro:cylinder_inertia mass="${wheel_mass}" radius="${wheel_radius}" length="${wheel_length}"/> </inertial> </link> <joint name="${prefix}2link" type="continuous"> <parent link="base_link"/> <child link="${prefix}_wheel"/> <origin xyz="${x} ${y} -0.0525" rpy="0 0 0"/> <axis xyz="0 1 0"/> </joint> </xacro:macro> <xacro:wheel prefix="left" x="0" y="0.1"/> <xacro:wheel prefix="right" x="0" y="-0.1"/> <!-- 万向轮 --> <xacro:macro name="caster_wheel" params="prefix x y"> <link name="${prefix}_wheel"> <visual> <geometry> <sphere radius="${front_wheel_radius}"/> </geometry> <material name="gray"/> </visual> <collision> <geometry> <sphere radius="${front_wheel_radius}"/> </geometry> </collision> <inertial> <mass value="${front_wheel_mass}"/> <xacro:sphere_inertia mass="${front_wheel_mass}" radius="${front_wheel_radius}"/> </inertial> </link> <joint name="${prefix}2link" type="fixed"> <parent link="base_link"/> <child link="${prefix}_wheel"/> <origin xyz="${x} ${y} -0.0775" rpy="0 0 0"/> </joint> </xacro:macro> <xacro:caster_wheel prefix="front" x="0.1" y="0"/> <xacro:caster_wheel prefix="back" x="-0.1" y="0"/> <!-- 雷达 --> <link name="radar"> <visual> <geometry> <box size="${radar_size} ${radar_size} ${radar_size}"/> </geometry> <material name="white"/> </visual> <collision> <geometry> <box size="${radar_size} ${radar_size} ${radar_size}"/> </geometry> </collision> <inertial> <mass value="${radar_mass}"/> <xacro:box_inertia mass="${radar_mass}" x="${radar_size}" y="${radar_size}" z="${radar_size}"/> </inertial> </link> <joint name="radar2link" type="fixed"> <parent link="base_link"/> <child link="radar"/> <origin xyz="0 0 0.08" rpy="0 0 0"/> </joint> <!-- Gazebo扩展 --> <gazebo reference="base_link"> <material>Gazebo/Yellow</material> </gazebo> <gazebo reference="left_wheel"> <material>Gazebo/Black</material> </gazebo> <gazebo reference="right_wheel"> <material>Gazebo/Black</material> </gazebo> <!-- 雷达传感器 --> <gazebo reference="radar"> <sensor type="ray" name="rplidar"> <pose>0 0 0 0 0 0</pose> <visualize>true</visualize> <update_rate>5.5</update_rate> <ray> <scan> <horizontal> <samples>360</samples> <min_angle>-3.1416</min_angle> <max_angle>3.1416</max_angle> </horizontal> </scan> <range> <min>0.10</min> <max>30.0</max> <resolution>0.01</resolution> </range> </ray> <plugin name="lidar_controller" filename="libgazebo_ros_laser.so"> <topicName>/scan</topicName> <frameName>radar</frameName> </plugin> </sensor> </gazebo> <!-- 传动系统 --> <xacro:macro name="wheel_transmission" params="prefix"> <transmission name="${prefix}_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${prefix}2link"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> </joint> <actuator name="${prefix}_motor"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> </xacro:macro> <xacro:wheel_transmission prefix="left"/> <xacro:wheel_transmission prefix="right"/> <!-- ROS控制插件 --> <gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/</robotNamespace> <controlPeriod>0.001</controlPeriod> <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> </plugin> </gazebo> <!-- 直接定义PID参数 --> <gazebo> <plugin name="pid_controller" filename="libgazebo_ros_control.so"> <leftJoint>left2link</leftJoint> <rightJoint>right2link</rightJoint> <wheelSeparation>${wheel_separation}</wheelSeparation> <wheelDiameter>${wheel_radius*2}</wheelDiameter> <ros> <namespace>/gazebo_ros_control/pid_gains</namespace> </ros> <leftPid> <p>10.0</p> <i>0.1</i> <d>0.01</d> <iMax>1.0</iMax> <iMin>-1.0</iMin> </leftPid> <rightPid> <p>10.0</p> <i>0.1</i> <d>0.01</d> <iMax>1.0</iMax> <iMin>-1.0</iMin> </rightPid> </plugin> </gazebo> <!-- 差速控制器 --> <gazebo> <plugin name="diff_drive" filename="libgazebo_ros_diff_drive.so"> <commandTopic>cmd_vel</commandTopic> <odometryTopic>odom</odometryTopic> <odometryFrame>odom</odometryFrame> <robotBaseFrame>base_footprint</robotBaseFrame> <publishWheelTF>true</publishWheelTF> <wheelSeparation>${wheel_separation}</wheelSeparation> <wheelDiameter>${wheel_radius*2}</wheelDiameter> <leftJoint>left2link</leftJoint> <rightJoint>right2link</rightJoint> <wheelTorque>30</wheelTorque> <wheelAcceleration>1.8</wheelAcceleration> </plugin> </gazebo> </robot>
06-14
评论 9
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值