LoginSignup
1
0

More than 1 year has passed since last update.

女子美術大学にロボットアームを使ってもらった結果(4班、5班)

Last updated at Posted at 2021-12-15

がじぇるねと女子美のコラボネタです。
前回からの続きをお楽しみください。

4班:キャンストップ(Can't Stop)

4.png
ニュースの時間がやって参りました。(リポーター風)
本日のテーマはお祭り。お祭りって全国様々ありますよね。ご覧の皆さんも熊本とか島根とか色々なところにいらっしゃいますね。上京して生活のストレスや環境の違いとか感じて地元がちょっと恋しくなるなんてことあるんじゃないですか!?
そんな日々のストレスに疲れている皆様にとっておきのイベント「和っshow」をご紹介。目で見て耳で聞いて、まるでそこでお祭りが行われているかのような Show Window です。お祭りとなると大人数で広い場所が必要になりますよね。そこが問題になります。これを解決するためのアイテムがロボットアーム!どこでもお祭りを表現することができちゃうわけなんです(うそでしょ!?)。
今回選んだ県は山形県です。山形県と言えば山形花笠まつりです。花笠まつりといえば花笠を動かす動作が大事でロボットアームとの相性がばっちりなんです(まじか!)。

  • 場所を選ばず省スペースでお披露目
  • 花笠を回す躍動感ある動き
  • 音頭に合わせて一定の動きが可能

そしてここから現場リポートに移り「和っshow」のお披露目になるわけです。どうぞご覧ください。すごい製作能力とこだわりです。

5班:ねもり

5.png

一人暮らしのおばあちゃん千鶴子さんと娘との会話から。
「最近寝つきが悪いんだよね~」
「そうなのねー、困ったね」
おばあちゃんが眠れないのはなぜだろう。社会問題から考えてみた。高齢化社会で孤独死をしてしまう方が増えている。不眠病は60歳以上の方に多い。途中覚醒が原因というデータがある。途中覚醒とは入眠の状態からなかなか寝付けない状態。一人暮らしの高齢者で不安な夜を過ごしている人が多くなっていることを実感した。
私たちは高齢者の睡眠をサポートする、途中覚醒したときに孤独感や不安感をなくす、そんなプロダクトとして「ねもり」を提案する。
「ねもり」にはストーリーがある。多くの動物が住む島で住むやもり。ある日の嵐で家族と離れ離れになったやもりが行き着いた先がおばあさんの部屋。そしておばあさんと過ごすことになる。ねもりのほっぺはオレンジ色にやさしく光る。ねもりのモチーフはやもり、家を守るという意味から。話しかけるとゆっくり起きてほっぺが光る。トイレの行き帰りでドアの開閉でもほっぺを光らせて安心を届ける。
パッケージは娘や孫からギフトとしてプレゼントすることを想定したものになっている。箱ではなく籠を用いることで開けたときのわくわく感を演出できる。Webサイトにはねもりのストーリーや製作者も掲載して安心感を出した。(是非見てみてください!)

コード(4班)

#include <Arduino.h>
#include <ICS.h>

#define KRS_MIN 3500
#define KRS_MAX 11500
#define KRS_ORG 7500
#define KRS_FREE 0
#define SERVO_MIN -135
#define SERVO_MAX 135

IcsController ICS(Serial1);
IcsServo servo[3];

const int16_t hanagasa0[][4] = {
  {   0,    0,    0, 5000},
  {  60,    0,    0, 3000},
  {   0,    0,    0, 1000},
};

const int16_t hanagasa1[][4] = {
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,    0,    0, 2000},
  {  60,    0,    0,  500}, // チョ
  {   0,    0,    0,  500}, // イ
  {  60,    0,    0,  500}, // チョ
  {   0,    0,    0,  500}, // イ
  {   0,    0, -135, 1000}, // 栄
  {   0,  -60, -135, 1000}, // 
  {   0,    0, -135, 1000}, // 
  {   0,    0,  135, 1000}, // 
  {   0,   60,  135, 1000}, // 
  {   0,   60,   90, 1000}, // 
  {   0,    0,    0, 2000}, // 
  {   0,    0, -135, 1000}, // 
  {   0,    0,    0, 1000}, // 
};

const int16_t kansou1[][4] = {
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,    0,    0, 2000},
};

const int16_t hanagasa2[][4] = {
  {  60,    0,    0, 1000}, //
  { -60,    0,    0, 1000}, //の
  {  60,    0,    0, 1000}, // が
  { -60,    0,    0, 1000}, // た
  {   0,    0,    0, 1000}, // も
  {   0,  -60,    0, 1000}, // み
  {   0,  -60, -135, 1000}, // じ
  {  60,  -60, -135,  600}, // の
  {   0,  -60, -135,  600},
  {   0,  -60,  -45,  600},
  { -60,  -60,  -45,  600},
  {   0,  -60,  -45,  600},
  {   0,    0,    0, 1000},
  {  60,    0,    0,  500}, // チョ
  {   0,    0,    0,  500}, // イ
  {  60,    0,    0,  500}, // チョ
  {   0,    0,    0,  500}, // イ
  {   0,   60,    0, 1000},
  {   0,  -60,    0, 1000},
  {   0,    0,    0, 1000}, // る
  {  60,    0,    0,  625},
  {   0,    0,    0,  625},
  {  60,    0,    0,  625},
  {   0,    0,    0,  625},
  {  60,    0,    0,  625},
  {   0,    0,    0,  625},
  {  60,    0,    0,  625},
  {   0,    0,    0,  625},
  {   0,    0,  135, 1000},
  {   0,    0,    0, 1000},
};

const int16_t kansou2[][4] = {
  {   0,   60,    0, 1000},//1.03
  {   0,  -60,    0, 1000},
  {   0,   60,    0, 1000},
  {   0,  -60,    0, 1000},//1.06
  {   0,   60,    0, 1000},//1.07
  {   0,  -60,    0, 1000},//1.08
  {   0,   60,    0, 1000},//1.09
};

const int16_t hanagasa3[][4] = {
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,   60,  135,  333},
  { -60,   60,  -45,  333},
  {   0,    0,  -45,  334},
  {   0,   60,  -45,  333},
  {  60,   60,  135,  333},
  {   0,    0,  135,  334},
  {   0,    0,    0, 2000},
  {  60,    0,    0,  500}, // チョ
  {   0,    0,    0,  500}, // イ
  {  60,    0,    0,  500}, // チョ
  {   0,    0,    0,  500}, // イ
  {   0,    0, -135, 1000}, // 栄
  {   0,  -60, -135, 1000}, // 
  {   0,    0, -135, 1000}, // 
  {   0,    0,  135, 1000}, // 
  {   0,   60,  135, 1000}, // 
  {   0,   60,   90, 1000}, // 
  {   0,    0,    0, 2000}, // 
};

const int16_t kansou3[][4] = {
  {   0,    0,    0, 9000},
};

const int16_t ending[][4] = {
  {   0,    0, -135, 1000},
  {   0,  -60, -135, 1000},
  {   0,    0, -135, 1000},
  {   0,    0,  135, 1000},
  {   0,   60,  135, 1000},
  {   0,    0,  135, 1000},
  {   0,    0,    0, 1000},
  {  60,    0,    0, 1000},
  {   0,    0,    0, 1000},
};

void krs_setposition(IcsServo* servo, float radian){
  int angle = radian * 180 / PI;
  int pos = map(angle, SERVO_MIN, SERVO_MAX, KRS_MIN, KRS_MAX);
  if(pos >= KRS_MIN && pos <= KRS_MAX){
    servo->setPosition(pos);
    delay(1);
  }
}

void krs_setposition_angle(IcsServo* servo, int angle){
  int pos = map(angle, SERVO_MIN, SERVO_MAX, KRS_MIN, KRS_MAX);
  if(pos >= KRS_MIN && pos <= KRS_MAX){
    servo->setPosition(pos);
    delay(1);
  }
}

void setup() {
  Serial.begin(9600);
  pinMode(PIN_LED1, OUTPUT);
  ICS.begin();
  for(int i = 0; i < 3; i++){
    servo[i].attach(ICS, i+1); // id1 to id3
    servo[i].setStretch(100);
    delay(1);
    servo[i].setSpeed(100);
    delay(1);
    krs_setposition(&servo[i], 0);
    delay(1);
  }
}

float mapfloat(float x, float in_min, float in_max, float out_min, float out_max)
{
  return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
}

void loop() {
  unsigned long time = 0;
  digitalWrite(PIN_LED1, HIGH);

  // 1番
  for(int i = 0; i < sizeof(hanagasa0) / sizeof(hanagasa0[0][0]) / (sizeof(hanagasa0[0]) / sizeof(hanagasa0[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], hanagasa0[i][0]);
    krs_setposition_angle(&servo[1], hanagasa0[i][1]);
    krs_setposition_angle(&servo[0], hanagasa0[i][2]);
    while((millis() - time) < hanagasa0[i][3]);
  }
  // 1番続き
  for(int i = 0; i < sizeof(hanagasa1) / sizeof(hanagasa1[0][0]) / (sizeof(hanagasa1[0]) / sizeof(hanagasa1[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], hanagasa1[i][0]);
    krs_setposition_angle(&servo[1], hanagasa1[i][1]);
    krs_setposition_angle(&servo[0], hanagasa1[i][2]);
    while((millis() - time) < hanagasa1[i][3]);
  }
  // 間奏
  for(int i = 0; i < sizeof(kansou1) / sizeof(kansou1[0][0]) / (sizeof(kansou1[0]) / sizeof(kansou1[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], kansou1[i][0]);
    krs_setposition_angle(&servo[1], kansou1[i][1]);
    krs_setposition_angle(&servo[0], kansou1[i][2]);
    while((millis() - time) < kansou1[i][3]);
  }
  // 2番
  for(int i = 0; i < sizeof(hanagasa2) / sizeof(hanagasa2[0][0]) / (sizeof(hanagasa2[0]) / sizeof(hanagasa2[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], hanagasa2[i][0]);
    krs_setposition_angle(&servo[1], hanagasa2[i][1]);
    krs_setposition_angle(&servo[0], hanagasa2[i][2]);
    while((millis() - time) < hanagasa2[i][3]);
  }
  // 間奏2
  for(int i = 0; i < sizeof(kansou2) / sizeof(kansou2[0][0]) / (sizeof(kansou2[0]) / sizeof(kansou2[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], kansou2[i][0]);
    krs_setposition_angle(&servo[1], kansou2[i][1]);
    krs_setposition_angle(&servo[0], kansou2[i][2]);
    while((millis() - time) < kansou2[i][3]);
  }
  // 3番
  for(int i = 0; i < sizeof(hanagasa3) / sizeof(hanagasa3[0][0]) / (sizeof(hanagasa3[0]) / sizeof(hanagasa3[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], hanagasa3[i][0]);
    krs_setposition_angle(&servo[1], hanagasa3[i][1]);
    krs_setposition_angle(&servo[0], hanagasa3[i][2]);
    while((millis() - time) < hanagasa3[i][3]);
  }
  // 間奏3
  for(int i = 0; i < sizeof(kansou3) / sizeof(kansou3[0][0]) / (sizeof(kansou3[0]) / sizeof(kansou3[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], kansou3[i][0]);
    krs_setposition_angle(&servo[1], kansou3[i][1]);
    krs_setposition_angle(&servo[0], kansou3[i][2]);
    while((millis() - time) < kansou3[i][3]);
  }
  // 4番 (2番と一緒)
  for(int i = 0; i < sizeof(hanagasa2) / sizeof(hanagasa2[0][0]) / (sizeof(hanagasa2[0]) / sizeof(hanagasa2[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], hanagasa2[i][0]);
    krs_setposition_angle(&servo[1], hanagasa2[i][1]);
    krs_setposition_angle(&servo[0], hanagasa2[i][2]);
    while((millis() - time) < hanagasa2[i][3]);
  }
  for(int i = 0; i < sizeof(kansou2) / sizeof(kansou2[0][0]) / (sizeof(kansou2[0]) / sizeof(kansou2[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], kansou2[i][0]);
    krs_setposition_angle(&servo[1], kansou2[i][1]);
    krs_setposition_angle(&servo[0], kansou2[i][2]);
    while((millis() - time) < kansou2[i][3]);
  }
  // 5番 (1番と一緒)
  for(int i = 0; i < sizeof(hanagasa1) / sizeof(hanagasa1[0][0]) / (sizeof(hanagasa1[0]) / sizeof(hanagasa1[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], hanagasa1[i][0]);
    krs_setposition_angle(&servo[1], hanagasa1[i][1]);
    krs_setposition_angle(&servo[0], hanagasa1[i][2]);
    while((millis() - time) < hanagasa1[i][3]);
  }
  for(int i = 0; i < sizeof(kansou1) / sizeof(kansou1[0][0]) / (sizeof(kansou1[0]) / sizeof(kansou1[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], kansou1[i][0]);
    krs_setposition_angle(&servo[1], kansou1[i][1]);
    krs_setposition_angle(&servo[0], kansou1[i][2]);
    while((millis() - time) < kansou1[i][3]);
  }
  // 終わり
  for(int i = 0; i < sizeof(ending) / sizeof(ending[0][0]) / (sizeof(ending[0]) / sizeof(ending[0][0])); i++){
    time = millis();
    krs_setposition_angle(&servo[2], ending[i][0]);
    krs_setposition_angle(&servo[1], ending[i][1]);
    krs_setposition_angle(&servo[0], ending[i][2]);
    while((millis() - time) < ending[i][3]);
  }

  digitalWrite(PIN_LED1, LOW);
  delay(5000);

}

コード(5班)

#include <ICS.h>

#define KRS_MIN 3500
#define KRS_MAX 11500
#define KRS_ORG 7500
#define KRS_FREE 0
#define SERVO_MIN -135
#define SERVO_MAX 135

IcsController ICS(Serial1);
IcsServo servo[3];

void krs_setfree(IcsServo* servo){
  servo->setPosition(KRS_FREE);
}

int krs_getposition(IcsServo* servo){
  return map(servo->getPosition(), KRS_MIN, KRS_MAX, SERVO_MIN, SERVO_MAX);
}


void krs_setposition(IcsServo* servo, float radian){
  int angle = radian * 180 / PI;
  int pos = map(angle, SERVO_MIN, SERVO_MAX, KRS_MIN, KRS_MAX);
  if(pos > KRS_MIN && pos < KRS_MAX){
    servo->setPosition(pos);
    delay(1);
  }
}

void krs_setposition_angle(IcsServo* servo, int angle){
  int pos = map(angle, SERVO_MIN, SERVO_MAX, KRS_MIN, KRS_MAX);
  if(pos > KRS_MIN && pos < KRS_MAX){
    servo->setPosition(pos);
    delay(1);
  }
}

float mapfloat(float x, float in_min, float in_max, float out_min, float out_max)
{
  return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
}

void setup() {
  Serial.begin(9600);
  ICS.begin();
  for(int i = 0; i < 3; i++){
    servo[i].attach(ICS, i+1); // id1 to id3
    servo[i].setStretch(50);
    delay(1);
    servo[i].setSpeed(30);
    delay(1);
    krs_setposition(&servo[i], 0);
    delay(1);
  }
}

void loop(){
  int sum = 0;
  int mic = 0;
  static bool voice_flag = false;
  static int voice_count = 0;
  static int voice_sum = 0;
  static bool voice_message = false;
  static bool led_flag = false;
  static int led_count = 0;

  if(led_flag == true){
    analogWrite(11, 255);
    led_count++;
    if(led_count > 200){
      for(int i = 0; i < 250; i++){
        analogWrite(11, 250-i);
        delay(3);
      }
      analogWrite(11, 0);
      led_flag = false;
      led_count = 0;
    }
  } 
  else {
    analogWrite(11, 0);
  }
  for(int i=0; i<10; i++){
    static unsigned long time = micros();
    while(1){
      if(micros() - time > 200){ // 5kHz
        mic = analogRead(10);
        if(abs(2048-mic) < 100){
          mic = 0; // cut noise
        }
        break;
      }
    }
    sum += mic;
  }
  if(sum > 10000 && voice_count == 0){
    voice_flag = true;
  }
  if(voice_flag == true && led_flag == false){
    voice_count++;
    if(sum > 10000){
      voice_sum++;
    }
    if(voice_count > 10){ // stop recording
      if(voice_sum > 3){
        voice_message = true;
        led_flag = true;
      }
      voice_flag = false;
      voice_sum = 0;
      voice_count = 0;
    }
  }
  if(voice_message == true){
    delay(1500);
    for(int i = 0; i < 90; i++){
      krs_setposition_angle(&servo[1], constrain(i, 0, 60));
      krs_setposition_angle(&servo[0], -1*i/2);
      krs_setposition_angle(&servo[2], constrain(i, 0, 80));
      analogWrite(11, i*2.5);
      delay(30);
    }
    for(int i = 0; i < 90; i++){
      krs_setposition_angle(&servo[1], 60-constrain(i, 0, 60));
      krs_setposition_angle(&servo[0], -1*(45-i/2));
      krs_setposition_angle(&servo[2], 80-constrain(i, 0, 80));      
      delay(30);
    }
    voice_message = false;
  }
  Serial.print(sum);
  Serial.print(" ");
  Serial.print(voice_flag);
  Serial.print(" ");
  Serial.print(voice_count);
  Serial.print(" ");
  Serial.println(voice_sum);
  delay(30);
}
1
0
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
1
0