พื้นที่เก็บข้อมูลนี้มีการใช้งานแบบสแตนด์อโลนที่ได้รับใบอนุญาต BSD สำหรับวิธีการเพิ่มประสิทธิภาพที่หลากหลาย เพื่อแก้ไขปัญหาจลนศาสตร์ผกผันทั่วไปได้อย่างมีประสิทธิภาพ
โมดูลทั้งหมดถูกนำมาใช้โดย Philipp Ruppel ซึ่งเป็นส่วนหนึ่งของวิทยานิพนธ์ระดับปริญญาโทของเขา
สำหรับการปรับใช้อัลกอริธึม "BioIK" ดั้งเดิมโดยใช้ C++ ดังที่จำหน่ายครั้งแรกในร้านค้า Unity คุณสามารถใช้โหมดที่ไม่ใช่ค่าเริ่มต้น bio1
ได้ โหมดเริ่มต้น bio2_memetic
ไม่ใช้โค้ดร่วมกับการใช้งานนี้ แสดงให้เห็นว่ามีประสิทธิภาพเหนือกว่าในแง่ของอัตราความสำเร็จ ความแม่นยำ และประสิทธิภาพ และใช้งานได้จริงกับการใช้งานหุ่นยนต์ที่แม่นยำ [4]
คุณจะต้องใช้ ROS เวอร์ชัน Indigo หรือใหม่กว่า (wiki.ros.org) ซอฟต์แวร์นี้ได้รับการพัฒนาบน Ubuntu Linux 16.04 LTS พร้อม ROS Kinetic แต่ยังได้รับการทดสอบบน Ubuntu Linux 14.04 LTS พร้อม ROS Indigo ROS เวอร์ชันใหม่กว่าควรใช้งานได้ แต่อาจต้องมีการปรับเปลี่ยนบ้าง ดูด้านล่างสำหรับคำแนะนำเฉพาะเวอร์ชัน
ดาวน์โหลดแพ็คเกจ bio_ik
และแกะลงในพื้นที่ทำงาน catkin ของคุณ
เรียกใช้ catkin_make
เพื่อรวบรวมพื้นที่ทำงานของคุณ:
roscd
cd src
git clone https://github.com/TAMS-Group/bio_ik.git
roscd
catkin_make
กำหนดค่า Moveit เพื่อใช้ bio_ik เป็นตัวแก้ปัญหาจลนศาสตร์ (ดูหัวข้อถัดไป)
ใช้ Moveit เพื่อวางแผนและดำเนินการเคลื่อนไหวหรือใช้รหัสของคุณเองร่วมกับโหนด move_group
เพื่อย้ายหุ่นยนต์ของคุณ
ตามปกติ API สาธารณะจะถูกระบุในไฟล์ส่วนหัวสาธารณะสำหรับแพ็คเกจ bio_ik
ซึ่งอยู่ในไดเรกทอรี include/bio_ik
แหล่งที่มารวมถึงไฟล์ส่วนหัวส่วนตัวบางไฟล์อยู่ในไดเรกทอรีย่อย src
เพื่อความสะดวกในการใช้งานและเข้ากันได้กับโค้ดที่มีอยู่ อัลกอริธึม bio_ik จึงถูกห่อหุ้มเป็นปลั๊กอิน Moveit kinematics ดังนั้น bio_ik จึงสามารถนำมาใช้แทนตัวแก้ปัญหา IK ที่ใช้ Orocos/KDL ที่เป็นค่าเริ่มต้นได้โดยตรง ด้วยชื่อของเอนด์เอฟเฟกต์และท่าทางเป้าหมาย 6-DOF bio_ik จะค้นหาการกำหนดค่าข้อต่อหุ่นยนต์ที่ถูกต้องซึ่งไปถึงเป้าหมายที่กำหนด
ในการทดสอบของเรา (ดูด้านล่าง) ทั้งในแง่ของอัตราความสำเร็จและเวลาในการแก้ปัญหา bio_ik มีประสิทธิภาพเหนือกว่าตัวแก้ปัญหา Orocos [1] เป็นประจำ และสามารถแข่งขันกับ trac-ik [2] ได้ อัลกอริธึม bio_ik ยังสามารถใช้กับระบบ DOF สูง เช่น หุ่นยนต์งู และอัลกอริธึมจะรวมเข้ากับโซลูชันโดยประมาณที่ดีที่สุดสำหรับแขน DOF ต่ำ ซึ่งท่าโพสบางท่าไม่สามารถเข้าถึงได้อย่างแน่นอน
แม้ว่าคุณจะสามารถเขียนไฟล์การกำหนดค่า Moveit ด้วยมือได้ แต่วิธีที่ง่ายที่สุดคือการเรียกใช้ผู้ช่วยการตั้งค่า Moveit สำหรับหุ่นยนต์ของคุณ จากนั้นเลือก bio_ik เป็นตัวแก้ปัญหา IK เมื่อกำหนดค่าเอนด์เอฟเฟกต์ เมื่อกำหนดค่าแล้ว คุณสามารถเรียกใช้ตัวแก้ปัญหาได้โดยใช้ Moveit API มาตรฐาน หรือใช้แบบโต้ตอบจาก rviz โดยใช้ปลั๊กอิน MotionPlanning GUI
ตรวจสอบให้แน่ใจว่าคุณมีโมเดล URDF (หรือ xacro) สำหรับหุ่นยนต์ของคุณ
เรียกใช้ตัวช่วยการตั้งค่า moveit เพื่อสร้างไฟล์การกำหนดค่า Moveit:
rosrun moveit_setup_assistant moveit_setup_assistant
ผู้ช่วยการตั้งค่าจะค้นหาปลั๊กอินตัวแก้ปัญหา IK ที่มีอยู่ทั้งหมดในพื้นที่ทำงานของคุณโดยอัตโนมัติ ดังนั้น คุณสามารถเลือก bio_ik เป็นตัวแก้ปัญหา IK จากรายการแบบเลื่อนลงสำหรับเอนด์เอฟเฟกต์ทุกตัว จากนั้นกำหนดค่าพารามิเตอร์จลนศาสตร์ ซึ่งได้แก่ ความแม่นยำของตำแหน่งเริ่มต้น (เมตร) และการหมดเวลา (เป็นวินาที) สำหรับแขน 6-DOF หรือ 7-DOF ทั่วไป ความแม่นยำ 0.001 ม. (หรือน้อยกว่า) และระยะหมดเวลา 1 มิลลิวินาทีน่าจะใช้ได้ โรบ็อตที่ซับซ้อนมากขึ้นอาจต้องใช้เวลาหมดเวลานานขึ้น
สร้างไฟล์การกำหนดค่า 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 ควรแสดงเครื่องหมายโต้ตอบ 6-D (ตำแหน่งและการวางแนว) สำหรับเอฟเฟกต์ปลายที่เลือก ย้ายเครื่องหมายโต้ตอบและดูการคำนวณ bio_ik สำหรับหุ่นยนต์ของคุณ
หากคุณติดตั้งการสาธิต bio_ik ด้วย (ดูด้านล่าง) คุณควรจะสามารถเรียกใช้หนึ่งในการสาธิตที่กำหนดไว้ล่วงหน้าได้:
roslaunch pr2_bioik_moveit demo.launch
roslaunch pr2_bioik_moveit valve.launch
roslaunch pr2_bioik_moveit dance.launch
ตอนนี้คุณพร้อมที่จะใช้ bio_ik จากโปรแกรม C/C++ และ Python โดยใช้ Moveit API มาตรฐานแล้ว หากต้องการขอโซลูชัน IK อย่างชัดเจนใน C ++:
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 งานดังกล่าวจะถูกระบุเป็นการรวมกันของหลาย เป้าหมาย
จากนั้นอัลกอริธึมจะพยายามค้นหาการกำหนดค่าหุ่นยนต์ที่ตอบสนองเป้าหมายที่กำหนดทั้งหมดพร้อมกันโดยการลดฟังก์ชันข้อผิดพลาดกำลังสองที่สร้างจากเป้าหมายแต่ละเป้าหมายที่ถ่วงน้ำหนักให้เหลือน้อยที่สุด แม้ว่า Moveit API ปัจจุบันไม่รองรับงานหลายเป้าหมายโดยตรง แต่ก็มีคลาส KinematicQueryOptions ดังนั้น bio_ik เพียงจัดเตรียมชุดของเป้าหมายการเคลื่อนไหวที่กำหนดไว้ล่วงหน้า และการรวมกันของเป้าหมายที่ผู้ใช้ระบุจะถูกส่งผ่าน Moveit ไปยังตัวแก้ปัญหา IK ไม่จำเป็นต้องเปลี่ยนแปลง API ใน Moveit แต่การใช้ IK Solver ในตอนนี้ประกอบด้วยการส่งผ่านเป้าหมายแบบถ่วงน้ำหนักผ่าน 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 ใช้เครื่องมือเพิ่มประสิทธิภาพส่วนกลางของ memetic ( bio2_memetic
) สามารถเลือกคลาสตัวแก้ปัญหาที่แตกต่างกันได้โดยการตั้งค่าพารามิเตอร์ mode
ในไฟล์ kinematics.yaml
ของการกำหนดค่าหุ่นยนต์ MoveIt ของคุณ
ตัวอย่าง:
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 ของพื้นที่ร่วมให้ใกล้เคียงที่สุดกับการกำหนดค่า Robot Seed ที่กำหนด โดยทั่วไป คุณจะใช้น้ำหนักที่สูงสำหรับ PoseGoal และน้ำหนักที่น้อยกว่าสำหรับเครื่องทำให้สม่ำเสมอ
คุณยังสามารถเพิ่ม MinimalDisplacementGoal แทน RegularizationGoal ได้ เป้าหมายทั้งสองพยายามที่จะให้โซลูชัน IK ใกล้เคียงกับสถานะหุ่นยนต์ปัจจุบัน/เมล็ดพันธุ์ แต่จะแตกต่างกันเล็กน้อยในการจัดการข้อต่อหุ่นยนต์ที่เร็วและช้า (เช่น PR2 มีข้อต่อแขนที่รวดเร็วและข้อต่อยกลำตัวค่อนข้างช้า) คุณอาจต้องการเล่นกับทั้งสองประตูเพื่อดูว่าประตูไหนตรงกับความต้องการของคุณมากกว่า
ตัวควบคุมหุ่นยนต์อุตสาหกรรมบางตัวบนแขน 7-DOF ทำงานเหมือนกับทำงานบนแขน 6-DOF โดยมีข้อต่อพิเศษเพียงข้อเดียว โดยปกติแล้ว สามารถระบุค่าของข้อต่อพิเศษได้ จากนั้นจึงค้นหาสารละลาย IK สำหรับข้อต่อที่เหลืออีก 6 ข้อ พฤติกรรมนี้สามารถทำได้ใน bio_ik โดยการรวม PoseGoal สำหรับเอนด์เอฟเฟกต์กับ JointPositionGoal สำหรับข้อต่อหุ่นยนต์หนึ่ง (อันใดอันหนึ่ง)
เคล็ดลับที่มีประโยชน์อีกประการหนึ่งคือการพยายามรักษาข้อต่อของหุ่นยนต์ให้อยู่ตรงกลาง เนื่องจากจะทำให้หุ่นยนต์ (ข้อต่อ) เคลื่อนไหวได้ทั้งสองทิศทาง เพียงรวม PoseGoal กับ CenterJointsGoal และอาจเลือกเป็น RegularizationGaol ก็ได้
คุณยังสามารถรวมการทำให้เป็นมาตรฐานเข้ากับตัวแก้ปัญหา gd_*
ในเครื่องได้
ตัวแก้ปัญหา bio_ik ขึ้นอยู่กับอัลกอริธึมมีมที่รวมการปรับให้เหมาะสมตามการไล่ระดับสีเข้ากับการปรับให้เหมาะสมทางพันธุกรรมและกลุ่มอนุภาค
ภายใน เวกเตอร์ของค่าข้อต่อหุ่นยนต์ทั้งหมดถูกใช้เพื่อเข้ารหัสโซลูชันระดับกลางที่แตกต่างกัน ( จีโนไทป์ ของอัลกอริทึมทางพันธุกรรม) ในระหว่างการปรับให้เหมาะสม ค่าข้อต่อจะถูกตรวจสอบกับขีดจำกัดข้อต่อล่างและบนที่ใช้งานอยู่เสมอ เพื่อให้สร้างเฉพาะการกำหนดค่าหุ่นยนต์ที่ถูกต้องเท่านั้น
ในการคำนวณความเหมาะสมของแต่ละบุคคล จะมีการคำนวณข้อผิดพลาดสะสมจากเป้าหมายแต่ละอย่างที่ได้รับทั้งหมด บุคคลใดๆ ที่ไม่มีข้อผิดพลาดคือวิธีแก้ปัญหา IK ที่แน่นอน ในขณะที่บุคคลใดๆ ที่มีข้อผิดพลาดเล็กน้อยจะสอดคล้องกับวิธีแก้ปัญหาโดยประมาณ
บุคคลจะถูกจัดเรียงตามความเหมาะสมของพวกเขา และมีการลองใช้การปรับให้เหมาะสมตามการไล่ระดับสีกับการกำหนดค่าที่ดีที่สุด ทำให้เกิดการบรรจบกันอย่างรวดเร็วและประสิทธิภาพที่ดีสำหรับปัญหาต่างๆ มากมาย หากไม่พบวิธีแก้ปัญหาจากการเพิ่มประสิทธิภาพตามการไล่ระดับสี บุคคลใหม่จะถูกสร้างขึ้นโดยชุดของตัวดำเนินการการกลายพันธุ์และการรวมตัวกันใหม่ ส่งผลให้มีการสำรวจพื้นที่การค้นหาที่ดี
ดู [3] และ [4] สำหรับรายละเอียดเพิ่มเติม ดู [5] และ [6] สำหรับคำอธิบายเชิงลึกของอัลกอริธึมวิวัฒนาการก่อนหน้านี้สำหรับการสร้างแอนิเมชั่นตัวละครในวิดีโอเกม
เราได้ทดสอบ bio_ik บนแขนหุ่นยนต์ต่างๆ มากมาย ทั้งโดยใช้ API เอฟเฟกต์ปลายเดี่ยวแบบดั้งเดิมและ API เอฟเฟกต์ปลายหลายขั้นสูงที่อิงตาม KinematicsQueryOptions
การทดสอบตัวเองอย่างง่ายอย่างหนึ่งประกอบด้วยการสร้างการกำหนดค่าหุ่นยนต์ที่ถูกต้องแบบสุ่ม การรันจลนศาสตร์ไปข้างหน้าเพื่อคำนวณผลลัพธ์ของท่าทางเอฟเฟกต์ปลาย และการสืบค้นปลั๊กอิน IK เพื่อค้นหาการกำหนดค่าข้อต่อหุ่นยนต์ที่เหมาะสม จากนั้นตรวจสอบความสำเร็จโดยการรันจลนศาสตร์ไปข้างหน้าอีกครั้ง และตรวจสอบว่าท่าเอนด์เอฟเฟกต์สำหรับโซลูชัน IK ที่สร้างขึ้นตรงกับท่าเป้าหมาย วิธีการนี้สามารถดำเนินการได้อย่างง่ายดายสำหรับท่าสุ่มนับพันหรือหลายล้านท่า สุ่มตัวอย่างพื้นที่ทำงานทั้งหมดของหุ่นยนต์ และช่วยให้สร้างอัตราความสำเร็จและเวลาประมาณการวิธีแก้ปัญหาสำหรับตัวแก้ IK ที่เลือกได้อย่างรวดเร็ว
แน่นอนว่า การรันการทดสอบจำเป็นต้องติดตั้งโมเดลหุ่นยนต์ที่เกี่ยวข้องและเพิ่มการพึ่งพาจำนวนมาก ดังนั้นการทดสอบเหล่านั้นจึงไม่รวมอยู่ในแพ็คเกจ bio_ik มาตรฐาน แต่จะบรรจุแยกกัน
เพื่อความสะดวก เราได้จัดเตรียมแพ็คเกจ pr2_bioik_moveit
ซึ่งรวมถึงการสาธิต bio_ik บางส่วนสำหรับหุ่นยนต์บริการ PR2 ด้วย นี่เป็นการสาธิตจลนศาสตร์เท่านั้น แต่แน่นอน คุณสามารถลองใช้การสาธิตบนหุ่นยนต์จริง (ถ้าคุณมี) หรือเครื่องจำลอง 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 Humanoids Conference กรุงโซล เกาหลี พฤศจิกายน 2558
Philipp Ruppel, Norman Hendrich, Sebastian Starke, Jianwei Zhang, Cost Functions to Specify Full-Body Motion and Multi-Goal Manipulation Tasks , การประชุมนานาชาติ IEEE เรื่องวิทยาการหุ่นยนต์และระบบอัตโนมัติ (ICRA-2018), บริสเบน, ออสเตรเลีย ดอย: 10.1109/ICRA.2018.8460799
Philipp Ruppel, การเพิ่มประสิทธิภาพการทำงานและการนำจลนศาสตร์ผกผันเชิงวิวัฒนาการไปใช้ใน ROS , วิทยานิพนธ์ MSc, มหาวิทยาลัยฮัมบูร์ก, 2017 PDF
เซบาสเตียน สตาร์ค, นอร์แมน เฮนดริช, เจียนเว่ย จาง, อัลกอริธึมวิวัฒนาการมีมสำหรับการเคลื่อนไหวทางจลนศาสตร์แบบเรียลไทม์ , สนามบินนานาชาติ IEEE Congress on Evolutionary Computation (CEC-2017), p.2437-2479, 4-8 มิถุนายน 2017, ซานเซบาสเตียน, สเปน ดอย: 10.1109/CEC.2017.7969605
เซบาสเตียน สตาร์ค, นอร์แมน เฮนดริช, เดนนิส ครุปเกะ, เจียนเว่ย จาง, การเพิ่มประสิทธิภาพเชิงวิวัฒนาการแบบหลายวัตถุประสงค์สำหรับจลน์ศาสตร์แบบผกผันของหุ่นยนต์ที่มีข้อต่อสูงและหุ่นยนต์คล้ายมนุษย์ นานาชาติ IEEE การประชุมเรื่องหุ่นยนต์และระบบอัจฉริยะ (IROS-2017) 24-28 กันยายน 2560 แวนคูเวอร์ แคนาดา