手の不自由な人のための食事介助ロボット0鍼灸マッサージ師の私が、手の不自由な方が操作可能な食事介助ロボットアームを製作してみました。押す引く2つの動作で4つのボタンを押し、2つのお皿を回転させながら食事をする事ができます。対象者の身体機能評価0・座位時に軽い介助下で肘の屈曲伸展が可能 (自力では不可)・手関節、手指の筋力は僅かにある程度 (物を握ることは不可)Add Annotation Order
コンテスト記載必要事項0For whom0Aさん(筋ジストロフィー)Why05年前、介護職員としてAさんの食事介助(介助者が、Aさんの手をスプーンとともに握りこんでの全介助)をしていた際、多少本人の筋力を感じたため、「何か装備を着ければ自力での食事ができるのではないか?」と伝えたところ、「じゃあ作って下さい」と頼まれた事がきっかけです。How0当初は木製のボディにゴムを使った形から制作を開始。5年間の期間、月1回フィッティングをしながらの試行錯誤。その後3Dプリンターとモーター、マイコンを使ったロボットアームへ。Outcome0全介助だった食事が、自らおかずを選択し、おおよそ自分のペースで食事をする事ができるようになる。Add Annotation Order
Why05年前、介護職員としてAさんの食事介助(介助者が、Aさんの手をスプーンとともに握りこんでの全介助)をしていた際、多少本人の筋力を感じたため、「何か装備を着ければ自力での食事ができるのではないか?」と伝えたところ、「じゃあ作って下さい」と頼まれた事がきっかけです。
第1段階0手袋のような物を作りスプーンを固定してみる。前腕の下にはバケツを解体し、カーブのついた側面でスプーンを動かせるように工夫してみた。結果0腕の筋力が弱く、スプーンを持ち上げることができなかった。Aさんの言葉0喜びながらも、「スプーンを握りたいですね。」気づいた事0自身の指でスプーンを握ることによって、スプーンから伝わる食べ物の感触を感じたかったのではないか。Add Annotation Order
第2段階0木材を蛇腹のように組み立て、バネをつけ、可動を補助した。結果0動きを調節することができなかった。Aさんの言葉0腕の曲げ伸ばしをしながら、「ラクに動きますね。コントロールが難しいですね。」Add Annotation Order
第3段階0肘の動きを固定し、お皿の下にターンテーブルを置き回転させる事によって、食べ物をすくえるように工夫してみた。結果0初めて食事を口に運ぶ事に成功した。お皿が自動的に回転し続けてしまうので、食べたい物を選ぶという動作ができなかった。課題0ゴムの調節が難しく、過剰な筋力を使うため身体的負担の心配があるAさんの言葉0嬉しそうに、「もっと筋トレして、完食できるようにしますね。」Add Annotation Order
3Dプリンターロボットアームに移行した経緯0何気ない会話の中で…0Aさんと雑談している際に、「AIやロボットアーム3Dプリンターなどが一般化しているので、これからはそういう自助具が使えるようになる未来があるかも知れない」と伝えたところ、「じゃあ作って下さい」と頼まれました。当初、私は自力で食事をとることができる自助具に執着していましたが、本人の希望(ロボットに対する興味)もあり、ロボットアームにチャレンジしてみることにしました。私自身、PCに疎く、マイコン3D CADなどの知識が全くなかったため、ネット等で検索し、自己流で制作を進める事に…Add Annotation Order
何気ない会話の中で…0Aさんと雑談している際に、「AIやロボットアーム3Dプリンターなどが一般化しているので、これからはそういう自助具が使えるようになる未来があるかも知れない」と伝えたところ、「じゃあ作って下さい」と頼まれました。当初、私は自力で食事をとることができる自助具に執着していましたが、本人の希望(ロボットに対する興味)もあり、ロボットアームにチャレンジしてみることにしました。私自身、PCに疎く、マイコン3D CADなどの知識が全くなかったため、ネット等で検索し、自己流で制作を進める事に…
第4段階 ロボットアームを利用しての食事0最初はジョイスティックなどを使いロボット操作を行おうと考えていましたが、十字キーの左右の動きが困難なため、まずはボタン2つでロボットを制御できるように工夫してみました。結果0良かった点3回に1回ほどはおかずをすくう事ができるようになった。時間はかかるがほぼ完食することが可能。悪かった点ロボットアームは負荷がかかった時に誤作動を起こす事があり、危険である。 ターンテーブルを逆回転するという配線が難しく、一方向でお皿を回すため、おかずをすくうのに時間がかかる。Aさんの言葉0「これは暴れ馬ですね。飼い慣らせるようになりたいですね。」Add Annotation Order
結果0良かった点3回に1回ほどはおかずをすくう事ができるようになった。時間はかかるがほぼ完食することが可能。悪かった点ロボットアームは負荷がかかった時に誤作動を起こす事があり、危険である。 ターンテーブルを逆回転するという配線が難しく、一方向でお皿を回すため、おかずをすくうのに時間がかかる。
第5段階 完成?0誤作動を起こす原因となる負荷を減らすため、紐を使ってアームを吊るし遊び、ゆとりを作りました。ターンテーブルとロボットアームの配線を分け、正転、逆転スイッチを使いました。Aさんの筋力を再評価し、どの方向で1番コントローラーを動かしやすいか、本人と再確認しました。結果0誤作動が減り、また衝撃を吸収される役割も果たし、精度が上がった。課題0緊急停止機能など安全装置の必要性があるプログラミングに対する知識が少なく、毎回設定に時間がかかるため、すぐに利用できるような立ち上げの設定が必要Aさんの言葉0「ありがとうございます。次はラーメンが食べたいです(笑)」 私「‼」Add Annotation Order
発見したこと0気づいた事0スプーンを上手く回転させれば、自助皿の曲面を利用してすくうことができるお皿を回転することができれば、スプーンを中央から端に動かす一方向の動きだけで、ほとんどの食べ物をすくうことができる人間の身体と似ている0ロボットアームと人の身体は同じであると感じることがありました。ボタンが押されるまで、ロボットアームは同じ体勢で維持するようプログラミングされていますが、過剰な負荷などがかかると揺れを起こし止まらなくなります。再びボタンを押すと揺れは止まります。この状態がパーキンソン病などに見られる安静時震戦に似ていると感じました。負荷や電圧が上がらないように肩甲骨などに負担を吸収する機能をつけてみましたが、思うようにいきませんでした。結果、より強力なモーターを使うことで揺れはなくなりましたが、固定力を強くすることで動きを制御するのではなく、人の身体のように姿勢の変化で動きを制御できるようになればと模索中です。Add Annotation Order
人間の身体と似ている0ロボットアームと人の身体は同じであると感じることがありました。ボタンが押されるまで、ロボットアームは同じ体勢で維持するようプログラミングされていますが、過剰な負荷などがかかると揺れを起こし止まらなくなります。再びボタンを押すと揺れは止まります。この状態がパーキンソン病などに見られる安静時震戦に似ていると感じました。負荷や電圧が上がらないように肩甲骨などに負担を吸収する機能をつけてみましたが、思うようにいきませんでした。結果、より強力なモーターを使うことで揺れはなくなりましたが、固定力を強くすることで動きを制御するのではなく、人の身体のように姿勢の変化で動きを制御できるようになればと模索中です。
まとめ0物作りとは…0当初は、自分の力で物を食べるということだけに着目して製作を行っていましたが、長い期間Aさんと接するうちに、彼の考え方や価値観を知る事ができました。なかなか成果が出なかった時に、「この試行錯誤しながら考えている時間が楽しいんですよ」と言われたことにとても感銘を受けました。ただ食事を食べるという目標を達成するだけの物作りなのではなく、そこに辿り着くまでのAさんとの時間こそが大切な時間だと感じました。Add Annotation Order
物作りとは…0当初は、自分の力で物を食べるということだけに着目して製作を行っていましたが、長い期間Aさんと接するうちに、彼の考え方や価値観を知る事ができました。なかなか成果が出なかった時に、「この試行錯誤しながら考えている時間が楽しいんですよ」と言われたことにとても感銘を受けました。ただ食事を食べるという目標を達成するだけの物作りなのではなく、そこに辿り着くまでのAさんとの時間こそが大切な時間だと感じました。
使用する道具03Dプリンターにて作成した部品0ELEGOO PLAフィラメント 1.75mmを使用フレーム上下皿台2つ滑車ネジ皿受け肩甲骨上腕上腕横・後ろ蓋肘前腕手手蓋指コントローラー台・コントローラーパッド購入した部品0AruduinoUSB昇降圧コンバーターPCA9685 PWMサーボモーターモジュールドライバーボードジャンパーワイヤーロッカースイッチ6ターミナル3ポジション購入した部品0MG996Rサーボホーン小型モーターサーボコネクター延長ケーブル正転逆転スイッチ購入した部品、使用する工具0配線コードスイッチ(ボタンから取り出す) ※動画参照USBケーブル工具類自助皿 スプーンスイッチ取り出しについて0ボタン内部のスイッチのみ取り出して使用しますAdd Annotation Order
コントローラー組み立て0①長コードをコントローラー台のボタン穴(小)から背面の穴に通す②コードをスイッチに取り付ける(極性なし)③スイッチをボタン穴にはめ込む④ロッカースイッチをボタン穴(大)にはめる (配線は動画にて説明)⑤反対側のスイッチも同様に取り付ける⑥コントローラーパッドを横の穴にはめ込む⑦完成配線0④ロッカースイッチ配線Add Annotation Order
配線を通す0①電源コードを取り付ける (極性なし)②コードを穴に通し、はめ込む③青コードの一方を2つのモーターの+に、もう一方を-へ繋ぐ (どちらでも良い) ※配線図参照混線を防ぐため、コードにビニールテープを巻く④フレーム下の差込口にコードを通す⑤上にコードを通すAdd Annotation Order
配線を通す0①2又コードを統合してGNDへ 右ボタンの赤コードを2へ 左ボタンの赤コードを3へ繋ぐ②極性あり ※+-間違えるとショートするため注意③フレーム上の上部にはめ込み、コードは穴から通して下へ④上から通したコードをArduinoに差し込み(配線図参照)、フレームの横部に取り付ける⑤USBケーブルを差し込み⑥蓋をして完成Add Annotation Order
アーム組み立て0①たこ糸、もしくはワイヤーや釣り糸などを使用する②肘と肩甲骨が平行になるように糸の長さを調節し、フックにかけて結ぶ③④肘と手が平行になるように、肘と手の穴に糸を通して結ぶ⑤手と前腕に延長コードをとりつけ、手のコードは前腕を通して肘の方へ⑥上腕の右側にコードを通していくAdd Annotation Order
STLファイル0皿台 左皿台 右回転盤 左回転盤 右フレーム下フレーム上フレーム上 ふた肩甲骨 ふた上腕上腕 ふた サイド・バック肘前腕 ふた手手 ふた指指 ネジ回転盤 ネジコントローラー台Add Annotation Order
新プログラミングコード0参考プログラミングコード0↓字数制限のため複数に分けて載せています10#include <Wire.h>#include <Adafruit_PWMServoDriver.h>Adafruit_PWMServoDriver pwm;#define SERVO_MIN 140#define SERVO_MAX 500#define SERVO0_PIN 0#define SERVO2_PIN 2#define SERVO3_PIN 3#define SERVO4_PIN 4#define SERVO5_PIN 5#define BUTTON1_PIN 2#define BUTTON2_PIN 320int servoPositions[6] = {90, 90, 90, 90, 90, 90}; // 各サーボモーターの初期位置bool button1Pressed = false;bool button2Pressed = false;30void setServoPosition(int servoNum, int targetAngle, int speed) { int currentAngle = servoPositions[servoNum]; int step = (targetAngle > currentAngle) ? 1 : -1; int delayTime = map(speed, 1, 10, 20, 5);40 while (currentAngle != targetAngle) { currentAngle += step; if ((step > 0 && currentAngle > targetAngle) || (step < 0 && currentAngle < targetAngle)) { currentAngle = targetAngle; }50 pwm.setPWM(servoNum, 0, map(currentAngle, 0, 180, SERVO_MIN, SERVO_MAX)); servoPositions[servoNum] = currentAngle; delay(delayTime); }}60void setServoPositionDual(int servoNum1, int targetAngle1, int servoNum2, int targetAngle2, int speed) { int currentAngle1 = servoPositions[servoNum1]; int currentAngle2 = servoPositions[servoNum2]; int step1 = (targetAngle1 > currentAngle1) ? 1 : -1;70 int step2 = (targetAngle2 > currentAngle2) ? 1 : -1; int delayTime = map(speed, 1, 10, 20, 5);80while (currentAngle1 != targetAngle1 || currentAngle2 != targetAngle2) { if (currentAngle1 != targetAngle1) { currentAngle1 += step1;90 if ((step1 > 0 && currentAngle1 > targetAngle1) || (step1 < 0 && currentAngle1 < targetAngle1)) { currentAngle1 = targetAngle1; } 100pwm.setPWM(servoNum1, 0, map(currentAngle1, 0, 180, SERVO_MIN, SERVO_MAX)); servoPositions[servoNum1] = currentAngle1; }110 if (currentAngle2 != targetAngle2) { currentAngle2 += step2; 120 if ((step2 > 0 && currentAngle2 > targetAngle2) || (step2 < 0 && currentAngle2 < targetAngle2)) { currentAngle2 = targetAngle2; }130 pwm.setPWM(servoNum2, 0, map(currentAngle2, 0, 180, SERVO_MIN, SERVO_MAX)); servoPositions[servoNum2] = currentAngle2; } delay(delayTime); }}140void setup() { pwm.begin(); pwm.setPWMFreq(60); pinMode(BUTTON1_PIN, INPUT_PULLUP); pinMode(BUTTON2_PIN, INPUT_PULLUP);}150void loop() { bool button1State = digitalRead(BUTTON1_PIN); bool button2State = digitalRead(BUTTON2_PIN);160 if (button1State == LOW && !button1Pressed) { // ボタン1が押されたら、アームの位置を制御 setServoPositionDual(SERVO4_PIN, 52, SERVO0_PIN, 180, 8); // 2つのサーボを同時に動かす setServoPositionDual(SERVO2_PIN, 0, SERVO3_PIN, 145, 3); // スプーンを皿に降ろす 170delay(200); // 一旦停止 setServoPosition(SERVO4_PIN, 0, 2); // 皿内移動 setServoPositionDual(SERVO0_PIN, 37, SERVO4_PIN, 4, 1); // スプーンを返す setServoPositionDual(SERVO0_PIN, 90, SERVO4_PIN, 20, 3); // 180 delay(200); setServoPositionDual(SERVO2_PIN, 60, SERVO3_PIN, 140, 3); // スプーンを引く setServoPosition(SERVO4_PIN, 90, 2); // 中央に setServoPositionDual(SERVO2_PIN, 120, SERVO3_PIN, 0, 3); // リーチ動作190delay(4000); // 初期位置に戻す setServoPositionDual(SERVO2_PIN, 140, SERVO3_PIN, 50, 3); setServoPositionDual(SERVO2_PIN, 100, SERVO3_PIN, 90, 3); setServoPosition(SERVO2_PIN, 100, 1); setServoPosition(SERVO4_PIN, 90, 2);200 setServoPosition(SERVO0_PIN, 90, 2); button1Pressed = true; } else if (button1State == HIGH) { button1Pressed = false; }210 if (button2State == LOW && !button2Pressed) { // ボタン2が押されたら、アームの位置を制御 setServoPositionDual(SERVO0_PIN, 10, SERVO4_PIN, 120, 8); setServoPositionDual(SERVO2_PIN, 35, SERVO3_PIN, 135, 3); // スプーンを皿に降ろす 220 setServoPosition(SERVO4_PIN, 168, 2); setServoPositionDual(SERVO0_PIN, 130, SERVO2_PIN, 25, 3); // 2つのサーボを同時に動かす setServoPosition(SERVO4_PIN, 160, 2); setServoPositionDual(SERVO0_PIN, 90, SERVO4_PIN, 150, 3); // バック230setServoPositionDual(SERVO2_PIN, 60, SERVO3_PIN, 140, 5); // setServoPosition(SERVO4_PIN, 90, 1); setServoPositionDual(SERVO2_PIN, 120, SERVO3_PIN, 0, 3); // リーチ動作240delay(4000); // 初期位置に戻す setServoPositionDual(SERVO2_PIN, 140, SERVO3_PIN, 50, 1); // 2つのサーボを同時に動かす setServoPositionDual(SERVO2_PIN, 100, SERVO3_PIN, 90, 3);250 setServoPosition(SERVO4_PIN, 90, 1); setServoPosition(SERVO0_PIN, 90, 1); button2Pressed = true; } else if (button2State == HIGH) { button2Pressed = false; }}Add Annotation Order
10#include <Wire.h>#include <Adafruit_PWMServoDriver.h>Adafruit_PWMServoDriver pwm;#define SERVO_MIN 140#define SERVO_MAX 500#define SERVO0_PIN 0#define SERVO2_PIN 2#define SERVO3_PIN 3#define SERVO4_PIN 4#define SERVO5_PIN 5#define BUTTON1_PIN 2#define BUTTON2_PIN 3
20int servoPositions[6] = {90, 90, 90, 90, 90, 90}; // 各サーボモーターの初期位置bool button1Pressed = false;bool button2Pressed = false;
30void setServoPosition(int servoNum, int targetAngle, int speed) { int currentAngle = servoPositions[servoNum]; int step = (targetAngle > currentAngle) ? 1 : -1; int delayTime = map(speed, 1, 10, 20, 5);
40 while (currentAngle != targetAngle) { currentAngle += step; if ((step > 0 && currentAngle > targetAngle) || (step < 0 && currentAngle < targetAngle)) { currentAngle = targetAngle; }
50 pwm.setPWM(servoNum, 0, map(currentAngle, 0, 180, SERVO_MIN, SERVO_MAX)); servoPositions[servoNum] = currentAngle; delay(delayTime); }}
60void setServoPositionDual(int servoNum1, int targetAngle1, int servoNum2, int targetAngle2, int speed) { int currentAngle1 = servoPositions[servoNum1]; int currentAngle2 = servoPositions[servoNum2]; int step1 = (targetAngle1 > currentAngle1) ? 1 : -1;
80while (currentAngle1 != targetAngle1 || currentAngle2 != targetAngle2) { if (currentAngle1 != targetAngle1) { currentAngle1 += step1;
90 if ((step1 > 0 && currentAngle1 > targetAngle1) || (step1 < 0 && currentAngle1 < targetAngle1)) { currentAngle1 = targetAngle1; }
100pwm.setPWM(servoNum1, 0, map(currentAngle1, 0, 180, SERVO_MIN, SERVO_MAX)); servoPositions[servoNum1] = currentAngle1; }
120 if ((step2 > 0 && currentAngle2 > targetAngle2) || (step2 < 0 && currentAngle2 < targetAngle2)) { currentAngle2 = targetAngle2; }
130 pwm.setPWM(servoNum2, 0, map(currentAngle2, 0, 180, SERVO_MIN, SERVO_MAX)); servoPositions[servoNum2] = currentAngle2; } delay(delayTime); }}
140void setup() { pwm.begin(); pwm.setPWMFreq(60); pinMode(BUTTON1_PIN, INPUT_PULLUP); pinMode(BUTTON2_PIN, INPUT_PULLUP);}
150void loop() { bool button1State = digitalRead(BUTTON1_PIN); bool button2State = digitalRead(BUTTON2_PIN);
160 if (button1State == LOW && !button1Pressed) { // ボタン1が押されたら、アームの位置を制御 setServoPositionDual(SERVO4_PIN, 52, SERVO0_PIN, 180, 8); // 2つのサーボを同時に動かす setServoPositionDual(SERVO2_PIN, 0, SERVO3_PIN, 145, 3); // スプーンを皿に降ろす
170delay(200); // 一旦停止 setServoPosition(SERVO4_PIN, 0, 2); // 皿内移動 setServoPositionDual(SERVO0_PIN, 37, SERVO4_PIN, 4, 1); // スプーンを返す setServoPositionDual(SERVO0_PIN, 90, SERVO4_PIN, 20, 3); //
180 delay(200); setServoPositionDual(SERVO2_PIN, 60, SERVO3_PIN, 140, 3); // スプーンを引く setServoPosition(SERVO4_PIN, 90, 2); // 中央に setServoPositionDual(SERVO2_PIN, 120, SERVO3_PIN, 0, 3); // リーチ動作
190delay(4000); // 初期位置に戻す setServoPositionDual(SERVO2_PIN, 140, SERVO3_PIN, 50, 3); setServoPositionDual(SERVO2_PIN, 100, SERVO3_PIN, 90, 3); setServoPosition(SERVO2_PIN, 100, 1); setServoPosition(SERVO4_PIN, 90, 2);
200 setServoPosition(SERVO0_PIN, 90, 2); button1Pressed = true; } else if (button1State == HIGH) { button1Pressed = false; }
210 if (button2State == LOW && !button2Pressed) { // ボタン2が押されたら、アームの位置を制御 setServoPositionDual(SERVO0_PIN, 10, SERVO4_PIN, 120, 8); setServoPositionDual(SERVO2_PIN, 35, SERVO3_PIN, 135, 3); // スプーンを皿に降ろす
220 setServoPosition(SERVO4_PIN, 168, 2); setServoPositionDual(SERVO0_PIN, 130, SERVO2_PIN, 25, 3); // 2つのサーボを同時に動かす setServoPosition(SERVO4_PIN, 160, 2); setServoPositionDual(SERVO0_PIN, 90, SERVO4_PIN, 150, 3); // バック
230setServoPositionDual(SERVO2_PIN, 60, SERVO3_PIN, 140, 5); // setServoPosition(SERVO4_PIN, 90, 1); setServoPositionDual(SERVO2_PIN, 120, SERVO3_PIN, 0, 3); // リーチ動作
240delay(4000); // 初期位置に戻す setServoPositionDual(SERVO2_PIN, 140, SERVO3_PIN, 50, 1); // 2つのサーボを同時に動かす setServoPositionDual(SERVO2_PIN, 100, SERVO3_PIN, 90, 3);
250 setServoPosition(SERVO4_PIN, 90, 1); setServoPosition(SERVO0_PIN, 90, 1); button2Pressed = true; } else if (button2State == HIGH) { button2Pressed = false; }}
Comments