SpiderRobot 蜘蛛-Arduino中文社区 - Powered by Discuz!

Arduino中文社区

 找回密码
 立即注册

QQ登录

只需一步,快速开始

查看: 44556|回复: 95

SpiderRobot 蜘蛛

  [复制链接]
发表于 2018-6-3 09:39 | 显示全部楼层 |阅读模式
本帖最后由 createskyblue 于 2020-3-3 12:08 编辑

关于SpiderRobot 项目实行方案



1_compressed.jpg


之前有人推荐我做这个项目,于是乎就有了这个


2.png


http://regishsu.blogspot.tw/search/label/0.SpiderRobot
蜘蛛制作教程以及程序:http://www.instructables.com/id/DIY-Spider-RobotQuad-robot-Quadruped/

3.png

好啦,废话不多说,接下来是我的制作过程以及注意事项,希望想做的朋友可以成功!


第一部分  材料准备
Atmega328  或 Arduino 2650          X1
16M晶振              X1
22pf陶瓷电容             X2    最好有
SG90舵机                X12
7x9CM洞洞板              X1
LED                                                   X1
220Ω电阻                X1
波动开关                                          X1
3x25MM螺丝            X6    最好有
排针若干
焊丝若干
3D打印件

3D打印文件下载:
files.zip (784.96 KB, 下载次数: 375)

4.jpg

第二部分 进行组装

这一步组装要注意好方向,有两组相反的零部件,一定要注意,当时我没留意对不上硬是搞了半小时反复拆装!
7_compressed.jpg
8_compressed.jpg


安装时,每只脚可以分为3部分,我个人推荐先安装红色部分然后再到蓝色部分最后安装绿色部分,这样拧螺丝会比较方便
11_compressed2.jpg
然后红色部分的灰白色位置是朝上的,因为这个蜘蛛有两组相对的脚相对应也有两组相反的零件,这里注意下就好。蓝色部分分为A和B;比较长的为A比较短的为B。组装的时候要注意方向

每只脚还有两个关节固定点,所以我们需要打印2份固定卡扣 (一共8个)。下图中红色为没有扣上固定卡扣,蓝色为扣上并拧上螺丝;安装时先把卡扣怼到卡位,再安装舵机。
12_compressed_2.jpg

并且舵机安装过程中一定要使用舵机测试程序进行测试,不然会导致后期腿会发疯甚至烧毁舵机,我因为没有留意原文的这一步导致最后又要拆掉重装!推荐每安装一条腿随后一起测试着3条腿的舵机!
舵机测试.zip (430 Bytes, 下载次数: 144)

10.jpg
图中的数字为对应舵机接到板子上的接口位置
根据这个关系我们需要制作最小系统电路板,它是蜘蛛的大脑,我们需要它来完成之后的测试
13_compressed.jpg


6_compressed.jpg


测试的要求,腿的红色部分要与地面垂直,蓝色部分向上倾斜大约40°,最后绿色部分也就是最靠近中间的4个舵机要形成X字形;

如果测试中达不到要求可以执行以下步骤:
1. 取下舵机臂上的螺丝及其舵机臂
2. 运行测试程序
3. 然后把舵机臂扣上,确保舵机臂为上述要求,最后拧上螺丝
4. 再次运行测试程序
5. 如果有小偏差重复以上步骤,大偏差说明你还没有理解以上步骤
6. 如果舵机臂与3d打印支架存在松动情况不推荐使用胶布或胶水,推荐使用橡皮筋,像我一样


如果最终测试像上图一样,恭喜,你已经完成90%的步骤!


第三部分  演示

视频:审核完成  

https://www.bilibili.com/video/av24322376/

程序: spider_robot.zip (4.06 KB, 下载次数: 253)
游客,如果您要查看本帖隐藏内容请回复


// 由RegisHsu添加

void body_left(int i)
{
  set_site(0, site_now[0][0] + i, KEEP, KEEP);
  set_site(1, site_now[1][0] + i, KEEP, KEEP);
  set_site(2, site_now[2][0] - i, KEEP, KEEP);
  set_site(3, site_now[3][0] - i, KEEP, KEEP);
  wait_all_reach();
}

void body_right(int i)
{
  set_site(0, site_now[0][0] - i, KEEP, KEEP);
  set_site(1, site_now[1][0] - i, KEEP, KEEP);
  set_site(2, site_now[2][0] + i, KEEP, KEEP);
  set_site(3, site_now[3][0] + i, KEEP, KEEP);
  wait_all_reach();
}

void hand_wave(int i)
{
  float x_tmp;
  float y_tmp;
  float z_tmp;
  move_speed = 1;
  if (site_now[3][1] == y_start)
  {
    body_right(15);
    x_tmp = site_now[2][0];
    y_tmp = site_now[2][1];
    z_tmp = site_now[2][2];
    move_speed = body_move_speed;
    for (int j = 0; j < i; j++)
    {
      set_site(2, turn_x1, turn_y1, 50);
      wait_all_reach();
      set_site(2, turn_x0, turn_y0, 50);
      wait_all_reach();
    }
    set_site(2, x_tmp, y_tmp, z_tmp);
    wait_all_reach();
    move_speed = 1;
    body_left(15);
  }
  else
  {
    body_left(15);
    x_tmp = site_now[0][0];
    y_tmp = site_now[0][1];
    z_tmp = site_now[0][2];
    move_speed = body_move_speed;
    for (int j = 0; j < i; j++)
    {
      set_site(0, turn_x1, turn_y1, 50);
      wait_all_reach();
      set_site(0, turn_x0, turn_y0, 50);
      wait_all_reach();
    }
    set_site(0, x_tmp, y_tmp, z_tmp);
    wait_all_reach();
    move_speed = 1;
    body_right(15);
  }
}

void hand_shake(int i)
{
  float x_tmp;
  float y_tmp;
  float z_tmp;
  move_speed = 1;
  if (site_now[3][1] == y_start)
  {
    body_right(15);
    x_tmp = site_now[2][0];
    y_tmp = site_now[2][1];
    z_tmp = site_now[2][2];
    move_speed = body_move_speed;
    for (int j = 0; j < i; j++)
    {
      set_site(2, x_default - 30, y_start + 2 * y_step, 55);
      wait_all_reach();
      set_site(2, x_default - 30, y_start + 2 * y_step, 10);
      wait_all_reach();
    }
    set_site(2, x_tmp, y_tmp, z_tmp);
    wait_all_reach();
    move_speed = 1;
    body_left(15);
  }
  else
  {
    body_left(15);
    x_tmp = site_now[0][0];
    y_tmp = site_now[0][1];
    z_tmp = site_now[0][2];
    move_speed = body_move_speed;
    for (int j = 0; j < i; j++)
    {
      set_site(0, x_default - 30, y_start + 2 * y_step, 55);
      wait_all_reach();
      set_site(0, x_default - 30, y_start + 2 * y_step, 10);
      wait_all_reach();
    }
    set_site(0, x_tmp, y_tmp, z_tmp);
    wait_all_reach();
    move_speed = 1;
    body_right(15);
  }
}

void head_up(int i)
{
  set_site(0, KEEP, KEEP, site_now[0][2] - i);
  set_site(1, KEEP, KEEP, site_now[1][2] + i);
  set_site(2, KEEP, KEEP, site_now[2][2] - i);
  set_site(3, KEEP, KEEP, site_now[3][2] + i);
  wait_all_reach();
}

void head_down(int i)
{
  set_site(0, KEEP, KEEP, site_now[0][2] + i);
  set_site(1, KEEP, KEEP, site_now[1][2] - i);
  set_site(2, KEEP, KEEP, site_now[2][2] + i);
  set_site(3, KEEP, KEEP, site_now[3][2] - i);
  wait_all_reach();
}

void body_dance(int i)
{
  float x_tmp;
  float y_tmp;
  float z_tmp;
  float body_dance_speed = 2;
  sit();
  move_speed = 1;
  set_site(0, x_default, y_default, KEEP);
  set_site(1, x_default, y_default, KEEP);
  set_site(2, x_default, y_default, KEEP);
  set_site(3, x_default, y_default, KEEP);
  wait_all_reach();
  //stand();
  set_site(0, x_default, y_default, z_default - 20);
  set_site(1, x_default, y_default, z_default - 20);
  set_site(2, x_default, y_default, z_default - 20);
  set_site(3, x_default, y_default, z_default - 20);
  wait_all_reach();
  move_speed = body_dance_speed;
  head_up(30);
  for (int j = 0; j < i; j++)
  {
    if (j > i / 4)
      move_speed = body_dance_speed * 2;
    if (j > i / 2)
      move_speed = body_dance_speed * 3;
    set_site(0, KEEP, y_default - 20, KEEP);
    set_site(1, KEEP, y_default + 20, KEEP);
    set_site(2, KEEP, y_default - 20, KEEP);
    set_site(3, KEEP, y_default + 20, KEEP);
    wait_all_reach();
    set_site(0, KEEP, y_default + 20, KEEP);
    set_site(1, KEEP, y_default - 20, KEEP);
    set_site(2, KEEP, y_default + 20, KEEP);
    set_site(3, KEEP, y_default - 20, KEEP);
    wait_all_reach();
  }
  move_speed = body_dance_speed;
  head_down(30);
}


/*
  - 舵机服务/定时器中断功能/50Hz
  - 当设置site expected时,这个函数会移动到目标直线
  - 在设置expect之前,应该设置temp_speed[4][3],确保
直线移动,决定移动速度。
   ---------------------------------------------------------------------------*/
void servo_service(void)  //舵机服务
{
  sei();
  static float alpha, beta, gamma;

  for (int i = 0; i < 4; i++)
  {
    for (int j = 0; j < 3; j++)
    {
      if (abs(site_now[j] - site_expect[j]) >= abs(temp_speed[j]))
        site_now[j] += temp_speed[j];
      else
        site_now[j] = site_expect[j];
    }

    cartesian_to_polar(alpha, beta, gamma, site_now[0], site_now[1], site_now[2]); //从笛卡尔坐标系到极坐标转化
    polar_to_servo(i, alpha, beta, gamma); //用对应的极坐标控制舵机
  }

  rest_counter++;
}

/*
  - 设置一个预计位置点
  - 这个函数将同时设置temp_speed[4][3]
  - non - 模块化功能
   ---------------------------------------------------------------------------*/
void set_site(int leg, float x, float y, float z)  //设置某一条腿的坐标
{
  float length_x = 0, length_y = 0, length_z = 0;  //初始化float类型变量length_x,length_y,length_z

  if (x != KEEP)  //假若x轴不是保持状态
    length_x = x - site_now[leg][0];  //计算x轴长度
  if (y != KEEP)  //假若y轴不是保持状态
    length_y = y - site_now[leg][1];  //计算y轴长度
  if (z != KEEP)  //假若z轴不是保持状态
    length_z = z - site_now[leg][2];  //计算z轴长度

  float length = sqrt(pow(length_x, 2) + pow(length_y, 2) + pow(length_z, 2));   //计算宗长度

  temp_speed[leg][0] = length_x / length * move_speed * speed_multiple;  //计算对应腿的舵机1移动速度
  temp_speed[leg][1] = length_y / length * move_speed * speed_multiple;  //计算对应腿的舵机2移动速度
  temp_speed[leg][2] = length_z / length * move_speed * speed_multiple;  //计算对应腿的舵机3移动速度

  if (x != KEEP)  //假若x轴不是保持状态,则设置目标角度
    site_expect[leg][0] = x;
  if (y != KEEP)  //假若y轴不是保持状态,则设置目标角度
    site_expect[leg][1] = y;
  if (z != KEEP)  //假若z轴不是保持状态,则设置目标角度
    site_expect[leg][2] = z;
}

/*
   ---------------------------------------------------------------------------*/
void wait_reach(int leg)  //等待某条腿动作完成函数
{
  while (1) //死循环
    if (site_now[leg][0] == site_expect[leg][0])    //等待目标腿的 舵机 1达到目标角度
      if (site_now[leg][1] == site_expect[leg][1])//等待目标腿的 舵机 2达到目标角度
        if (site_now[leg][2] == site_expect[leg][2])//等待目标腿的 舵机 3达到目标角度
          break;  //跳出循环
}

/*
   ---------------------------------------------------------------------------*/
void wait_all_reach(void) //等待全部腿动作完成函数
{
  for (int i = 0; i < 4; i++)   //依次等待4条腿动作完成
    wait_reach(i);
}

/*
  - 从笛卡尔坐标系到极坐标转化
  - 数学模型2/2
   ---------------------------------------------------------------------------*/
void cartesian_to_polar(volatile float &alpha, volatile float &beta, volatile float &gamma, volatile float x, volatile float y, volatile float z)
{
  //calculate w-z degree
  float v, w;
  w = (x >= 0 ? 1 : -1) * (sqrt(pow(x, 2) + pow(y, 2)));
  v = w - length_c;
  alpha = atan2(z, v) + acos((pow(length_a, 2) - pow(length_b, 2) + pow(v, 2) + pow(z, 2)) / 2 / length_a / sqrt(pow(v, 2) + pow(z, 2)));
  beta = acos((pow(length_a, 2) + pow(length_b, 2) - pow(v, 2) - pow(z, 2)) / 2 / length_a / length_b);
  //calculate x-y-z degree
  gamma = (w >= 0) ? atan2(y, x) : atan2(-y, -x);
  //trans degree pi->180
  alpha = alpha / pi * 180;
  beta = beta / pi * 180;
  gamma = gamma / pi * 180;
}

/*
  - 用对应的极坐标控制舵机
  - 数学模型与事实相吻合的情况下
  - EEprom中存储的错误将被添加
   ---------------------------------------------------------------------------*/
void polar_to_servo(int leg, float alpha, float beta, float gamma)
{
  if (leg == 0)
  {
    alpha = 90 - alpha;
    beta = beta;
    gamma += 90;
  }
  else if (leg == 1)
  {
    alpha += 90;
    beta = 180 - beta;
    gamma = 90 - gamma;
  }
  else if (leg == 2)
  {
    alpha += 90;
    beta = 180 - beta;
    gamma = 90 - gamma;
  }
  else if (leg == 3)
  {
    alpha = 90 - alpha;
    beta = beta;
    gamma += 90;
  }

  servo[leg][0].write(alpha);  //设定对应腿上的舵机1旋转角度
  servo[leg][1].write(beta);   //设定对应腿上的舵机2旋转角度
  servo[leg][2].write(gamma);  //设定舵机3旋转角度
}[/mw_shl_code]
有读者提到一个问题,怎么转换为极坐标,可以看另外一个制作贴

芯片装配.pdf

253.92 KB, 下载次数: 145

发表于 2018-7-18 10:10 | 显示全部楼层
放假就开始设计—打印—安装—调试…………那里是爬啊就是在挪
谢谢楼主分享,给予很多的启发
发表于 2018-6-13 17:19 | 显示全部楼层
3d打印每样都要打印几个?
发表于 2018-6-13 17:55 | 显示全部楼层
有原理图吗
发表于 2018-9-5 17:46 | 显示全部楼层
感谢楼主分享
您需要登录后才可以回帖 登录 | 立即注册

本版积分规则

小黑屋|Archiver|手机版|Arduino中文社区

GMT+8, 2024-12-27 11:34 , Processed in 0.128054 second(s), 19 queries .

Powered by Discuz! X3.4

Copyright © 2001-2021, Tencent Cloud.

快速回复 返回顶部 返回列表