Writing a New Controller - modulabs/gazebo-tutorial GitHub Wiki

Introduction

ros_control์€ pr2๋ฅผ ์ œ์–ดํ•˜๊ธฐ ์œ„ํ•ด์„œ ๋งŒ๋“ค์—ˆ๋˜ framework๋ฅผ ๋‹ค๋ฅธ ๋กœ๋ด‡์—๋„ ์ ์šฉํ•  ์ˆ˜ ์žˆ๊ฒŒ ์ผ๋ฐ˜ํ™” ํ•ด ๋†“์€ meta package์ด๋‹ค. ๊ทธ๋ฆฌ๊ณ , ros_control์—์„œ ์“ธ ์ˆ˜ ์žˆ๊ฒŒ ros_controllers์— ๊ธฐ๋ณธ์ ์ธ controller plugin์ด ๋งˆ๋ จ๋˜์–ด ์žˆ๋‹ค. ros-controls/ros_controllers ๋งํฌ๋ฅผ ๋ณด๋ฉด ํ˜„์žฌ ์‚ฌ์šฉ ๊ฐ€๋Šฅํ•œ controller๋“ค์„ ๋ณผ ์ˆ˜ ์žˆ๋‹ค. ํ•˜๋‚˜๋งŒ ์˜ˆ๋ฅผ ๋“ค๋ฉด effort_controllers ํŒจํ‚ค์ง€๋Š” ๋กœ๋ด‡์—๊ฒŒ ํ† ํฌ ์ž…๋ ฅ์„ ์ฃผ๋Š” ์ œ์–ด๊ธฐ๋ฅผ ๊ตฌํ˜„ํ•œ ๊ฒƒ์œผ๋กœ์„œ ๋‹ค์Œ๊ณผ ๊ฐ™์€ ์ œ์–ด๊ธฐ๋“ค์ด ์žˆ๋‹ค.

  • joint_effort_controller: ๋‹จ์ถ• ํ† ํฌ ์ œ์–ด๊ธฐ
  • joint_group_effort_controller: ๋‹ค์ถ• ํ† ํฌ ์ œ์–ด๊ธฐ
  • joint_group_position_controller: ๋‹ค์ถ• ์œ„์น˜ ์ œ์–ด๊ธฐ
  • joint_position_controller: ๋‹จ์ถ• ์œ„์น˜ ์ œ์–ด๊ธฐ
  • joint_velocity controller: ๋‹จ์ถ• ์†๋„ ์ œ์–ด๊ธฐ

ํ•˜์ง€๋งŒ, ๊ผญ ์—ฌ๊ธฐ์„œ ์ œ๊ณตํ•˜๋Š” ์ œ์–ด๊ธฐ๋งŒ์„ ์‚ฌ์šฉํ•ด์•ผ ํ•˜๋Š” ๊ฒƒ์€ ์•„๋‹ˆ๋ฉฐ ๊ธฐ๋ณธ ์ œ์–ด๊ธฐ๋ฅผ ์ฐธ์กฐํ•ด์„œ ์‚ฌ์šฉ์ž๊ฐ€ ์ž…๋ง›์— ๋งž๊ฒŒ ์ž์‹ ๋งŒ์˜ ์ œ์–ด๊ธฐ๋ฅผ ์ถ”๊ฐ€ํ•  ์ˆ˜๋„ ์žˆ๋‹ค. ์ด๋ฒˆ ํŽ˜์ด์ง€์—์„œ๋Š” ๊ทธ ๋ฐฉ๋ฒ•์— ๋Œ€ํ•ด์„œ ์„ค๋ช…ํ•œ๋‹ค.

plugin

์ƒˆ๋กœ์šด ์ œ์–ด๊ธฐ๋Š” plugin ํ˜•ํƒœ๋กœ ์ž‘์„ฑํ•˜๋ฏ€๋กœ, ros pluginlib์— ๋Œ€ํ•œ ์ดํ•ด๊ฐ€ ์„ ํ–‰๋˜์–ด์•ผ ํ•œ๋‹ค. plugin์€ ์ž„์˜์˜ ROS package์—์„œ loading, unloadingํ•  ์ˆ˜ ์žˆ๋Š” C++ library๋ฅผ ์ผ์ปฌ์œผ๋ฉฐ, runtime์— ๋™์ ์œผ๋กœ ๋ถˆ๋Ÿฌ ์˜ฌ ์ˆ˜ ์žˆ๋„๋ก ๋™์  library ํ˜•ํƒœ๋กœ ์ž‘์„ฑ๋œ๋‹ค. ๊ทธ๋ƒฅ ๋™์  library๋ผ๋ฉด ๋ถ€๋ฅด๋Š” ์ชฝ์—์„œ ๋ช…์‹œ์ ์œผ๋กœ ํ•ด๋‹น ๋ผ์ด๋ธŒ๋Ÿฌ๋ฆฌ๋ฅผ link์‹œ์ผœ ์ค˜์•ผ ํ•˜์ง€๋งŒ, pluginlib๋ฅผ ์ด์šฉํ•˜๋ฉด ์‚ฌ์šฉ๋˜๋Š” library ์ธก์—์„œ ์ž์‹ ์„ export ์‹œ์ผœ์„œ ์ž„์˜์˜ ros package์—์„œ ํŽธํ•˜๊ฒŒ ๋ถˆ๋Ÿฌ ์“ธ ์ˆ˜ ์žˆ๋‹ค. ๊ทธ๋Ÿฌ๋ ค๋ฉด, pluginlib์—์„œ ์ œ์‹œํ•˜๋Š” ์ž‘์„ฑ๋ฒ•์„ ๋”ฐ๋ผ์•ผ ํ•˜๊ณ  ์ƒ์„ธํ•œ ๋ฐฉ๋ฒ•์€ ros pluginlib๋ฅผ ์ฐธ์กฐํ•œ๋‹ค.

Package ํŒŒ์ผ ์ž‘์„ฑ

๊ฐ€์žฅ ๋จผ์ € ํ•  ์ผ์€ ros package๋ฅผ ์ƒ์„ฑํ•˜๋Š” ๊ฒƒ์ด๋‹ค. my_controllers ํŒจํ‚ค์ง€๋ฅผ ๋งŒ๋“ค๊ณ  package.xml ํŒŒ์ผ์—์„œ controller_interface plugin์œผ๋กœ export ํ•ด ์ค€๋‹ค.

  <export>
    <controller_interface plugin="${prefix}/my_controllers_plugins.xml"/>
  </export>

๊ทธ๋ฆฌ๊ณ  ๋‚˜์„œ my_controllers_plugins.xml ํŒŒ์ผ์„ package.xml ํŒŒ์ผ๊ณผ ๊ฐ™์€ ๋””๋ ‰ํ† ๋ฆฌ์— ์ž‘์„ฑํ•ด ์ค€๋‹ค. ํ•˜๋‚˜์˜ controller package์—์„œ ๋ณต์ˆ˜ ๊ฐœ์˜ ์ œ์–ด๊ธฐ๋„ ์ž‘์„ฑํ•  ์ˆ˜ ์žˆ๋Š”๋ฐ 2๊ฐœ์˜ ์ œ์–ด๊ธฐ๋ฅผ ์ž‘์„ฑํ•œ๋‹ค๊ณ  ํ–ˆ์„ ๋•Œ ๋‹ค์Œ๊ณผ ๊ฐ™์ด ํ•˜๋ฉด ๋œ๋‹ค.

<library path="lib/libmy_controllers">

  <class name="my_controllers/NewController1" type="my_controllers::NewController1" base_class_type="controller_interface::ControllerBase">
    <description>
	My New Controller 1
    </description>
  </class>

  <class name="my_controllers/NewController2" type="my_controllers::NewController2" base_class_type="controller_interface::ControllerBase">
    <description>
	My New Controller 2
    </description>
  </class>
</library>

๋จผ์ € library path์—๋Š” ๋นŒ๋“œ๋  ๊ฒฝ๋กœ๋ฅผ ์ง€์ •ํ•˜๊ฒŒ ๋˜๋Š”๋ฐ ์œ„์™€ ๊ฐ™์ด ์ž‘์„ฑํ•˜๋ฉด ๋นŒ๋“œ ํ›„์— libmy_controllers.so ํŒŒ์ผ์ด ~/catkin_ws/devel/lib ํด๋”์— ์ƒ์„ฑ๋œ๋‹ค. ๋‹ค์Œ์œผ๋กœ ๊ฐ๊ฐ์˜ class ์ด๋ฆ„์„ namespace์™€ ๊ฐ™์ด ๊ธฐ์ˆ ํ•˜๊ณ , Base class๋กœ๋Š” controller_interface::ControllerBase ๋ฅผ ์ง€์ •ํ•ด ์ฃผ๋ฉด ๋œ๋‹ค.

CMake ํŒŒ์ผ ์ž‘์„ฑ

Build๋ฅผ ์œ„ํ•ด์„œ CMakeLists.txt๋ฅผ ์ž‘์„ฑํ•œ๋‹ค. ๋จผ์ €, ์˜์กด์„ฑ์ด ์žˆ๋Š” ํŒจํ‚ค์ง€๋“ค์„ ์ฐธ์กฐํ•ด์ค€๋‹ค.

find_package(catkin REQUIRED COMPONENTS
  controller_interface
  control_msgs
)

include_directories(include ${catkin_INCLUDE_DIRS})

catkin_package(
  CATKIN_DEPENDS
    controller_interface
    control_msgs
  LIBRARIES ${PROJECT_NAME}
)

๊ธฐ๋ณธ์ ์œผ๋กœ controller_interface, control_msgs๋ฅผ ์ฐธ์กฐํ•ด์ฃผ๋Š”๋ฐ ํ•„์š”์— ๋”ฐ๋ผ์„œ ros_control์—์„œ ์ง€์›ํ•ด์ฃผ๋Š” control_toolbox, realtime-tools ๋“ฑ๋„ ์ฐธ์กฐํ•  ์ˆ˜ ์žˆ๋‹ค.

๋‹ค์Œ์œผ๋กœ, ์ฐธ์กฐํ•œ ๋ผ์ด๋ธŒ๋Ÿฌ๋ฆฌ๋ฅผ ๋งํฌํ•ด์„œ ์ œ์–ด๊ธฐ ๋ผ์ด๋ธŒ๋Ÿฌ๋ฆฌ๋ฅผ ๋งŒ๋“ค์–ด ์ค€๋‹ค.

add_library(${PROJECT_NAME}
  src/new_controller_1.cpp
  src/new_controller_2.cpp
)

target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})

์†Œ์Šค ํŒŒ์ผ ์ž‘์„ฑ

๋์œผ๋กœ ๊ฐ๊ฐ ์ œ์–ด๊ธฐ์— ๋”ฐ๋ผ new_controller_1.cpp์™€ new_controller_2.cpp๋ฅผ ์ž‘์„ฑํ•ด์ค€๋‹ค. new_controller_1.cpp๋งŒ ์˜ˆ๋กœ ๋“ค์–ด๋ณด๊ฒ ๋‹ค.

#include <controller_interface/controller.h>
#include <hardware_interface/joint_command_interface.h>
#include <pluginlib/class_list_macros.h>

namespace my_controllers{

class NewController1 : public controller_interface::Controller<hardware_interface::EffortJointInterface>
{
public:
  bool init(hardware_interface::EffortJointInterface* hw, ros::NodeHandle &n)
  {
    // get joint name from the parameter server
    std::string my_joint;
    if (!n.getParam("joint", my_joint)){
      ROS_ERROR("Could not find joint name");
      return false;
    }

    // get the joint object to use in the realtime loop
    joint_ = hw->getHandle(my_joint);  
    return true;
  }

  void update(const ros::Time& time, const ros::Duration& period)
  {
    double error = setpoint_ - joint_.getPosition();
    joint_.setCommand(error*gain_);
  }

  void starting(const ros::Time& time) { }
  void stopping(const ros::Time& time) { }

private:
  hardware_interface::JointHandle joint_;
  double gain_ = 2.0;
  double setpoint_ = 3.0;
};
PLUGINLIB_DECLARE_CLASS(package_name, NewController1, controller_ns::NewController1, controller_interface::ControllerBase);
}//namespace

๋จผ์ € ํ•„์š”ํ•œ ๋ผ์ด๋ธŒ๋Ÿฌ๋ฆฌ๋ฅผ include ํ•ด์ค€๋‹ค.

#include <controller_interface/controller.h>
#include <hardware_interface/joint_command_interface.h>
#include <pluginlib/class_list_macros.h>

<controller_interface/controller.h>๋Š” ๋ง ๊ทธ๋Œ€๋กœ controller_interface๋ฅผ ์ƒ์†ํ•ด์„œ ์ œ์–ด๊ธฐ๋ฅผ ์ž‘์„ฑํ•˜๊ธฐ ์œ„ํ•จ์ด๊ณ , <hardware_interface/joint_command_interface.h>๋Š” hardware_interface ์ค‘์— ํ† ํฌ ์ถœ๋ ฅ์„ ์ค„ ์ˆ˜ ์žˆ๋Š” effort_interface๋ฅผ ์ด์šฉํ•˜๊ธฐ ์œ„ํ•จ์ด๋‹ค. hardware_interface๋Š” ํ•˜๋“œ์›จ์–ด์— ๋”ฐ๋ผ position_interface, velocity_interface ๋“ฑ์ด ์žˆ์œผ๋ฉฐ ์‚ฌ์šฉํ•˜๋Š” ๋ชจํ„ฐ ๋“œ๋ผ์ด๋ธŒ ์ข…๋ฅ˜์— ๋”ฐ๋ผ์„œ ์„ ํƒํ•  ์ˆ˜ ์žˆ๋‹ค.

controller class๋Š” namespace ์•ˆ์— ํŠน์ • ํ•˜๋“œ์›จ์–ด ์ธํ„ฐํŽ˜์ด์Šค๋ฅผ ์‚ฌ์šฉํ•˜๋Š” ์ œ์–ด๊ธฐ ๋ฒ ์ด์Šค ํด๋ž˜์Šค๋ฅผ ์ƒ์†๋ฐ›์•„์„œ ์ž‘์„ฑํ•œ๋‹ค.

namespace my_controllers{

class NewController1 : public controller_interface::Controller<hardware_interface::EffortJointInterface>
{
     ...

my_controllers namespace ์•ˆ์— hardware_interface๋กœ EffortJointInterface๋ฅผ ์‚ฌ์šฉํ•˜๋Š” controller๋ฅผ ์ƒ์†๋ฐ›์•„์„œ class๋ฅผ ์ž‘์„ฑํ•˜์˜€๋‹ค.

class ๋‚ด๋ถ€๋Š” init, starting, update, stop ํ•จ์ˆ˜๋ฅผ ์˜ค๋ฒ„๋ผ์ด๋”ฉ ํ•ด์„œ ๊ธฐ๋ณธ ๊ธฐ๋Šฅ์„ ๊ตฌํ˜„ํ•˜๊ณ , ์ถ”๊ฐ€์ ์œผ๋กœ command๋ฅผ subscribeํ•  ์ˆ˜ ์žˆ๋„๋ก callback ํ•จ์ˆ˜ ๋“ฑ์„ ์ถ”๊ฐ€ํ•ด ์ค„ ์ˆ˜๋„ ์žˆ๋‹ค. init์€ ์ œ์–ด๊ธฐ๊ฐ€ controller_manager์— ์˜ํ•ด์„œ ๋กœ๋”ฉ ๋  ๋•Œ ๋ถˆ๋ฆฌ๊ณ , starting, stop์€ ์ œ์–ด๊ธฐ๊ฐ€ ์‹œ์ž‘๋˜๊ณ  ๋๋‚  ๋•Œ ํ•œ๋ฒˆ์”ฉ ๋ถˆ๋ฆฌ๋ฉฐ, updateํ•จ์ˆ˜๋Š” ์ œ์–ด ์ฃผ๊ธฐ๋งˆ๋‹ค ๋งค๋ฒˆ ๋ถˆ๋ฆฌ๊ฒŒ ๋œ๋‹ค.

init ํ•จ์ˆ˜๋Š” joint handle์„ ์–ป์–ด์„œ ํด๋ž˜์Šค์—์„œ ์“ธ ์ˆ˜ ์žˆ๊ฒŒ ํ•ด์ฃผ๋ฉด, ros node handle๋„ ์ž…๋ ฅ์œผ๋กœ ๋“ค์–ด์˜ค๊ธฐ ๋•Œ๋ฌธ์— node์™€ ๊ด€๋ จ๋œ ํ† ํ”ฝ, ์„œ๋น„์Šค, ํŒŒ๋ผ๋ฏธํ„ฐ ํ•ธ๋“ค๋ง ๋“ฑ์„ ํ•„์š”์— ๋”ฐ๋ผ ์ž‘์„ฑํ•˜์—ฌ ์“ธ ์ˆ˜ ์žˆ๋‹ค.

  bool init(hardware_interface::EffortJointInterface* hw, ros::NodeHandle &n)
  {
    // get joint name from the parameter server
    std::string my_joint;
    if (!n.getParam("joint", my_joint)){
      ROS_ERROR("Could not find joint name");
      return false;
    }

    // get the joint object to use in the realtime loop
    joint_ = hw->getHandle(my_joint);  // throws on failure
    return true;
  }

update ํ•จ์ˆ˜์—๋Š” ์ œ์–ด๊ธฐ ์ฃผ ๋กœ์ง์ด ๋“ค์–ด๊ฐ€๊ฒŒ ๋˜๋ฉฐ, joint handle์„ ์ด์šฉํ•ด์„œ ๋ช…๋ น์„ ์ค„ ์ˆ˜ ์žˆ๋‹ค.

  void update(const ros::Time& time, const ros::Duration& period)
  {
    double error = setpoint_ - joint_.getPosition();
    joint_.setCommand(error*gain_);
  }

hardware_interface๊ฐ€ ๋ฌด์—‡์ด๋ƒ์— ๋”ฐ๋ผ์„œ setCommand๋Š” ๋‹ค๋ฅธ ์˜๋ฏธ๋ฅผ ์ง€๋‹ˆ๋Š”๋ฐ, ์—ฌ๊ธฐ์„œ๋Š” EffortJointInterface๋ฅผ ์„ ํƒํ–ˆ์œผ๋ฏ€๋กœ setCommand๋Š” ํ† ํฌ๊ฐ’์„ ๋ชจํ„ฐ ๋“œ๋ผ์ด๋ธŒ์— ๋„˜๊ฒจ์ฃผ๋Š” ํ•จ์ˆ˜๊ฐ€ ๋œ๋‹ค. ๋งŒ์•ฝ์— PositionJointInterface๋ฅผ ์„ ํƒํ–ˆ์œผ๋ฉด ์œ„์น˜๋ช…๋ น์„ ์ฃผ๋Š” ํ•จ์ˆ˜๊ฐ€ ๋œ๋‹ค.

์‹ค์ œ ์˜ˆ์ œ๋Š” ์ผ๋‹จ time delay controller, gravity compensation controller๋ฅผ ์ž‘์„ฑํ•œ ์˜ˆ์ œ๋ฅผ ์ฐธ์กฐํ•œ๋‹ค. (์ถ”ํ›„์— 1์ž์œ ๋„ ์งœ๋ฆฌ pendulum์ด๋‚˜ rrbot์œผ๋กœ ์‰ฌ์šด ์˜ˆ์ œ๋ฅผ ์ž‘์„ฑํ•ด๋ณด๋ ค๊ณ  ํ•œ๋‹ค..)

Reference

  1. Metapackages
  2. Write a new controller
โš ๏ธ **GitHub.com Fallback** โš ๏ธ