يوفر هذا المستودع تطبيقًا مستقلاً مرخصًا من BSD لمجموعة متنوعة من أساليب التحسين لحل مشكلات الحركية العكسية المعممة بكفاءة.
تم تنفيذ الوحدة بأكملها بواسطة فيليب روبل كجزء من رسالة الماجستير الخاصة به.
لإعادة تنفيذ خوارزمية "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
لتحريك الروبوت الخاص بك.
كالعادة، يتم تحديد واجهة برمجة التطبيقات العامة في ملفات الرأس العامة لحزمة bio_ik
، الموجودة في الدليل الفرعي include/bio_ik
؛ المصادر بما في ذلك بعض ملفات الرأس الخاصة موجودة في الدليل الفرعي src
.
لسهولة الاستخدام والتوافق مع التعليمات البرمجية الموجودة، تم تغليف خوارزمية bio_ik كمكون إضافي لعلم الحركة الحركية لـ Moveit. ولذلك، يمكن استخدام 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 القياسية أو استخدامه بشكل تفاعلي من rviz باستخدام البرنامج الإضافي MotionPlanning GUI.
تأكد من أن لديك نموذج URDF (أو xacro) للروبوت الخاص بك.
قم بتشغيل مساعد إعداد moveit لإنشاء ملفات تكوين Moveit:
rosrun moveit_setup_assistant moveit_setup_assistant
يقوم مساعد الإعداد تلقائيًا بالبحث عن جميع المكونات الإضافية المتوفرة لـ IK Solver في مساحة العمل الخاصة بك. لذلك، يمكنك فقط تحديد 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 علامة تفاعلية ثلاثية الأبعاد (الموضع والاتجاه) للمؤثر (المؤثرين) النهائي المحدد. قم بتحريك العلامة التفاعلية وشاهد وضعيات حساب 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 القياسية. لطلب حل 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 الحالية لا تدعم المهام متعددة الأهداف بشكل مباشر، إلا أنها توفر فئة KinematicQueryOptions. لذلك، يوفر bio_ik ببساطة مجموعة من أهداف الحركة المحددة مسبقًا، ويتم تمرير مجموعة من الأهداف المحددة بواسطة المستخدم عبر Moveit إلى حل IK. ليست هناك حاجة إلى تغييرات في واجهة برمجة التطبيقات (API) في Moveit، ولكن استخدام حل 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 مُحسِّنًا عالميًا 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 للمساحة المشتركة أقرب ما يمكن إلى التكوين الأولي للروبوت المحدد. عادةً ما تستخدم وزنًا مرتفعًا لـ PoseGoal ووزنًا أصغر لجهاز التنظيم.
يمكنك أيضًا إضافة MinimalDisplacementGoal بدلاً من RegularizationGoal . يحاول كلا الهدفين إبقاء حل IK قريبًا من حالة الروبوت الحالي/البذور، لكنهما يختلفان قليلاً في التعامل مع مفاصل الروبوت السريعة والبطيئة (على سبيل المثال، يحتوي PR2 على مفاصل ذراع سريعة ومفصل رفع الجذع بطيء نوعًا ما). قد ترغب في اللعب بكلا الهدفين لمعرفة أيهما يناسب احتياجاتك بشكل أفضل.
تتصرف بعض وحدات التحكم في الروبوتات الصناعية الموجودة على أذرع 7-DOF كما لو كانت تعمل على ذراع 6-DOF بمفصل إضافي واحد. عادة، يمكن تحديد قيمة المفصل الإضافي، ثم يتم البحث عن حل IK للمفاصل الستة المتبقية. يمكن تحقيق هذا السلوك في bio_ik من خلال الجمع بين PoseGoal للمؤثر النهائي و JointPositionGoal لواحد (أي واحد) من مفاصل الروبوت.
هناك خدعة أخرى مفيدة وهي محاولة إبقاء مفاصل الروبوت في المنتصف، حيث سيسمح ذلك بحركات الروبوت (المفصل) في كلا الاتجاهين. ما عليك سوى دمج PoseGoal مع CenterJointsGoal ، واختياريًا أيضًا RegularizationGaol .
يمكنك أيضًا الجمع بين التنظيم ومحلل gd_*
المحلي.
يعتمد حل bio_ik على خوارزمية ميمي تجمع بين التحسين القائم على التدرج والتحسين الجيني وسرب الجسيمات.
داخليًا، يتم استخدام نواقل جميع القيم المشتركة للروبوت لتشفير الحلول الوسيطة المختلفة ( النمط الجيني للخوارزمية الجينية). أثناء عملية التحسين، يتم دائمًا التحقق من قيم المفاصل مقابل حدود المفصل السفلية والعليا النشطة، بحيث يتم إنشاء تكوينات الروبوت الصالحة فقط.
لحساب اللياقة البدنية للأفراد، يتم حساب الخطأ التراكمي على جميع الأهداف الفردية المحددة. أي فرد لديه خطأ صفر هو الحل الدقيق لمشكلة IK، في حين أن الأفراد الذين لديهم خطأ بسيط يتوافقون مع الحلول التقريبية.
يتم فرز الأفراد حسب لياقتهم البدنية، ويتم تجربة التحسين القائم على التدرج على أفضل التكوينات القليلة، مما يؤدي إلى تقارب سريع وأداء جيد للعديد من المشكلات. إذا لم يتم العثور على حل من التحسين القائم على التدرج، فسيتم إنشاء أفراد جدد بواسطة مجموعة من عوامل الطفرة وإعادة التركيب، مما يؤدي إلى استكشاف جيد لمساحة البحث.
انظر [3] و[4] لمزيد من التفاصيل. راجع [5] و[6] للحصول على شرح متعمق لخوارزمية تطورية سابقة لتحريك شخصيات ألعاب الفيديو.
لقد اختبرنا bio_ik على العديد من أذرع الروبوتات المختلفة، وكلاهما يستخدم واجهة برمجة التطبيقات ذات المؤثر النهائي التقليدي وواجهة برمجة التطبيقات ذات المؤثر النهائي المتعدد المتقدمة المستندة إلى 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 and B. Ames, TRAC-IK: مكتبة مفتوحة المصدر لتحسين حل الحركية العكسية العامة ، وقائع مؤتمر IEEE RAS Humanoids، سيول، كوريا، نوفمبر 2015.
فيليب روبل، نورمان هندريش، سيباستيان ستارك، جيانوي تشانغ، وظائف التكلفة لتحديد حركة الجسم بالكامل ومهام التلاعب متعدد الأهداف ، مؤتمر IEEE الدولي حول الروبوتات والأتمتة، (ICRA-2018)، بريسبان، أستراليا. DOI: 10.1109/ICRA.2018.8460799
فيليب روبل، تحسين الأداء وتنفيذ الكينماتيكا العكسية التطورية في ROS ، رسالة ماجستير، جامعة هامبورغ، 2017 PDF
سيباستيان ستارك، نورمان هندريش، جيانوي تشانغ، خوارزمية تطورية ميميتيكية للحركة الحركية المفصلية في الوقت الفعلي ، IEEE Intl. مؤتمر الحساب التطوري (CEC-2017)، الصفحات 2437-2479، 4-8 يونيو 2017، سان سيباستيان، إسبانيا. دوى: 10.1109/CEC.2017.7969605
سيباستيان ستارك، نورمان هندريش، دينيس كروبكي، جيانوي تشانغ، التحسين التطوري متعدد الأهداف للحركيات العكسية على الروبوتات المفصلية للغاية والروبوتات الشبيهة بالبشر ، IEEE Intl. مؤتمر الروبوتات والأنظمة الذكية (IROS-2017)، 24-28 سبتمبر 2017، فانكوفر، كندا