Using orocos KDL library - modulabs/gazebo-tutorial GitHub Wiki

Introduction

๋กœ๋ด‡์•” 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

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๋ฅผ ์ฐธ์กฐํ•˜๋Š” ๊ฒƒ์ด ์ข‹๋‹ค.

Dependency

์˜์กด์„ฑ์€ 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));
	}
โš ๏ธ **GitHub.com Fallback** โš ๏ธ