Using orocos KDL library - modulabs/gazebo-tutorial GitHub Wiki
๋ก๋ด์ Controller๋ฅผ ์์ฑํ๋ค ๋ณด๋ฉด kinematics, dynamics library๊ฐ ํ์ํ ๊ฒฝ์ฐ๊ฐ ์๋ค. kinematics๋ ๋งํฌ ๊ธธ์ด๋ ๊ด์ ๊ตฌ์กฐ์ ๋ฐ๋ผ์ ์กฐ์ธํธ ๊ฐ๊ณผ ์๋์ดํํฐ ์์น/์์ธ์ ๊ด๊ณ๋ฅผ ๋ํ๋ธ ๊ฒ์ด๊ณ , dynamics๋ ๊ด์ฑ, ์ค๋ ฅ, Coriolis, ๋ง์ฐฐ๋ ฅ ๋ฑ์ ํ๊ณผ ๋งํฌ ์ฌ์ด์ ๊ด๊ณ๋ฅผ ๊ณ์ฐํ๋ ๊ฒ์ด๋ค. kinematics๋ ์ ์ด๊ธฐ์์ ์ฃผ๋ก ์ญ๊ธฐ๊ตฌํ์ ์ด์ฉํด์ task space์์์ ๋ช ๋ น์ joint space๋ก ์ฎ๊ฒจ์ joint ์์น ๋ช ๋ น์ ๋ณด๋ผ ๋ ์ฌ์ฉํ๊ณ , dynamics๋ joint์ ํ ํฌ ๋ช ๋ น์ ์ฃผ๋ ค๊ณ ํ ๋ ๋ฏธ๋ฆฌ ํ์ํ ๊ฒ ๊ฐ์ ํ ํฌ๋ฅผ ๊ณ์ฐํด์ feedforward๋ก ๋ณด์ํด์ฃผ๊ฑฐ๋ feedback linearization์ ํ ๋ ์ฌ์ฉํ๋ค.
kinematics, dynamics์ ์๋ฆฌ, ์์, ์๊ณ ๋ฆฌ์ฆ์ ๋ก๋ณดํฑ์ค ํ ์คํธ๋ถ์ ์ ๋์ ์์ด์ ์ง์ ๊ตฌํํ ์๋ ์๊ฒ ์ง๋ง, ์ฌ๊ธฐ์๋ ์ ๋ฝ ์ชฝ์์ orocos๋ผ๋ ros์ ๋น์ทํ middleware์์ ์ง์ํด์ฃผ๋ KDL library๋ฅผ ์ฌ์ฉํ๋ ๋ฒ์ ์์๋ณด์. KDL library๋ ros์๋ ํฌํ ๋์ด ์์ผ๋ฉฐ urdf ๋ชจ๋ธ์ parsingํ ์ ์๋ kdl_parser๋ ์์ด์ kinematics, dynamics๋ฅผ ๊ณ์ฐํ ๋ ํ์ํ ๋งํฌ ๊ธธ์ด, Inertia ์ ๋ณด ๋ฑ์ ๋ค์ ์์ฑํ ํ์์์ด urdf ๋ชจ๋ธ์์ ๋ถ๋ฌ์ฌ ์ ์์ด์ ๋งค์ฐ ํธ๋ฆฌํ๋ค.
์ด๋ฒ ํ์ด์ง์์๋ ๊ฐ๋จํ ์ค๋ ฅ ๋ณด์ ์ ์ด๊ธฐ ์์ ๋ฅผ ํตํด์ kdl library๋ฅผ ros์์ ์ฌ์ฉํ๋ ๋ฒ์ ์์๋ณด์.
์ค๋ ฅ ๋ณด์ ์ ์ด๊ธฐ๋ ์ค๋ ฅ์ ์ํด์ ๊ฐ ๊ด์ ์ด ๋ฐ๋ ํ์ ๊ณ์ฐํด์ ์ด ํ์ ๋ณด์ํด์ฃผ๊ณ ํผ๋๋ฐฑ ์ ์ด๊ธฐ๋ฅผ ์ ์ฉํ๋ ๋ฐฉ๋ฒ์ด๋ค. ๋ก๋ด์์ ์์ธ์ ๋ฐ๋ผ์ ๊ฐ ๊ด์ ์ด ์ค๋ ฅ์ ๊ฒฌ๋์ผ ํ๋ ํ ํฌ๊ฐ ๋ฌ๋ผ์ง๊ฒ ๋ง๋ จ์ด๊ณ ๋ชจํฐ ์ ์ฅ์์๋ ๊ฐ๋งํ ์์ผ๋ ค๊ณ ํด๋ ์ด๋จ ๋๋ 1๋งํผ์ ํ์ด ํ์ํ๋ฐ, ์ด๋จ ๋๋ ๋ 2๋งํผ์ ํ์ด ํ์ํ๊ฒ ๋๋ ๊ฒ์ด๊ธฐ ๋๋ฌธ์ ๊ฝค ํฐ ์ธ๋์ด ๋๋ค. ์ด๊ฒ์ ํผ๋๋ฐฑ์ผ๋ก๋ง ์ก์ผ๋ ค๊ณ ํ๋ฉด ์ค์ฐจ๊ฐ ์ด๋ฏธ ์๊ฒจ์ผ ๋ณต์ํ๋ ค๋ ํ์ด ์๊ธฐ๋ฏ๋ก ๋ฐ์์ด ๋ฆ์ด์ง๊ณ ์ค์ฐจ๋ง์ผ๋ก ์ ์ด๋ฅผ ํด์ผํ๊ธฐ ๋๋ฌธ์ ๊ฒ์ธ์ด ์ปค์ง๊ฒ ๋๋ค. ๋ฐ๋ผ์ ์ค๋ ฅ์ ์ํ ํ์ ๋ฏธ๋ฆฌ ๊ณ์ฐํด์ ์ด๋ฅผ ๋ณด์ํด์ฃผ๊ณ ๊ทธ ๋๋จธ์ง๋ฅผ ํผ๋๋ฐฑ ์ ์ด๊ธฐ๊ฐ ๋ด๋นํ๊ฒ ํด์ ๋ถ๋ด์ ์ค์ฌ์ฃผ๋ ๊ฒ์ด๋ค.
์์ผ๋ก ํํํด๋ณด์. ๋ก๋ด์์ ๋์ญํ ์์ ๊ฐ์๋์ ์ํ ๊ด์ฑ์ง๋ term, Coriolis term, ์ค๋ ฅ term ์ ํฉ์ด Joint์ ๊ฐํ๋ torque์ ์ผ์นํ๋ค.
์ด ๋, ์ ์ด ์ ๋ ฅ์ธ Joint torque์ ์ค๋ ฅ๊ณผ ํผ๋๋ฐฑ ์ ์ด ์ ๋ ฅ์ ์ฃผ๋ฉด ์ค๋ ฅ term์ ์์๋๊ณ ๋๋จธ์ง๋ง ์ธ๋์ผ๋ก ์์ฉํ๊ณ , ์ด๊ฒ์ ํผ๋๋ฐฑ ์ ์ด๊ธฐ๊ฐ ์ก์์ฃผ๋ ๊ฒ์ด๋ค.
kdl์ ros๋ก ํฌํ ํด์ฃผ๋ package๋ kdl_parser์ด๋ค. ํ์ฌ lunar๊น์ง ์ง์๋๋ ๊ฒ ๊ฐ๊ณ , ํ ์คํธ๋ kinetic์ผ๋ก ํด ๋ณด์๋ค. kdl์ ๋งํฌ, ์กฐ์ธํธ ๊ตฌ์กฐ๋ฅผ chain์ด๋ผ๋ ๊ฐ๋ ์ผ๋ก ๋ฐ์๋ค์ด๋๋ฐ ์ ์ฒด ๋ก๋ด urdf ๋ชจ๋ธ ์ค์์ ๋ด๊ฐ ์ ์ดํ ๋ ํ์ํ segment๋ง์ chain์ผ๋ก ์ ๋ ฅ๋ฐ์์ ๊ทธ chain์ root๋ถํฐ tip๊น์ง kinematics์ dynamics๋ฅผ ๊ณ์ฐํด์ค๋ค. kdl์ vector, homogeneous transform ๋ฑ ๋ก๋ณดํฑ์ค ๊ณ์ฐ์ ํ์ํ math ๋ ์ง์ํด์ฃผ๊ณ , joint๋ฅผ ๋ค๋ฃฐ ๋ ์ ์ฉํ class ๋ค๋ ์ ๊ณตํด์ค๋ค. ํ์ง๋ง, ๋ฌธ์๊ฐ ์ข ๋น์ฝํด์ doxygen page๋ฅผ ์ฐธ์กฐํ๋ ๊ฒ์ด ์ข๋ค.
์์กด์ฑ์ kdl_parser๋ง ์ฐธ์กฐํด์ฃผ๋ฉด ํด๊ฒฐ๋๋ค. package.xml์ kdl_parser๋ฅผ ํฌํจํด์ฃผ๊ณ ,
<build_depend>kdl_parser</build_depend>
<run_depend>kdl_parser</run_depend>CMakeLists.txt์๋ kdl_parser๋ฅผ ํฌํจํด์ค๋ค.
find_package(catkin REQUIRED COMPONENTS
...
kdl_parser
)
include_directories(include ${catkin_INCLUDE_DIRS})
catkin_package(
CATKIN_DEPENDS
...
kdl_parser
LIBRARIES ${PROJECT_NAME}
)ํ์ํ ํ์ผ๋ค์ includeํด ์ค๋ค. tree.hpp, kdl.hpp, chain.hpp, kdl_parser.hpp๋ ๊ธฐ๋ณธ์ ์ผ๋ก ๋ค์ด๊ฐ๊ณ chaindynparam.hpp๋ kinematics๋ฅผ ํ์ง, dynamics๋ฅผ ํ์ง ๋๋ ์ด๋ค solver๋ฅผ ์ธ์ง์ ๋ฐ๋ผ ๋ฌ๋ผ์ง๋ค.
#include <kdl/tree.hpp>
#include <kdl/kdl.hpp>
#include <kdl/chain.hpp>
#include <kdl/chaindynparam.hpp>
#include <kdl_parser/kdl_parser.hpp>ํ์ํ ๋ณ์๋ค์ KDL::Tree, KDL::Chain๊ฐ ๊ธฐ๋ณธ์ด๊ณ , solver๋ ํ์์ ๋ฐ๋ผ ์ ํํ๋ค. ์ฌ๊ธฐ์๋ Gravity torque vector๋ฅผ ๊ณ์ฐํด์ผ ํ๋ฏ๋ก KDL::ChainDynParam์ solver๋ก ์ ํํ๋ค. ๊ทธ ์ธ์ ํ์ํ ๋ณ์๋ฅผ KDL::JntArray ๋ฅผ ์ด์ฉํด์ ๋ฒกํฐ ๊ธธ์ด๋ฅผ ๊ฐ๋ณ์ ์ผ๋ก ์ฌ์ฉํ ์ ์๋ค.
// kdl
KDL::Tree kdl_tree_;
KDL::Chain kdl_chain_;
boost::scoped_ptr<KDL::ChainDynParam> id_solver_; // inverse dynamics solver
KDL::JntArray G_; // gravity torque vector
KDL::Vector gravity_;
// pid gain
KDL::JntArray Kp_, Ki_, Kd_; // p,i,d gain
KDL::JntArray q_error_integral_;
double q_integral_min_;
double q_integral_max_;
// cmd, state
KDL::JntArray tau_cmd_;
KDL::JntArray q_cmd_, qdot_cmd_, qddot_cmd_;
KDL::JntArray q_cmd_sp_;
KDL::JntArray q_, qdot_;
// limit
KDL::JntArray q_limit_min_, q_limit_max_, qdot_limit_, qddot_limit_;์ฌ๊ธฐ์๋ ์ฌ์ฉํ์ง ์์์ง๋ง KDL::JntArrayAcc ๊ฐ์ class๋ Joint pos, vel, acc๋ฅผ ๋ชจ๋ ํฌํจํ๋ ์๋ฃํ์ผ๋ก์ ๊ฐ๊ฐ ์ ์ธํด์ ์ฌ์ฉํ๊ธฐ ๋ฒ๊ฑฐ๋ก์ธ ๋ ์ฌ์ฉํ๊ธฐ ์ข๋ค.
์ ์ด๊ธฐ init ํจ์์์ urdf๋ฅผ ์ฝ๊ณ joint handle ์ ์ฝ์ด์ฌ ๋, kdl chain๋ ๋ง๋ค์ด์ค๋ค. treeFromUrdfModel, getChain ํจ์๋ฅผ ์ด์ฉํ๋ฉด ๋ช ์ค๋ก chain์ ๋ง๋ค ์ ์๊ณ , ์ด ๋ ๋ค์ด๊ฐ๋ ๋งํฌ ์ด๋ฆ์ด root์ tip์ผ๋ก ๊ทธ ์ฌ์ด๊ฐ ๋ชจ๋ ๊ณ์ฐํ๋ ๊ตฌ๊ฐ์ด ๋๋ค. ๋ง์ง๋ง์ผ๋ก solver๋ chain๊ณผ ์ค๋ ฅ ๋ฒกํฐ๋ฅผ ์ ๋ ฅ์ผ๋ก ์ฃผ๊ณ ์์ฑํ๋ค.
// kdl parser
if (!kdl_parser::treeFromUrdfModel(urdf, kdl_tree_)){
ROS_ERROR("Failed to construct kdl tree");
return false;
}
// kdl chain
std::string root_name = "world";
std::string tip_name = "elfin_link6";
if(!kdl_tree_.getChain(root_name, tip_name, kdl_chain_))
{
return false;
}
gravity_ = KDL::Vector::Zero();
gravity_(2) = -9.81;
G_.resize(n_joints_);
// inverse dynamics solver
id_solver_.reset( new KDL::ChainDynParam(kdl_chain_, gravity_) );์ ์ด๊ธฐ ๋ก์ง์ ๊ณ์ฐํ๋ update ํจ์์์๋ ์ค์ ์ค๋ ฅ ๋ณด์ ์ ์ด๊ธฐ๋ฅผ ๊ตฌํํ๋ค. JntToGravityํจ์์ ํ์ฌ ์กฐ์ธํธ๊ฐ์ ์ฃผ๋ฉด ์ค๋ ฅ ํ ํฌ๋ฅผ ๊ณ์ฐํด์ฃผ๊ณ ๋๋จธ์ง ํผ๋๋ฐฑ ์ ์ด๊ธฐ๋ฅผ pid๋ก ๊ตฌํํ์๋ค. KDL::JntArray๋ eigen์ VectorXdํ data๋ฅผ ๊ฐ์ง๊ณ ์์ด์ JntArray ์์ฒด์์ ์ง์๋์ง ์๋ ๋ฒกํฐ ์ฐ์ฐ์ data์ ์ง์ ์ ๊ทผํด์ ์ฌ์ฉํ๋ฉด ๋๋ค.
// compute gravity torque
id_solver_->JntToGravity(q_, G_);
// error
KDL::JntArray q_error;
q_error.data = q_cmd_.data - q_.data; // [to do] shortest distance using angle
q_error_integral_.data += q_error.data;
// integral saturation
for (size_t i; i<n_joints_; i++)
{
if (q_error_integral_(i) > q_integral_max_)
q_error_integral_(i) = q_integral_max_;
else if (q_error_integral_(i) < -q_integral_max_)
q_error_integral_(i) = -q_integral_max_;
}
// torque command
tau_cmd_.data = G_.data + Kp_.data.cwiseProduct(q_error.data) - Kd_.data.cwiseProduct(qdot_.data) + Ki_.data.cwiseProduct(q_error_integral_.data);
for(int i=0; i<n_joints_; i++)
{
joints_[i].setCommand(tau_cmd_(i));
}