Writing a New Controller - modulabs/gazebo-tutorial GitHub Wiki
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 ํํ๋ก ์์ฑํ๋ฏ๋ก, ros pluginlib์ ๋ํ ์ดํด๊ฐ ์ ํ๋์ด์ผ ํ๋ค. plugin์ ์์์ ROS package์์ loading, unloadingํ ์ ์๋ C++ library๋ฅผ ์ผ์ปฌ์ผ๋ฉฐ, runtime์ ๋์ ์ผ๋ก ๋ถ๋ฌ ์ฌ ์ ์๋๋ก ๋์ library ํํ๋ก ์์ฑ๋๋ค. ๊ทธ๋ฅ ๋์ library๋ผ๋ฉด ๋ถ๋ฅด๋ ์ชฝ์์ ๋ช ์์ ์ผ๋ก ํด๋น ๋ผ์ด๋ธ๋ฌ๋ฆฌ๋ฅผ link์์ผ ์ค์ผ ํ์ง๋ง, pluginlib๋ฅผ ์ด์ฉํ๋ฉด ์ฌ์ฉ๋๋ library ์ธก์์ ์์ ์ export ์์ผ์ ์์์ ros package์์ ํธํ๊ฒ ๋ถ๋ฌ ์ธ ์ ์๋ค. ๊ทธ๋ฌ๋ ค๋ฉด, pluginlib์์ ์ ์ํ๋ ์์ฑ๋ฒ์ ๋ฐ๋ผ์ผ ํ๊ณ ์์ธํ ๋ฐฉ๋ฒ์ ros pluginlib๋ฅผ ์ฐธ์กฐํ๋ค.
๊ฐ์ฅ ๋จผ์ ํ ์ผ์ 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 ๋ฅผ ์ง์ ํด ์ฃผ๋ฉด ๋๋ค.
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์ผ๋ก ์ฌ์ด ์์ ๋ฅผ ์์ฑํด๋ณด๋ ค๊ณ ํ๋ค..)