نحيا السداسي. الجزء الأول

في مقال سابق ، شاركنا تجربتنا في إنشاء سداسي الأرجل باستخدام تقنية الطباعة ثلاثية الأبعاد. الآن سنتحدث عن مكون البرنامج ، الذي سمح له بالإحياء.

كان من المخطط في الأصل تقديم جميع المعلومات في مقال واحد ، ولكن في عملية الكتابة أصبح من الواضح أن مثل هذا العرض سيكون سطحيًا وغير ملهم. لذلك ، تقرر كتابة العديد من المقالات مع عرض أكثر تفصيلاً للموضوع.

جهاز Hexapod


حاليا ، يتم استخدام لوحة UNO R3 مع Wi-Fi ESP8266 كوحدة تحكم رئيسية . في الواقع ، هذه اللوحة مع اثنين من وحدات التحكم على متنها ، تتفاعل مع بعضها البعض عبر واجهة UART.



على الرغم من حقيقة أن Uno لديه كمية محدودة من موارد الحوسبة ، إلا أنه يكفي لتعليم الروبوت كيفية تنفيذ الأوامر الأساسية:

  • حركة خط مستقيم بسرعة ومدة معينة
  • حركة دائرية إلى اليسار أو اليمين (بدوره)
  • خذ مواقع أطراف محددة مسبقًا

إن ESP8266 مسؤول عن تنظيم قناة الاتصال اللاسلكي ويعمل كبوابة يتلقى Uno من خلالها أوامر التحكم.

يمكن التحكم في الروبوت عن طريق الشبكة المحلية في جلسة telnet التي تم إنشاؤها معه أو عبر اتصال سلكي بوحدة التحكم (للبرامج الثابتة أو التصحيح). للراحة ، كتبنا أيضًا تطبيق Android بسيطًا يطبق الحد الأدنى من الوظائف التفاعلية للتحكم في الروبوت.



يوضح الشكل أدناه بشكل تخطيطي هيكل سداسي الأرجل.



جميع الماكينات متصلة ببطاقة توسيع Multiservo Shield ، والتي تتيح لك التحكم في 18 مؤازرة. اتصالها مع Arduino عبر حافلة I²C. لذلك ، حتى مع وجود 18 من أجهزة التوجيه في نفس الوقت ، ستظل جميع دبابيس Arduino تقريبًا مجانية.
وتجدر الإشارة إلى أن لوحة التوسيع لديها موصل لتشغيل الماكينات المتصلة. لكن الحد الأقصى المسموح به للتيار الذي تم تصميم اللوحة من أجله هو حوالي 10 أمبير ، وهو لا يكفي لتشغيل محركات سيرفو MG996R ، والتي يمكن أن يتجاوز إجمالي استهلاك التيار الأقصى لها القيمة المحددة. لذلك ، في نسختنا ، تم توصيل كل سيرفو بخط طاقة منفصل ، متجاوزًا لوحة التوسيع.

إدارة Hexapod


يتم تنفيذ منطق التحكم في الأطراف السداسية في البرنامج باستخدام فئة GeksaFoot .

فئة GeksaFoot
class GeksaFoot {
private:
//         
  Vector3D m_p0;
//          
  Vector3D m_r0;
//  Multiservo,    
  Multiservo m_coxaServo;   //  
  Multiservo m_femoraServo; //  
  Multiservo m_tibiaServo;  //  
public:
  GeksaFoot(Vector3D p0,Vector3D r0);
//   
  void begin(int coxaPin, int femoraPin, int tibiaPin);
//   
  void end();   

//   

  void coxaAngle(int);      //      (-90 .. 90 )
  int coxaAngle();          //     

  void femoraAngle(int);    //       (-90 .. 90 )
  int femoraAngle();        //     

  void tibiaAngle(int);     //       (-90 .. 90 )
  int tibiaAngle();         //     

//         

  //         
  int getAngles(Vector3D p, int& coxaAngle, int& femoraAngle, int& tibiaAngle);
  //       
  int getPoint(int coxaAngle, int femoraAngle, int tibiaAngle, Vector3D& p);
};


و coxaAngle ، femoraAngle ، طرق tibiaAngle تسمح لك لتحديد أو معرفة زاوية دوران المفصل الساق الفردية. الطرق المساعدة getAngles و getPoint تطبق منطق الحساب للكينماتيكا المباشرة والعكسية ، والتي يمكنك من خلالها حساب قيمة زوايا الساق لنقطة معينة في مساحة طرفه. أو العكس ، نقطة مسافة لقيم الزاوية الحالية.

يتوافق متوسط ​​موضع كل مفصل مع قيمة صفرية للزاوية ، ويقع نطاق دوران المفصل في النطاق من -90 إلى 90 درجة.

فئة المستوى الأعلى هي فئة Geksapod. ينفذ منطق الروبوت بالكامل. يتم تضمين كل ساق سداسي الأرجل في هذه الفئة كمثيل منفصل لفئة GeksaFoot .

فئة geksapod
class Geksapod: public AJobManager {
  friend class MotionJob;
  friend CommandProcessorJob;
  //  
  GeksaFoot m_LeftFrontFoot;
  GeksaFoot m_LeftMidleFoot;
  GeksaFoot m_LeftBackFoot;
  GeksaFoot m_RigthFrontFoot;
  GeksaFoot m_RigthMidleFoot;
  GeksaFoot m_RigthBackFoot;
  // ,    
  MotionJob m_MotionJob;
private:
  //       
  //       
  //     
  int _setPose(int idx, int ca, int fa, int ta);
  int _setPose(int[FOOTS_COUNT][3]);  
  int _setPose(Vector3D points[FOOTS_COUNT]); 
protected:
  //          
  int setPose(int idx, int ca, int fa, int ta, int actionTime); 
  int setPose(int pose[FOOTS_COUNT][3], int actionTime);
  int setPose(int idx, Vector3D p, int actionTime);
  int setPose(Vector3D points[FOOTS_COUNT], int actionTime = 0);
  int setPose(int ca, int fa, int ta, int actionTime);
  //      
  void getPose(int idx, int& ca, int& fa, int& ta);
  void getPose(int pose[FOOTS_COUNT][3]);
  void getPose(int idx, Vector3D& p);
  void getPose(Vector3D points[FOOTS_COUNT]);
  //    
  int execute(Motion* pMotion);
public:
  Geksapod();
  void setup();
  //   
  int move(int speed, int time);    //   
  int rotate(int speed, int time);  //   
  void stop();                      //  
  //         
  int getAngles(int idx, Vector3D p, int& ca, int& fa, int& ta);
  int getPoint(int idx, int coxaAngle, int femoraAngle, int tibiaAngle, Vector3D& p);
  int getAngles(Vector3D points[FOOTS_COUNT], int pose[FOOTS_COUNT][3]);
  int getPoints(int pose[FOOTS_COUNT][3], Vector3D points[FOOTS_COUNT]);
};


تم تصميم طريقتين getPose و setPose المحملة بشكل زائد للاستخدام الداخلي وتسمح لك بالحصول على الوضع الحالي لأطراف الروبوت أو تعيين طرف جديد. في هذه الحالة ، يتم تعيين موضع الساقين على شكل مجموعة من قيم زوايا الدوران لكل مفصل أو كمجموعة من إحداثيات نقاط النهاية لأطراف الروبوت بالنسبة لمركزه. لحركة الطرف السلس عند استدعاء طرق setPose ، يمكنك تحديد الوقت (معلمة actionTime ) التي يجب بعدها أن تصل الكفوف إلى الموضع المحدد. يتم التحكم في الروبوت عن طريق الطرق العامة التحرك ، تدوير و توقف .



مضاهاة المهام المتعددة


ترث فئة Geksapod تطبيق فئة AJobManager وتحتوي على نسخة من فئة MotionJob ، والتي ترث بدورها من فئة AJob . تسمح لك هذه الفئات بتنفيذ ما يسمى بالمهام المتعددة غير الاستباقية ، مما يسمح لك بالتجريد من خطية البرامج وأداء العديد من المهام في نفس الوقت.

وظيفة الطبقة
class AJob {
  friend class AJobManager;
private:
  AJobManager* m_pAJobManager;   
  AJob* mJobNext;                      
  unsigned long m_counter;         //    onRun
  unsigned long m_previousMillis; //     onRun
  unsigned long m_currentMillis;  //   
  unsigned long m_delayMillis;    //    onRun
  void run();
public:
  AJob(AJobManager*, unsigned long delay = 0L);
  ~AJob();
                  
  void finish();  //     
  long counter(); //    onRun    
  long setDelay(unsigned long); //    onRun
  unsigned long previousMillis();//      onRun
  unsigned long currentMillis(); //    
                              
  virtual void onInit();  //      
  virtual void onRun();   //     
  virtual void onDone();  //        finish
};


فئة AJob هي الفئة الأساسية لجميع المهام التي تتطلب التنفيذ المتزامن. يجب على ورثته تجاوز طريقة onRun ، التي تنفذ منطق المهمة التي يتم تنفيذها. بالنظر إلى تفاصيل المهام المتعددة الوقائية ، فإن استدعاء هذه الطريقة لا يجب أن تستغرق وقتًا طويلاً. يوصى بتقسيم منطق المهمة إلى عدة مهام فرعية أخف ، سيتم تنفيذ كل منها لإجراء مكالمة onRun منفصلة .

فئة AJobManager
class AJobManager {
  friend class AJob;
  AJob* mJobFirst;  //      
  void attach(AJob*);   //    
  void dettach(AJob*); //    
  void dettachAll();   //   
public:  
  AJobManager();
  ~AJobManager();
  void setup();
  void loop();
};


و AJobManager الطبقة لديها إعلان أكثر تواضعا ويحتوي على اثنين فقط الطرق العامة: الإعداد و حلقة . يجب استدعاء طريقة الإعداد مرة واحدة قبل بدء حلقة البرنامج الرئيسية. في ذلك ، تتم تهيئة جميع المهام واحدًا تلو الآخر ، عن طريق استدعاء طريقة onInit المقابلة لكل مهمة من القائمة.
تتم إضافة مهمة إلى القائمة تلقائيًا عندما يتم استدعاء مُنشئها ويمكن حذفها عن طريق استدعاء طريقة الإنهاء العامة للمهمة نفسها.

طريقة حلقةيتم استدعاؤها بشكل متكرر في دورة البرنامج الرئيسية وهي مسؤولة عن تنفيذ منطق كل مهمة بالتسلسل من القائمة على فترات زمنية محددة (إذا تم تثبيتها).

وهكذا ، عند إنشاء مثيل لفئة Geksapod الموروثة من فئة AJobManager ، نحصل على تصرفنا أداة ملائمة لتعدد المهام.

تنفيذ الحركة


يمكن وصف أي حركة للجسم من خلال بعض الوظائف التي تحدد موقعها في نقطة زمنية معينة. يمكن أن تكون هذه الوظيفة مركبة ، أي أنها يمكن أن تكون مجموعة من الوظائف ، كل منها قابل للتطبيق فقط لفترة زمنية معينة.

يتم تعريف الأنواع المختلفة لحركة أطراف سداسي الأرجل ويمكن توسيعها باستخدام الفئات الموروثة من فئة الحركة .

الحركة الطبقية
class Motion {
  friend class MotionJob;
protected:
  long m_MaxTime;     //      
  long m_TotalTime;   //      
  bool m_IsLooped;    //   
  Motion* m_pNext;    //     
public:  
  Motion(long maxTime, bool isLooped, long totalTime = -1, Motion* pNext = NULL);
  ~Motion();
  
  inline long maxTime() { return m_MaxTime; }
  inline long totalTime() { return m_TotalTime; }
  inline bool isLooped() { return m_IsLooped; }

  //          

  //       0 <= time <= m_MaxTime 
  virtual int getPose(long time, Vector3D points[FOOTS_COUNT]) { return E_NOT_IMPL; };  
  //        0 <= time <= m_MaxTime
  virtual int getPose(long time, int pose[FOOTS_COUNT][3]) { return E_NOT_IMPL; };       
};


لتنفيذ الحركة، ومتجاوزة getPose طريقة يجب أن يعود موقف الأطراف للروبوت لفترة معينة من الزمن الوقت في نطاق من 0 إلى mMaxTime (بالملي ثانية). في حالة تكرار الحركة ( m_IsLooped == true) ، يمكن تقييد وقت الحركة عن طريق تحديد المدة في m_TotalTime . وأخيرًا ، يمكنك تنظيم سلسلة من الحركات من خلال دمجها في قائمة.

وبالتالي ، لدينا الفرصة لوصف حركات الروبوت. لكن الوصف نفسه (في حالتنا ، بعض الحالات من الطبقة الموروثة من الحركة) لن يجعل الروبوت يتحرك. نحن بحاجة إلى آلية من شأنها إعادة ترتيب أرجل سداسي الأرجل ، مسترشدة بالوصف المعطى لها.

وهذه الآلية هي مثال لفئة MotionJob المعلنة في فئة Geksapod .

فئة MotionJob
class MotionJob: public AJob {
  enum STATUS { 
    NONE, RUNING, STOPING 
   } m_Status;
  
  Geksapod* m_pGeksapod;
  Motion* m_pMotion;
  long m_MotionTime;
  long m_TotalTime;
public:  
  MotionJob(Geksapod* pGeksapod);
  int execute(Motion* pMotion);
  void onRun();
};


مثيل لفئة MotionJob ، الموروثة من AJob ، هو مهمة يتم فيها استدعاء طريقة onRun على فترات منتظمة . كما أنها تنفذ آلية تجبر الروبوت على أداء الحركات. نحتاج فقط إلى إخباره بكيفية التحرك ، مع الإشارة إلى وصف الحركة عند استدعاء طريقة التنفيذ. هذا كل شئ حتى الان. لا تزال هناك العديد من القضايا غير المضاءة التي سأحاول الكتابة عنها في المقالة التالية. آمل ألا أتعب القراء بالكثير من التعليمات البرمجية. جاهز للإجابة على جميع أسئلتك. يتبع ... PS في عملية إعداد المقالة التالية ، قمت بتغيير هيكل رؤية الأساليب في فئة AJob بشكل طفيف . طرق OnInit







و onRun و onDone لا يحتاجون إلى وصول عام ، لأن مكالمتهم تأتي من فئة AJobManager الودودة . بالنظر إلى أن هذه الأساليب يجب أن تتداخل في الورثة ، يكفي وضعها في القسم المحمي .

وظيفة الطبقة
class AJob {
  friend class AJobManager;
private:
  AJobManager* m_pAJobManager;   
  AJob* mJobNext;                      
  unsigned long m_counter;         //    onRun
  unsigned long m_previousMillis; //     onRun
  unsigned long m_currentMillis;  //   
  unsigned long m_delayMillis;    //    onRun
  void run();
protected:
  virtual void onInit();  //      
  virtual void onRun();   //     
  virtual void onDone();  //        finish
public:
  AJob(AJobManager*, unsigned long delay = 0L);
  ~AJob();

  void finish();  //     
  long counter(); //    onRun    
  long setDelay(unsigned long); //    onRun
  unsigned long previousMillis();//      onRun
  unsigned long currentMillis(); //    
};


All Articles