我们复兴了六足动物。第一部分

上一篇文章中,我们分享了使用3D打印技术创建六脚架的经验。现在,我们将讨论使他复活的软件组件。

最初计划在一篇文章中展示所有信息,但是在撰写过程中,很清楚的是,这样的展示是肤浅的,无用的。因此,决定撰写几篇文章,并对该主题进行更详细的介绍。

六足仪


当前,带有Wi-Fi ESP8266UNO R3作主控制器实际上,该板上有两个控制器,它们通过UART接口相互交互。



尽管Uno的计算资源非常有限,但是足以教导机器人如何执行基本命令:

  • 给定速度和持续时间的直线运动
  • 向左或向右圆周运动(就位)
  • 采取预设的肢体位置

ESP8266负责组织无线通信通道,并用作Uno接收控制命令的网关。

可以通过与其建立的telnet会话中的本地网络或通过与控制器的有线连接(用于固件或调试)来控制机器人。为了方便起见,我们还编写了一个简单的android应用程序,该应用程序实现了用于控制机器人的最小交互功能。



下图示意性地显示了六脚架结构。



所有伺服均连接到Multiservo Shield扩展,该可让您控制18个伺服。她与Arduino的通信是通过I²C总线进行的。因此,即使同时操纵18个舵机,几乎所有Arduino引脚都将保持空闲状态。
应当注意,扩展板具有用于为所连接的伺服器供电的连接器。但是,该板设计所允许的最大允许电流约为10A,不足以为MG996R伺服驱动器供电,而MG996R伺服驱动器的总最大电流消耗可能超过指定值。因此,在我们的版本中,每个伺服器都绕过扩展板连接到单独的电源线。

六足动物管理


肢控制逻辑是使用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);
};


方法coxaAnglefemoraAngletibiaAngle允许您设置或找出单个腿部关节的旋转角度。辅助方法getAnglesgetPoint实现了计算正向运动和逆向运动学的逻辑,利用该逻辑可以计算肢体空间中给定点的腿部角度值。反之亦然,当前角度值的空格。

每个关节的平均位置对应于角度的零值,并且关节的旋转范围在-90至90度的范围内。

顶级班是Geksapod它实现了整个机器人的逻辑。每个六足动物腿都作为GeksaFoot类的单独实例包含在此类中

盖克萨波特类
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]);
};


重载的getPosesetPose方法仅供内部使用,并允许您获取机器人肢体的当前位置或设置新的肢体。在这种情况下,以每个关节的旋转角度的一组值的形式设置腿的位置,或者以机器人肢体相对于其中心的端点的一组坐标的形式设置腿的位置。
为了在调用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具有更适度的声明,并且仅包含两个公共方法:setuploop在开始主程序循环之前,必须调用一次setup方法。在其中,通过为列表中的每个任务调用相应的onInit方法对所有任务进行一次初始化
调用任务的构造函数时,任务会自动添加到列表中,并且可以通过调用任务本身的public finish方法将其删除循环

它在主程序周期中被重复调用,并负责以指定的时间间隔(如果已安装)从列表中依次执行每个任务的逻辑。

因此,当创建继承自AJobManagerGeksapod类的实例时,我们可以使用便利的多任务处理工具。

运动实施


身体的任何运动都可以通过确定其在给定时间点的位置的某些功能来描述。这样的功能可以是复合的,也就是可以是一组功能,每个功能仅在特定时间段内适用。

定义了六足动物肢体的各种类型的运动,可以使用从Motion类继承的类扩展这些类型的运动

运动类
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中设置持续时间来限制运动时间最后,您可以通过将一系列动作组合成一个列表来组织一系列动作。

因此,我们有机会描述机器人的运动。但是描述本身(在我们的例子中,是从Motion继承的类的某些实例)不会使机器人移动。我们需要一种机制,可以根据给出的说明重新排列六脚架的腿。

该机制是在Geksapod类中声明的MotionJob的实例

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();
};


继承自AJobMotionJob实例是一项任务,其中将定期调用onRun方法。它还实现了迫使我们的机器人执行运动的机制。我们只需要告诉他如何移动,并在调用execute方法时说明移动的描述即可。

目前为止就这样了。在下一篇文章中,我仍然会尝试解决许多未解决的问题。希望我不会对太多代码感到厌倦。准备回答您的所有问题。

待续...

PS

在准备下一篇文章的过程中,我稍微更改了AJob类中方法的可见性的结构初始化方法onRunonDone不需要公共访问,因为它们的调用来自友好的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