이 저장소는 일반화된 역기구학 문제를 효율적으로 해결하기 위해 다양한 최적화 방법의 BSD 라이센스 독립 실행형 구현을 제공합니다.
전체 모듈은 Philipp Ruppel이 석사 논문의 일부로 구현했습니다.
원래 Unity 스토어에서 판매된 원래 "BioIK" 알고리즘을 C++ 기반으로 다시 구현하려면 기본이 아닌 모드 bio1
사용할 수 있습니다. 기본 모드 bio2_memetic
이 구현과 코드를 공유하지 않으며 성공률, 정밀도 및 효율성 측면에서 이를 능가하는 것으로 나타났으며 실제로 정밀 로봇 애플리케이션에 사용할 수 있습니다[4].
ROS 버전 Indigo 이상이 필요합니다(wiki.ros.org). 이 소프트웨어는 ROS Kinetic이 포함된 Ubuntu Linux 16.04 LTS에서 개발되었지만 ROS Indigo가 포함된 Ubuntu Linux 14.04 LTS에서도 테스트되었습니다. 최신 버전의 ROS는 작동하지만 약간의 조정이 필요할 수 있습니다. 버전별 지침은 아래를 참조하세요.
bio_ik
패키지를 다운로드하고 catkin 작업 공간에 압축을 풀어보세요.
작업공간을 컴파일하려면 catkin_make
실행하세요:
roscd
cd src
git clone https://github.com/TAMS-Group/bio_ik.git
roscd
catkin_make
bio_ik을 운동학 솔버로 사용하도록 Moveit을 구성합니다(다음 섹션 참조).
Moveit을 사용하여 모션을 계획하고 실행하거나 move_group
노드와 함께 자신의 코드를 사용하여 로봇을 움직일 수 있습니다.
평소와 같이 공개 API는 include/bio_ik
하위 디렉터리에 있는 bio_ik
패키지의 공개 헤더 파일에 지정됩니다. 몇 가지 개인 헤더 파일을 포함한 소스는 src
하위 디렉터리에 있습니다.
사용 편의성과 기존 코드와의 호환성을 위해 bio_ik 알고리즘은 Moveit 운동학 플러그인으로 캡슐화됩니다. 따라서 bio_ik은 기본 Orocos/KDL 기반 IK 솔버를 직접 대체하는 데 사용할 수 있습니다. 엔드 이펙터의 이름과 6-DOF 목표 포즈가 주어지면 bio_ik은 주어진 목표에 도달하는 유효한 로봇 관절 구성을 검색합니다.
테스트(아래 참조)에서 성공률과 해결 시간 측면에서 bio_ik은 정기적으로 Orocos [1] 솔버보다 성능이 뛰어났으며 trac-ik [2]와 경쟁적이었습니다. bio_ik 알고리즘은 로봇 뱀과 같은 고DOF 시스템에도 사용할 수 있으며 일부 대상 포즈에 정확하게 도달할 수 없는 저DOF 팔에 대한 최적의 근사 솔루션으로 자동으로 수렴됩니다.
Moveit 구성 파일을 직접 작성할 수도 있지만 가장 쉬운 방법은 로봇의 Moveit 설정 도우미를 실행한 다음 엔드 이펙터를 구성할 때 bio_ik을 IK 솔버로 선택하는 것입니다. 일단 구성되면 표준 Moveit API를 사용하여 솔버를 호출하거나 MotionPlanning GUI 플러그인을 사용하여 rviz에서 대화식으로 사용할 수 있습니다.
로봇에 대한 URDF(또는 xacro) 모델이 있는지 확인하십시오.
Moveit 설정 도우미를 실행하여 Moveit 구성 파일을 생성합니다.
rosrun moveit_setup_assistant moveit_setup_assistant
설정 도우미는 작업 공간에서 사용 가능한 모든 IK 솔버 플러그인을 자동으로 검색합니다. 따라서 모든 엔드 이펙터에 대한 드롭다운 목록에서 bio_ik을 IK 솔버로 선택한 다음 운동학 매개변수, 즉 기본 위치 정확도(미터) 및 시간 제한(초)을 구성하면 됩니다. 일반적인 6-DOF 또는 7-DOF 암의 경우 0.001m(또는 그 이하)의 정확도와 1msec의 시간 제한이 괜찮습니다. 더 복잡한 로봇에는 더 긴 시간 초과가 필요할 수 있습니다.
설정 도우미에서 moveit 구성 파일을 생성합니다. 물론 선호하는 텍스트 편집기를 사용하여 config/kinematics.yaml
구성 파일을 편집할 수도 있습니다. 예를 들어 PR2 로봇의 구성은 다음과 같습니다.
# example kinematics.yaml for the PR2 robot
right_arm:
# kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
# kinematics_solver_attempts: 1
kinematics_solver: bio_ik/BioIKKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 1
left_arm:
kinematics_solver: bio_ik/BioIKKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 1
all:
kinematics_solver: bio_ik/BioIKKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.02
kinematics_solver_attempts: 1
# optional bio_ik configuration parameters
# center_joints_weight: 1
# minimal_displacement_weight: 1
# avoid_joint_limits_weight: 1
첫 번째 테스트를 위해 Moveit에서 만든 데모 실행을 실행하세요. rviz가 실행되면 모션 계획 플러그인을 활성화한 다음 로봇의 엔드 이펙터 중 하나를 선택하십시오. Rviz는 선택된 엔드 이펙터에 대한 6D(위치 및 방향) 대화형 마커를 표시해야 합니다. 대화형 마커를 이동하고 bio_ik이 로봇의 포즈를 계산하는 모습을 지켜보세요.
bio_ik 데모(아래 참조)도 설치한 경우 사전 정의된 데모 중 하나를 실행할 수 있습니다.
roslaunch pr2_bioik_moveit demo.launch
roslaunch pr2_bioik_moveit valve.launch
roslaunch pr2_bioik_moveit dance.launch
이제 표준 Moveit API를 사용하여 C/C++ 및 Python 프로그램에서 bio_ik을 사용할 준비가 되었습니다. C++에서 IK 솔루션을 명시적으로 요청하려면:
robot_model_loader::RobotModelLoader robot_model_loader(robot);
auto robot_model = robot_model_loader.getModel();
auto joint_model_group = robot_model->getJointModelGroup(group);
auto tip_names = joint_model_group->getSolverInstance()->getTipFrames();
kinematics::KinematicsQueryOptions opts;
opts.return_approximate_solution = true; // optional
robot_state::RobotState robot_state_ik(robot_model);
// traditional "basic" bio_ik usage. The end-effector goal poses
// and end-effector link names are passed into the setFromIK()
// call. The KinematicsQueryOptions are empty.
//
bool ok = robot_state_ik.setFromIK(
joint_model_group, // joints to be used for IK
tip_transforms, // multiple end-effector goal poses
tip_names, // names of the end-effector links
attempts, timeout, // solver attempts and timeout
moveit::core::GroupStateValidityCallbackFn(),
opts // mostly empty
);
많은 로봇 애플리케이션의 경우 단일 엔드 이펙터 포즈 이상을 지정하는 것이 필수적입니다. 전형적인 예는 다음과 같습니다
bio_ik에서는 이러한 작업이 여러 개별 목표 의 조합으로 지정됩니다.
그런 다음 알고리즘은 가중치가 부여된 개별 목표로부터 구축된 2차 오류 함수를 최소화하여 주어진 모든 목표를 동시에 충족하는 로봇 구성을 찾으려고 시도합니다. 현재 Moveit API는 다중 목표 작업을 직접 지원하지 않지만 KinematicQueryOptions 클래스를 제공합니다. 따라서 bio_ik은 단순히 사전 정의된 모션 목표 세트를 제공하고 사용자가 지정한 목표의 조합이 Moveit을 통해 IK 솔버로 전달됩니다. Moveit에서는 API 변경이 필요하지 않지만 이제 IK 솔버를 사용하면 KinematicQueryOptions를 통해 가중치 목표를 전달하게 됩니다. 사전 정의된 목표에는 다음이 포함됩니다.
로봇의 모션 문제를 해결하기 위한 비결은 이제 개별 목표의 적절한 조합을 구성하는 것입니다.
다음 예에서는 PR2 로봇의 왼쪽 및 오른쪽 그리퍼로 밸브 휠을 잡고 천천히 돌리 려고 합니다.
bio_ik::BioIKKinematicsQueryOptions ik_options;
ik_options.replace = true;
ik_options.return_approximate_solution = true;
auto* ll_goal = new bio_ik::PoseGoal();
auto* lr_goal = new bio_ik::PoseGoal();
auto* rl_goal = new bio_ik::PoseGoal();
auto* rr_goal = new bio_ik::PoseGoal();
ll_goal->setLinkName("l_gripper_l_finger_tip_link");
lr_goal->setLinkName("l_gripper_r_finger_tip_link");
rl_goal->setLinkName("r_gripper_l_finger_tip_link");
rr_goal->setLinkName("r_gripper_r_finger_tip_link");
ik_options.goals.emplace_back(ll_goal);
ik_options.goals.emplace_back(lr_goal);
ik_options.goals.emplace_back(rl_goal);
ik_options.goals.emplace_back(rr_goal);
우리는 또한 몇 가지 부차적인 목표도 설정했습니다. 먼저 PR2의 헤드가 밸브 중앙을 바라보기를 원합니다. 둘째, 가능하다면 모든 관절에 대한 관절 제한을 피하고 싶습니다. 셋째, 우리는 IK 솔루션이 이전 관절 구성에 최대한 가깝기를 원하며 이는 작고 효율적인 동작을 의미합니다. 이는 MinimalDisplacementGoal을 추가하여 처리됩니다. 넷째, PR2에서는 매우 느린 몸통 들어올리기 동작을 피하고 싶습니다. 이 모든 것은 쉽게 지정됩니다.
auto* lookat_goal = new bio_ik::LookAtGoal();
lookat_goal->setLinkName("sensor_mount_link");
ik_options.goals.emplace_back(lookat_goal);
auto* avoid_joint_limits_goal = new bio_ik::AvoidJointLimitsGoal();
ik_options.goals.emplace_back(avoid_joint_limits_goal);
auto* minimal_displacement_goal = new bio_ik::MinimalDisplacementGoal();
ik_options.goals.emplace_back(minimal_displacement_goal);
auto* torso_goal = new bio_ik::PositionGoal();
torso_goal->setLinkName("torso_lift_link");
torso_goal->setWeight(1);
torso_goal->setPosition(tf::Vector3( -0.05, 0, 1.0 ));
ik_options.goals.emplace_back(torso_goal);
실제 회전 동작을 위해 루프에서 필요한 그리퍼 포즈 세트를 계산합니다.
for(int i = 0; ; i++) {
tf::Vector3 center(0.7, 0, 1);
double t = i * 0.1;
double r = 0.1;
double a = sin(t) * 1;
double dx = fmin(0.0, cos(t) * -0.1);
double dy = cos(a) * r;
double dz = sin(a) * r;
tf::Vector3 dl(dx, +dy, +dz);
tf::Vector3 dr(dx, -dy, -dz);
tf::Vector3 dg = tf::Vector3(0, cos(a), sin(a)) * (0.025 + fmin(0.025, fmax(0.0, cos(t) * 0.1)));
ll_goal->setPosition(center + dl + dg);
lr_goal->setPosition(center + dl - dg);
rl_goal->setPosition(center + dr + dg);
rr_goal->setPosition(center + dr - dg);
double ro = 0;
ll_goal->setOrientation(tf::Quaternion(tf::Vector3(1, 0, 0), a + ro));
lr_goal->setOrientation(tf::Quaternion(tf::Vector3(1, 0, 0), a + ro));
rl_goal->setOrientation(tf::Quaternion(tf::Vector3(1, 0, 0), a + ro));
rr_goal->setOrientation(tf::Quaternion(tf::Vector3(1, 0, 0), a + ro));
lookat_goal->setAxis(tf::Vector3(1, 0, 0));
lookat_goal->setTarget(rr_goal->getPosition());
// "advanced" bio_ik usage. The call parameters for the end-effector
// poses and end-effector link names are left empty; instead the
// requested goals and weights are passed via the ik_options object.
//
robot_state.setFromIK(
joint_model_group, // active PR2 joints
EigenSTL::vector_Affine3d(), // no explicit poses here
std::vector<std::string>(), // no end effector links here
0, 0.0, // take values from YAML file
moveit::core::GroupStateValidityCallbackFn(),
ik_options // four gripper goals and secondary goals
);
... // check solution validity and actually move the robot
}
코드를 실행하면 PR2가 밸브 휠에 닿아 회전합니다. 때때로 현재 암 구성으로는 밸브에 도달할 수 없어 휠을 다시 잡게 됩니다.
더 많은 예를 보려면 [3]과 [4]를 참조하세요.
BioIK는 다중 목표 및 로컬 최소값이 있는 비볼록 역운동학 문제에 대한 좋은 솔루션을 효율적으로 찾기 위해 개발되었습니다. 그러나 일부 애플리케이션의 경우 이는 직관적이지 않은 결과를 초래할 수 있습니다. 주어진 IK 문제에 대해 가능한 솔루션이 여러 개 있고 사용자가 선택할 솔루션을 명시적으로 지정하지 않은 경우 모든 유효한 솔루션 세트에서 결과가 무작위로 선택될 수 있습니다. 데카르트 경로를 점진적으로 추적하면 원치 않는 점프, 흔들림 등이 발생할 수 있습니다. BioIK를 사용하여 부드러운 궤적을 점진적으로 생성하려면 원하는 동작을 명시적으로 지정해야 하며 이 작업은 두 가지 방법으로 수행할 수 있습니다.
BioIK는 전역 최적화 프로그램과 로컬 최적화 프로그램을 포함하여 다양한 솔버를 제공합니다. 기본적으로 BioIK는 밈적 전역 최적화 프로그램( bio2_memetic
)을 사용합니다. MoveIt 로봇 구성의 kinematics.yaml
파일에서 mode
매개변수를 설정하여 다른 솔버 클래스를 선택할 수 있습니다.
예:
all:
kinematics_solver: bio_ik/BioIKKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.02
kinematics_solver_attempts: 1
mode: gd_c
현재 사용 가능한 로컬 최적화 프로그램:
gd, gd_2, gd_4, gd_8
gd_r, gd_r_2, gd_r_4, gd_r_8
gd_c, gd_c_2, gd_c_4, gd_c_8
jac, jac_2, jac_4, jac_8
명명 규칙: <solver type>_[<variant>_]<number of threads>
참고:
gd_*
솔버는 임의의 목표 유형을 지원합니다.jac_*
솔버는 포즈 목표만 지원하지만 이론적으로 어떤 경우에는 더 안정적일 수 있습니다.gd_c
변형은 일반적으로 다른 로컬 솔버보다 성능이 뛰어났습니다.gd_c
, gd
또는 jac
).정규화를 통해 전역 최적화 프로그램이 로컬 최소값을 반환하도록 강제할 수 있습니다.
증분 로봇 동작( 조깅 이라고도 함)의 특정 사례에 대해 가장 간단한 해결책은 PoseGoal 과 특수 RegularizationGoal을 모두 지정하는 것입니다. 이는 관절 공간 IK 솔루션을 주어진 로봇 시드 구성에 최대한 가깝게 유지하려고 합니다. 일반적으로 PoseGoal 에는 높은 가중치를 사용하고 정규화에는 더 작은 가중치를 사용합니다.
RegularizationGoal 대신 MinimalDisplacementGoal 을 추가할 수도 있습니다. 두 목표 모두 IK 솔루션을 현재/시드 로봇 상태에 가깝게 유지하려고 시도하지만 빠르고 느린 로봇 관절을 처리하는 데는 약간 다릅니다(예: PR2에는 빠른 팔 관절이 있고 다소 느린 몸통 리프트 관절이 있습니다). 어느 목표가 귀하의 요구 사항에 더 잘 맞는지 확인하기 위해 두 목표를 모두 가지고 플레이할 수 있습니다.
7-DOF 암의 일부 산업용 로봇 컨트롤러는 하나의 추가 관절이 있는 6-DOF 암에서 작업하는 것처럼 동작합니다. 일반적으로 추가 관절의 값을 지정할 수 있으며 그런 다음 나머지 6개 관절에 대해 IK 솔루션을 검색합니다. 이 동작은 엔드 이펙터에 대한 PoseGoal 과 로봇 관절 중 하나에 대한 JointPositionGoal을 결합하여 bio_ik에서 달성할 수 있습니다.
또 다른 유용한 트릭은 로봇 관절을 중앙에 유지하는 것입니다. 이렇게 하면 로봇(관절)이 양방향으로 움직일 수 있습니다. PoseGoal을 CenterJointsGoal 과 결합하고 선택적으로 RegularizationGaol 도 결합하면 됩니다.
정규화를 로컬 gd_*
솔버와 결합할 수도 있습니다.
bio_ik 솔버는 경사 기반 최적화와 유전자 및 입자 떼 최적화를 결합한 밈적 알고리즘을 기반으로 합니다.
내부적으로 모든 로봇 관절 값의 벡터는 다양한 중간 솔루션(유전자 알고리즘의 유전자형 )을 인코딩하는 데 사용됩니다. 최적화 중에 관절 값은 항상 활성 하한 및 상한 관절 제한과 비교하여 확인되므로 유효한 로봇 구성만 생성됩니다.
개인의 적합성을 계산하기 위해 주어진 모든 개인 목표에 대한 누적 오류가 계산됩니다. 오류가 없는 개인은 IK 문제에 대한 정확한 솔루션이고, 오류가 작은 개인은 대략적인 솔루션에 해당합니다.
개인은 적합도에 따라 정렬되고 가장 좋은 몇 가지 구성에서 그래디언트 기반 최적화가 시도되어 많은 문제에 대해 빠른 수렴과 좋은 성능을 얻습니다. 그래디언트 기반 최적화에서 솔루션을 찾을 수 없는 경우 일련의 돌연변이 및 재조합 연산자에 의해 새로운 개체가 생성되어 좋은 검색 공간 탐색이 가능합니다.
자세한 내용은 [3]과 [4]를 참조하세요. 비디오 게임 캐릭터 애니메이션을 위한 초기 진화 알고리즘에 대한 자세한 설명은 [5]와 [6]을 참조하십시오.
우리는 전통적인 단일 엔드 이펙터 API와 KinematicsQueryOptions를 기반으로 하는 고급 다중 엔드 이펙터 API를 사용하여 다양한 로봇 팔에서 bio_ik을 테스트했습니다.
간단한 자체 테스트 중 하나는 임의의 유효한 로봇 구성 생성, 순방향 운동학 실행을 통해 최종 엔드 이펙터 자세 계산, IK 플러그인 쿼리로 적절한 로봇 관절 구성 찾기로 구성됩니다. 그런 다음 순방향 운동학을 다시 실행하고 생성된 IK 솔루션의 엔드 이펙터 포즈가 대상 포즈와 일치하는지 확인하여 성공 여부를 확인합니다. 이 접근 방식은 수천 또는 수백만 개의 임의 포즈에 대해 쉽게 실행할 수 있고 로봇의 전체 작업 공간을 샘플링하며 선택한 IK 솔버에 대한 성공률 및 솔루션 시간 추정치를 빠르게 생성할 수 있습니다.
물론 테스트를 실행하려면 해당 로봇 모델을 설치해야 하며 많은 종속성이 추가됩니다. 따라서 이러한 테스트는 표준 bio_ik 패키지에 포함되지 않고 별도로 패키지됩니다.
편의를 위해 우리는 PR2 서비스 로봇에 대한 몇 가지 bio_ik 데모도 포함하는 pr2_bioik_moveit
패키지를 제공합니다. 이것은 운동학 전용 데모입니다. 물론 실제 로봇(있는 경우)이나 Gazebo 시뮬레이터(Gazebo를 설치한 경우)에서 데모를 실행해 볼 수도 있습니다.
간단히 PR2 설명 패키지( pr2_common
내부)와 pr2_bioik_moveit
패키지를 catkin 작업 공간에 복제하세요.
roscd
cd src
git clone https://github.com/PR2/pr2_common.git
git clone https://github.com/TAMS-Group/bioik_pr2.git
catkin_make
FK-IK-FK 성능 테스트를 위해서는 다음을 실행하십시오.
roslaunch pr2_bioik_moveit env_pr2.launch
roslaunch pr2_bioik_moveit test_fk_ik.launch
... // wait for test completion and results summary
Orocos 운동학 및 역학, http://www.orocos.org
P. Beeson 및 B. Ames, TRAC-IK: 일반 역기구학 해결 개선을 위한 오픈 소스 라이브러리 , IEEE RAS 휴머노이드 컨퍼런스 논문집, 대한민국 서울, 2015년 11월.
Philipp Ruppel, Norman Hendrich, Sebastian Starke, Jianwei Zhang, 전신 동작 및 다중 목표 조작 작업을 지정하는 비용 함수 , 로봇 공학 및 자동화에 관한 IEEE 국제 컨퍼런스(ICRA-2018), 호주 브리즈번. DOI: 10.1109/ICRA.2018.8460799
Philipp Ruppel, ROS에서 진화적 역운동학의 성능 최적화 및 구현 , 석사 논문, 함부르크 대학교, 2017 PDF
Sebastian Starke, Norman Hendrich, Jianwei Zhang, 실시간 관절 운동학 모션을 위한 밈적 진화 알고리즘 , IEEE Intl. 진화 계산에 관한 회의(CEC-2017), p.2437-2479, 2017년 6월 4~8일, 스페인 산세바스티안. DOI: 10.1109/CEC.2017.7969605
Sebastian Starke, Norman Hendrich, Dennis Krupke, Jianwei Zhang, 고도로 관절화된 인간형 로봇의 역기구학을 위한 다목표 진화 최적화 , IEEE Intl. 지능형 로봇 및 시스템에 관한 컨퍼런스(IROS-2017), 2017년 9월 24~28일, 캐나다 밴쿠버