مقدمة
إن برامج المحاكاة هي أداة أساسية لكل شخص مهتم بالروبوتات، فوجود المحاكي يسرع عملية تطور الخوارزميات وتجريبها من دون خوف من حصول مشاكل في الأنظمة الفرعية للروبوت، على سبيل المثال حدوث عطل في أحد محركات الروبوت أو الانتظار لشحن البطاريات المستخدمة داخل الروبوت. في هذا المقال سنلقي نظرة على أحد برامج المحاكاة في بيئة تطوير الروبوتات ROS وهو المحاكي Gazebo و سنشرح كيفية صنع يد روبوتية وإضافتها له. للتعرف عن بيئة تطوير الروبوتات ROS راجع المقالة المنشورة سابقاً برمجة الروبوتات باستخدام نظام تشغيل الروبوت ROS: مقدمة.
مدخل إلى المحاكي Gazebo
هو أحد برامج المحاكاة ثلاثية الأبعاد المستخدمة في ROS، يوفر Gazebo خيارات أختيار المحرك الفيزيائي مع كون المحرك الافتراضي هو Open dynamics engine، ومن مميزاته انك تستطيع محاكاة الحساسات بالإضافة للديناميك أيضاً. يتألف Gazebo من قسمين:- Server (gzserver) الخادم
- Client (gzclient) العميل
يستخدم العميل gzclient من أجل إظهار الرسوم ولكن نستطيع استخدام المحاكي بدون الواجهة الرسومية عن طريق تشغيل gzserver فقط.
لاستخدام Gazebo مع ROS نستطيع استخدام حزمة (package) أسمها gazebo_ros. راجع كيفية تنزيل الحزمة.
لتشغيل المحاكي مع النموذج الافتراضي نستخدم الأمر التالي:
roslaunch gazebo_ros empty_world.launch
هذا الأمر سوف يقوم بتشغيل gzserver و gzclient
شرح الواجهة
- توقيف المحاكي أو إعادة تشغيله بعد توقيفه
- Real Time Factor يوضح كفاءة المحاكي يعني لو كانت القيمة 0.25 هذا يعني أن المحاكي يحتاج 4 ثواني ليحاكي 1 ثانية في أرض الواقع.
- الوقت الذي حاكاه المحاكي غالبا أقل من Real Time بسبب Real Time Factor.
- الوقت الحقيقي الذي أشتغل فيه المحاكي.
- عدد المرات التي تم أستدعاء المحلل (LCP solver).
- عدد الاطارات في الثانية (Frame Per Second).
- إعادة تعيين Sim Time, Real Time, Iterations للصفر.
- تحتوي على خصائص العالم الذي نحاكيه على سبيل المثال نستطيع تغيير الجاذبية بالضغط على Physics بعد ذلك تغيير قيمة gravity.
- تستخدم لإدراج شيء جديد على سبيل المثال قمت بإدراج iRobot Create كما في الصورة التالية:
الأن بعد أن قمنا بشرح بسيط للمحاكي سنقوم بصناعة يد روبوتية وإدراجها داخل المحاكي.
بناء يد روبوتية من الصفر
قبل البدء ببناء اليد الروبوتية سنلقي نظرة سريعة على توزيعة الملفات
أولاً سنقوم بإنشاء ملف باسم الروبوت وبداخل الملف سننشئ ثلاث حزم
- robot_name_description هي الحزمة التي سنضع بداخلها الملفات المتعلقة بتصميم الروبوت.
- robot_name_gazebo هي الحزمة التي سنضع بداخلها الملفات المتعلقة بالمحاكي Gazebo.
- robot_name_control هي الحزمة التي سنضع بداخلها الملفات المتعلقة بالمتحكمات المستخدم في الروبوت.
ملف وصف الروبوت URDF
لكن قبل البدء بكتابة الملف سأشرح هذه الصيغة قليلاً Universal Robotic Description Format (URDF)سنبدأ بناء الروبوت بإنشاء ملف الــURDF وهو صيغة XML المستخدمة في نظام ROS لوصف كل مكونات الروبوت, الروبوت في هذه الصيغة يتألف من ( المربط )Link و (المفصل) Joint.
المفصل يوصل مربطين معاً والمربط يوصل مفصلين معاً وكلاهما يشكلان سلسلة (chain). شكل تعريف المفصل هو كالتالي، كما يوجد عناصر أخرى للمزيد يمكن الاطلاع عليها في الويكي الرسمي للمشروع.
<joint name="اسم المفصل" type="نوع المفصل"> <parent link="اسم المربط الأم"/> <child link="اسم المربط الابن"/> <origin xyz="مركز المفصل بالنسبة لأطار المربط الأم" rpy=" فرق الزاوية بين إطار المفصل وإطار المربط الأم"/> <axis xyz="محور الدوران"/> <dynamics damping="معامل التخميد الديناميكي"/> </joint>
سنعرف ثلاث عناصر للمربط
- visual :تعرف المزايا الظاهرية للمربط هنا استخدمنا الشكل Box يوجد اشكال اخرى مثال اسطوانة أو كرة
- collision :تعرف مزايا الاصطدام للمربط بشكل عام(ليس دائما) هي مماثلة للعنصر visual
- inertial :تعرف المزايا الديناميكية للمربط للمزيد عن مصفوفة عزم العطالة في صفحة الويكيبيديا عن عزم العطالة.
إن القانون بالنسبة للشكل الذي استخدمناه هو:
<link name="اسم المربط"> <collision> <origin xyz="مركز المربط بالنسبة لإطار المفصل الذي يكون هذا المربط ابن بالنسبة له" rpy="فرق الزاوية بين إطار المفصل و إطار هذا المربط"/> <geometry> <box size="أبعاد الشكل"/> </geometry> </collision> <visual> <origin xyz="مركز المربط بالنسبة لإطار المفصل الذي يكون هذا المربط أبن بالنسبة له" rpy="فرق الزاوية بين إطار المفصل و إطار هذا المربط"/> <geometry> <box size="أبعاد الشكل"/> </geometry> </visual> <inertial> <origin xyz="مركز المربط بالنسبة لإطار المفصل والذي سنقوم بكتابة مصفوفة عزم العطالة" rpy="فرق الزواية"/> <mass value="الكتلة"/> <inertia ixx="عناصر مصفوفة عزم العطالة" ixy="عناصر مصفوفة عزم العطالة" ixz="عناصر مصفوفة عزم العطالة" iyy="عناصر مصفوفة عزم العطالة" iyz="عناصر مصفوفة عزم العطالة" izz="عناصر مصفوفة عزم العطالة"/> </inertial> </link>
الروبوت الذي سنقوم بإنشائه اسمه [1] elbow arm وهو يتألف من ثلاث Joint وأربع Link (مع القاعدة) كما موضح في الصورة التالية:
أولا إذهب للملف المخصّص للحزم في حالتنا وقم بإنشاء ملف باسم الروبوت elbow_arm وادخل إلى الملف
cd ~/catkin_ws/src mkdir elbow_arm && cd elbow_arm
بعد ذلك قم بإنشاء حزمة باسم elbow_arm_description
catkin_create_pkg elbow_arm_description
داخل الحزمة انشئ ملف باسم urdf وبداخل هذا الملف مستند باسم elbow_arm_description.urdf تستطيع استخدامأي محرر شخصياً استخدمت sublime ثم قم بلصق الكود فيه
cd elbow_arm_description && mkdir urdf && cd urdf subl elbow_arm.xacro
ملاحظة: أنشأنا الملف بصيغة xacro وليس urdf السبب هو أن هذه الصيغة ستسهل علينا كتابة الملف لانها تسمح لنا بإنشاء ثوابت وتقوم بحسابات رياضية بسيطة.
<?xml version="1.0"?> <!-- Elbow Arm --> <robot name="elbow_arm" xmlns:xacro="http://www.ros.org/wiki/xacro"> <!-- Constants for robot dimensions --> <xacro:property name="mass" value="1" /> <!-- arbitrary value for mass --> <xacro:property name="width" value="0.1" /> <!-- Square dimensions (widthxwidth) of beams --> <xacro:property name="height1" value="1.5" /> <!-- Link 1 --> <xacro:property name="height2" value="1" /> <!-- Link 2 --> <xacro:property name="height3" value="1" /> <!-- Link 3 --> <xacro:property name="axel_offset" value="0.05" /> <!-- Space btw top of beam and the each joint --> <!-- Used for fixing robot to Gazebo 'base_link' --> <link name="world"/> <joint name="joint1" type="continuous"> <parent link="world"/> <child link="link1"/> <origin xyz="0 0 0" rpy="0 0 0"/> <axis xyz="0 0 1"/> <dynamics damping="0.7"/> </joint> <!-- Base Link --> <link name="link1"> <collision> <origin xyz="0 0 ${height1/2}" rpy="0 0 0"/> <geometry> <box size="${width} ${width} ${height1}"/> </geometry> </collision> <visual> <origin xyz="0 0 ${height1/2}" rpy="0 0 0"/> <geometry> <box size="${width} ${width} ${height1}"/> </geometry> </visual> <inertial> <origin xyz="0 0 ${height1/2}" rpy="0 0 0"/> <mass value="${mass}"/> <inertia ixx="${mass / 12.0 * (width*width + height1*height1)}" ixy="0.0" ixz="0.0" iyy="${mass / 12.0 * (height1*height1 + width*width)}" iyz="0.0" izz="${mass / 12.0 * (width*width + width*width)}"/> </inertial> </link> <joint name="joint2" type="continuous"> <parent link="link1"/> <child link="link2"/> <origin xyz="0 ${width} ${height1 - axel_offset}" rpy="0 0 0"/> <axis xyz="0 1 0"/> <dynamics damping="0.7"/> </joint> <!-- Middle Link --> <link name="link2"> <collision> <origin xyz="0 0 ${height2/2 - axel_offset}" rpy="0 0 0"/> <geometry> <box size="${width} ${width} ${height2}"/> </geometry> </collision> <visual> <origin xyz="0 0 ${height2/2 - axel_offset}" rpy="0 0 0"/> <geometry> <box size="${width} ${width} ${height2}"/> </geometry> </visual> <inertial> <origin xyz="0 0 ${height2/2 - axel_offset}" rpy="0 0 0"/> <mass value="${mass}"/> <inertia ixx="${mass / 12.0 * (width*width + height2*height2)}" ixy="0.0" ixz="0.0" iyy="${mass / 12.0 * (height2*height2 + width*width)}" iyz="0.0" izz="${mass / 12.0 * (width*width + width*width)}"/> </inertial> </link> <joint name="joint3" type="continuous"> <parent link="link2"/> <child link="link3"/> <origin xyz="0 ${width} ${height2 - axel_offset*2}" rpy="0 0 0"/> <axis xyz="0 1 0"/> <dynamics damping="0.7"/> </joint> <!-- Top Link --> <link name="link3"> <collision> <origin xyz="0 0 ${height3/2 - axel_offset}" rpy="0 0 0"/> <geometry> <box size="${width} ${width} ${height3}"/> </geometry> </collision> <visual> <origin xyz="0 0 ${height3/2 - axel_offset}" rpy="0 0 0"/> <geometry> <box size="${width} ${width} ${height3}"/> </geometry> </visual> <inertial> <origin xyz="0 0 ${height3/2 - axel_offset}" rpy="0 0 0"/> <mass value="${mass}"/> <inertia ixx="${mass / 12.0 * (width*width + height3*height3)}" ixy="0.0" ixz="0.0" iyy="${mass / 12.0 * (height3*height3 + width*width)}" iyz="0.0" izz="${mass / 12.0 * (width*width + width*width)}"/> </inertial> </link> </robot>
ملاحظات حول الكود أعلاه:
- السطر التالي لتعريف الروبوت وإعطائه أسم هنا elbow_arm
<robot name="أسم الروبوت" xmlns:xacro="http://www.ros.org/wiki/xacro">
- طريقة تعريف ثابت في ملف xacro
<xacro:property name="أسم الثابت" value="القيمة" />
- الشعار التالي {تعبير رياضي}$ يعني تنفيذ التعبير الرياضي داخل القوسين مثال:
<origin xyz="0 0 ${height1/2}" rpy="0 0 0"/>
وتعني عوض قيمة التعبير الرياضي بالتالي، وهي مماثلة للسطر التالي:
<origin xyz="0 0 0.5" rpy="0 0 0"/>
ولكي نقوم بإضافة الروبوت للمحاكي سنقوم بإنشاء حزمة بإسم elbow_arm_gazebo داخل الملف elbow_arm ونقوم بإنشاء ملف launch داخل هذه الحزمة
catkin_create_pkg elbow_arm_gazebo cd elbow_arm_gazebo mkdir launch
داخل هذا الملف أنشأ ملف بإسم elbow_arm_world.launch
subl launch/elbow_arm_world.launch
ثم قم بلصق النص التالي بداخله. الملف التالي سيقوم بتشغيل المحاكي وإضافة الروبوت إليه
<launch> <!-- these are the arguments you can pass this launch file, for example paused:=true --> <arg name="paused" default="false"/> <arg name="use_sim_time" default="true"/> <arg name="gui" default="true"/> <arg name="headless" default="false"/> <arg name="debug" default="false"/> <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched --> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <!--arg name="world_name" value="$(find elbow_arm_gazebo)/worlds/elbow_arm.world"/--> <arg name="debug" value="$(arg debug)" /> <arg name="gui" value="$(arg gui)" /> <arg name="paused" value="$(arg paused)"/> <arg name="use_sim_time" value="$(arg use_sim_time)"/> <arg name="headless" value="$(arg headless)"/> </include> <!-- Load the URDF into the ROS Parameter Server --> <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find elbow_arm_description)/urdf/elbow_arm.xacro'"/> <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot --> <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -model elbow_arm -param robot_description"/> </launch>
ملف launch يستخدم لبدء عدة برامج وضبط بعض المعامل (Parameter) ولكنه يحتاح درس بحد ذاته لذلك سأكتفي بشرح سطحي وفي مقال أخر سأقوم بشرحه
الأن لكي تقوم بتشغيل الروبوت سنقوم بتنفيذ هذا الأمر
roslaunch elbow_arm_gazebo elbow_arm_world.launch
انتظر قليلا سيبدأ المحاكي وسترى الروبوت ولكن بعد فترة زمنية بسيطة سيسقط الروبوت لأننا لم نضيف محركات ونضيف متحكم لهم وهي خطوتنا التالية
إضافة المحرك والمتحكمات
كما هو ملاحظ الروبوت الذي بنيناه إلى الأن لا يقوم بأشياء مثيرة، ولكي نقوم بالتحكم فيه علينا أولا إضافة محرك لكل مفصل عن طريق إضافة النص التالي إلى نهاية الملف elbow_arm_description/urdf/elbow_arm.xacro
<transmission name="trans1"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint1"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="motor1"> <mechanicalReduction>1</mechanicalReduction> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </actuator> </transmission> <transmission name="trans2"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint2"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="motor2"> <mechanicalReduction>1</mechanicalReduction> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </actuator> </transmission> <transmission name="trans3"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint3"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="motor3"> <mechanicalReduction>1</mechanicalReduction> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </actuator> </transmission>
الوسم transmission يستخدم لتعريف العلاقة بين المحرك والمفصل
<transmission name="اسم جهاز نقل الحركة"> <type>transmission_interface/SimpleTransmission نوع جهاز النقل, النوع الوحيد هو</type> <joint name="اسم المفصل"> <hardwareInterface>نوع الأوامر التي سيتم إرسالها للتحكم</hardwareInterface> </joint> <actuator name="اسم المحرك"> <mechanicalReduction>1</mechanicalReduction> <hardwareInterface>نوع الأوامر التي سيتم إرسالها للتحكم</hardwareInterface> </actuator> </transmission>
العنصر hardwareInterface قد يكون :
- hardware_interface/PositionJointInterface
- hardware_interface/EffortJointInterface
- hardware_interface/VelocityJointInterface
وهي تحدد نوع الأوامر التي سيتم إرسالها. هنا قد اخترنا النوع الثاني.
الأن، إذا قمت بتشغيل المحاكي فإن الروبوت سيقع مرة أخرة؛ هذا لأننا لم نقم بعد ببناء متحكم للتحكم بالمحرك, ولحسن الحظ فإن Gazebo توفر لنا إضافة لمتحكم من نوع PID للتحكم بالمحرك لكن هذا الإضافة تحتاج لملف Configuration لكل متحكم.
قبل البدأ سنقوم بإنشاء حزمة بإسم catkin_create_pkg elbow_arm_control
catkin_create_pkg elbow_arm_control
داخل هذه الحزمة سنقوم بإنشاء ملف launch و ملف config
mkdir launch mkdir config
سنبدأ بملف الإعدادات، ويمكن قراءة المزيد عن ملف الـYAML من الويكي الرسمي.
subl config/elbow_arm_control.yaml
elbow_arm: # Publish all joint states ----------------------------------- joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 # Position Controllers --------------------------------------- joint1_position_controller: type: effort_controllers/JointPositionController joint: joint1 pid: {p: 100.0, i: 0.01, d: 10.0} joint2_position_controller: type: effort_controllers/JointPositionController joint: joint2 pid: {p: 100.0, i: 0.01, d: 10.0} joint3_position_controller: type: effort_controllers/JointPositionController joint: joint3 pid: {p: 100.0, i: 0.01, d: 10.0}
سنحتاج متحكم لكل مفصل
Joint1_position_controller: # أسم المتحكم type: effort_controllers/JointPositionController # نوع المتحكم نفس نوع المتحكم في ملف الروبوت joint: joint1 # أسم المفصل pid: {p: 100.0, i: 0.01, d: 10.0} # قيم المعامل للمتحكم, قد تحتاج لتحسين
هذا القسم يستخدم لنشر حالة المفاصل للموضوع (Topic) بإسم joint_states/
joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50
الأن سنقوم بإخبار Gazebo بتشغيل الأداة عن طريق إضافة السطور التالية إلى نهاية الملف elbow_arm_description/urdf/elbow_arm.xacro قبل </robot>
<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/elbow_arm</robotNamespace> </plugin> </gazebo>
لقد بقي لنا خطوة واحدة وسنكون قادرين على تشغيل الروبوت والتحكم فيه، وهي إنشاء ملف elbow_arm_contrtol.launch
<launch> <rosparam file="$(find elbow_arm_control)/config/elbow_arm_control.yaml" command="load"/> <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/elbow_arm" args="joint1_position_controller joint2_position_controller joint3_position_controller joint_state_controller"/> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"> <remap from="/joint_states" to="/elbow_arm/joint_states"/> </node> </launch>
لكي نقوم بتشغيل الروبوت والمتحكم كل أمر في Terminal منفصل
roslaunch elbow_arm_gazebo elbow_arm_world.launch roslaunch elbow_arm_control elbow_arm_control.launch
كما تلاحظ لن يسقط الروبوت، للتحكم بالروبوت سنقوم بإرسال ثلاث أوامر لكل محرك
rostopic pub /elbow_arm/joint1_position_controller/command std_msgs/Float64 "data: 1.0" -1 rostopic pub /elbow_arm/joint2_position_controller/command std_msgs/Float64 "data: 1.0" -1 rostopic pub /elbow_arm/joint3_position_controller/command std_msgs/Float64 "data: 1.0" -1
الخاتمة
كان هذا المقال عن المحاكي Gazebo وكيفية إنشاء يد روبوتية وإضافتها للمحاكي للتحكم فيه، ولا يقتصر المحاكي على هذه اليد، وإنما نستطيع أيضا إضافة حساسات للروبوتات أو إضافة روبوتات أكثر تعقيدا مثل Baxter أو الروبوتات البشرية(humanoid robot)، حتى إن مسابقة وكالة ناسا الأخيرة SRC كانت بإستخدام هذا المحاكي، و للسنة الثانية على التوالي مسابقة Agile تستخدمه أيضاً، وكما تم سابقاً تغطية تجربة استخدام هذا النظام لبناء نظام روبوتات متعاونة Multi-agent Robots بواسطة فريق إيليت من مصر.
المراجع
- صفحة 12 من كتاب Robot Modeling and control
- Gazebo Tutorials
- Ros Control