Marble Robot (マーブルロボット)その5 最終回
マーブルロボット その5 ソフトウェア編 2
2021年5月28日
マニピュレータを使ってアームロボットを動かすモーションデータを作ります。
スタート位置とホール位置の設定
①スタート位置
ここでは、スタート位置をスロープ台と決めています。
先ず、マニピュレータを使ってアームロボットのHandアームがスロープ台の円形ビー玉受け中央の上側
10から15㎜に移動します。(この位置がビー玉を放す位置にもなります)。
この位置を動かさずにシリアルモニターの表示からscv0からscv3の値を記録します。
私の例では、scv0 = 180, scv1 = 133, scv2 = 38, scv3=116 です。
②ホール位置
次に3ヶ所のホール位置へアームロボット移動し、実際にHand(手)を操作してビー玉が掴めることを確認します。
上手くビー玉が掴めることを確認したら。この位置を記録します。この作業を3ヶ所のホール毎に行います。
私の例ではホール1の位置が、scv0 = 145, scv1 = 174, scv2 = 104, scv3=92 です。
③データの作成
スタート位置とビー玉を放す位置は必ず同じ位置にします。
前回のマニピュレータ用ソフトに少し手を加えれば、アームロボットの動きをシミュレートして得たシリアルデータを
コピーして使えますが、マニピュレータの動かし方や速度によってデータ量が多くなることや、慣れないと動きが
ぎこちない等の短所があります。 そこで短いデータコードなので手作りとしました。
ここではスタート位置と各ホール間の片道を36行に分割して往復72行のデータを配列にしました。
また、データを1行実行後にdeley(timeset)を50mS挿入して適当な速度で比較的滑らかに動くようにしています。
注意点:スタート位置と各ホール間を単に案分すると最短距離となるが、スロープ台の下にあるホール1の場合
スロープ台と衝突するのでアームを左側へ迂回させています。
また、左側に位置するホール2、ホール3もスロープ台の手前でArm1、Arm2を上げて接触を避けています。
私のマーブルロボットのソースファイルを参考に添付しました。
Marble_Robot_Saucefile.txt
但し、私のマーブルロボット以外では各部の寸法が異なるので、データがそのままでは使えません。
// 参考資料:ホール1のデータ作成を参考にして下さい。
1 #include "Servo.h"// サーボライブラリー
2 #define HOLE_MAX 3 // ホールの数
3 #define STEP_MAX 72 // データの数
4
5 Servo servo_0; // hand
6 Servo servo_1; // arm1
7 Servo servo_2; // arm2
8 Servo servo_3; // pan
9
10 int timeset = 50; // deley time
11 int motion_table[HOLE_MAX][STEP_MAX][4] = { // 配列の生成
12 { // Hole 1 motion data ホール1のモーションデータ
13 { 180, 133, 38, 116 }, // スタート位置
14 { 180, 133, 40, 110 },
15 { 180, 134, 42, 100 },
16 { 180, 134, 44, 90 },
17 { 180, 136, 46, 80 },
18 { 180, 138, 48, 75 },
19 { 180, 140, 50, 75 },
20 { 180, 141, 52, 75 },
21 { 180, 142, 54, 74 },
22 { 180, 143, 56, 74 },
23 { 180, 144, 58, 74 },
24 { 180, 145, 60, 74 },
25 { 180, 146, 62, 74 },
26 { 180, 147, 64, 74 },
27 { 180, 148, 68, 74 },
28 { 180, 149, 70, 74 },
29 { 180, 150, 72, 74 },
30 { 180, 151, 74, 74 },
31 { 180, 152, 76, 74 },
32 { 180, 153, 78, 74 },
33 { 180, 154, 80, 74 },
34 { 180, 155, 82, 74 },
35 { 180, 156, 84, 74 },
36 { 180, 157, 86, 76 },
37 { 180, 159, 88, 78 },
38 { 180, 160, 90, 80 },
39 { 180, 162, 92, 82 },
40 { 180, 164, 94, 84 },
41 { 180, 166, 96, 86 },
42 { 180, 168, 98, 88 },
43 { 180, 170, 100, 90 },
44 { 180, 171, 102, 90 },
45 { 180, 172, 104, 92 },
46 { 180, 173, 104, 92 },
47 { 145, 174, 104, 92 }, // handを閉じる。
48 { 145, 172, 104, 92 },
49 { 145, 171, 104, 92 },
50 { 145, 170, 104, 90 },
51 { 145, 170, 102, 90 },
52 { 145, 168, 100, 90 },
53 { 145, 166, 98, 88 },
54 { 145, 164, 96, 86 },
55 { 145, 162, 94, 84 },
56 { 145, 161, 94, 82 },
57 { 145, 160, 92, 80 },
58 { 145, 159, 90, 78 },
59 { 145, 158, 88, 76 },
60 { 145, 157, 86, 74 },
61 { 145, 156, 84, 74 },
62 { 145, 155, 82, 74 },
63 { 145, 154, 80, 74 },
64 { 145, 153, 78, 74 },
65 { 145, 152, 76, 74 },
66 { 145, 151, 74, 74 },
67 { 145, 150, 72, 74 },
68 { 145, 149, 70, 74 },
69 { 145, 148, 68, 74 },
70 { 145, 147, 66, 74 },
71 { 145, 146, 64, 74 },
72 { 145, 145, 62, 74 },
73 { 145, 144, 60, 74 },
74 { 145, 143, 58, 74 },
75 { 145, 142, 56, 74 },
76 { 145, 142, 54, 75 },
77 { 145, 141, 52, 75 },
78 { 145, 140, 50, 75 },
79 { 145, 138, 48, 80 },
80 { 145, 136, 46, 90 },
81 { 145, 134, 44, 100 },
82 { 145, 134, 42, 110 },
83 { 180, 133, 40, 116 }, // スタートポイントに戻るとHandを開いてビー玉を放す。
84 { 180, 133, 38, 116 },
85 },
86 { // Hole 2 motion data ホール2のモーションデータ
87 { 180, 133, 38, 116 }, // スタート位置
88 { 180, 133, 40, 110 },
89 { 180, 134, 42, 100 },
// 中省略
121 { 145, 159, 108, 47 }, // ホール2に到着Handを閉じてビー玉を掴む。
// 中省略
156 { 145, 134, 42, 110 },
157 { 180, 133, 40, 116 }, // スタート位置に戻戻るとHandを開いてビー玉を放す。
158 { 180, 133, 38, 116 },
159 },
160 { // Hole 3 motion data ホール3のモーションデータ
161 { 180, 133, 38, 116 }, // スタートポイント
162 { 180, 133, 40, 110 },
163 { 180, 132, 42, 100},
// 中省略
195 { 145, 112, 130, 29 }, // ホール3に到着Handを閉じてビー玉を掴む。
// 中省略
230 { 145, 132, 42, 110 },
231 { 180, 133, 40, 116 }, // スタート位置に戻戻るとHandを開いてビー玉を放す。
232 { 180, 133, 38, 116 }
233 }
234 };
235
236 void setup() {
237 Serial.begin(115200);
238 pinMode(PB0, INPUT); // Hole Sensor1
239 pinMode(PB1, INPUT); // Hole Sensor2
240 pinMode(PA4, INPUT); // Hole Sensor3
241 servo_0.attach(PB9, 500, 2500); // hand *pinMode(PWMピン、最小パルス幅、最大パルス幅)
242 servo_1.attach(PB8, 500, 2500); // arm1 上記のパルス幅を変更して個体差が補正できます。
243 servo_2.attach(PB7, 500, 2500); // arm2 *ここでは、同じ値を使用しています。
244 servo_3.attach(PB6, 500, 2500); // pan *詳しくは、Servo.hライブラリーを検索して下さい。
245 // initial write value スタート位置を初期値設定
246 servo_0.write(180), servo_1.write(133), servo_2.write(38), servo_3.write(116);
247 }
248
249 void loop() {
250 if (digitalRead(PB0) == LOW) { // Hole 1 ホール1のセンサーがONの場合
251 Motion_dat(1);
252 }
253 if (digitalRead(PB1) == LOW) { // Hole 2 ホール2のセンサーがONの場合
254 Motion_dat(2);
255 }
256 if (digitalRead(PA4) == LOW) { // Hole 3 ホール3のセンサーがONの場合
257 Motion_dat(3);
258 }
259 }
260
261 void Motion_dat(int hole) { // 配列データによりサーボモータ動かします。
262 for (int step = 0; step < STEP_MAX; step++){
263 servo_0.write(motion_table[hole-1][step][0]); // hand
264 servo_1.write(motion_table[hole-1][step][1]); // arm1
265 servo_2.write(motion_table[hole-1][step][2]); // arm2
266 servo_3.write(motion_table[hole-1][step][3]); // pan
267 delay(timeset);
268 }
269 }
最後までご覧頂きましてありがとうございます。
次回からRspberry pi Picoを掲載予定です。
皆さまの参考になれば幸いです。
by Paradise
2021年5月28日
マニピュレータを使ってアームロボットを動かすモーションデータを作ります。
スタート位置とホール位置の設定
①スタート位置
ここでは、スタート位置をスロープ台と決めています。
先ず、マニピュレータを使ってアームロボットのHandアームがスロープ台の円形ビー玉受け中央の上側
10から15㎜に移動します。(この位置がビー玉を放す位置にもなります)。
この位置を動かさずにシリアルモニターの表示からscv0からscv3の値を記録します。
私の例では、scv0 = 180, scv1 = 133, scv2 = 38, scv3=116 です。
②ホール位置
次に3ヶ所のホール位置へアームロボット移動し、実際にHand(手)を操作してビー玉が掴めることを確認します。
上手くビー玉が掴めることを確認したら。この位置を記録します。この作業を3ヶ所のホール毎に行います。
私の例ではホール1の位置が、scv0 = 145, scv1 = 174, scv2 = 104, scv3=92 です。
③データの作成
スタート位置とビー玉を放す位置は必ず同じ位置にします。
前回のマニピュレータ用ソフトに少し手を加えれば、アームロボットの動きをシミュレートして得たシリアルデータを
コピーして使えますが、マニピュレータの動かし方や速度によってデータ量が多くなることや、慣れないと動きが
ぎこちない等の短所があります。 そこで短いデータコードなので手作りとしました。
ここではスタート位置と各ホール間の片道を36行に分割して往復72行のデータを配列にしました。
また、データを1行実行後にdeley(timeset)を50mS挿入して適当な速度で比較的滑らかに動くようにしています。
注意点:スタート位置と各ホール間を単に案分すると最短距離となるが、スロープ台の下にあるホール1の場合
スロープ台と衝突するのでアームを左側へ迂回させています。
また、左側に位置するホール2、ホール3もスロープ台の手前でArm1、Arm2を上げて接触を避けています。
私のマーブルロボットのソースファイルを参考に添付しました。
Marble_Robot_Saucefile.txt
但し、私のマーブルロボット以外では各部の寸法が異なるので、データがそのままでは使えません。
// 参考資料:ホール1のデータ作成を参考にして下さい。
1 #include "Servo.h"// サーボライブラリー
2 #define HOLE_MAX 3 // ホールの数
3 #define STEP_MAX 72 // データの数
4
5 Servo servo_0; // hand
6 Servo servo_1; // arm1
7 Servo servo_2; // arm2
8 Servo servo_3; // pan
9
10 int timeset = 50; // deley time
11 int motion_table[HOLE_MAX][STEP_MAX][4] = { // 配列の生成
12 { // Hole 1 motion data ホール1のモーションデータ
13 { 180, 133, 38, 116 }, // スタート位置
14 { 180, 133, 40, 110 },
15 { 180, 134, 42, 100 },
16 { 180, 134, 44, 90 },
17 { 180, 136, 46, 80 },
18 { 180, 138, 48, 75 },
19 { 180, 140, 50, 75 },
20 { 180, 141, 52, 75 },
21 { 180, 142, 54, 74 },
22 { 180, 143, 56, 74 },
23 { 180, 144, 58, 74 },
24 { 180, 145, 60, 74 },
25 { 180, 146, 62, 74 },
26 { 180, 147, 64, 74 },
27 { 180, 148, 68, 74 },
28 { 180, 149, 70, 74 },
29 { 180, 150, 72, 74 },
30 { 180, 151, 74, 74 },
31 { 180, 152, 76, 74 },
32 { 180, 153, 78, 74 },
33 { 180, 154, 80, 74 },
34 { 180, 155, 82, 74 },
35 { 180, 156, 84, 74 },
36 { 180, 157, 86, 76 },
37 { 180, 159, 88, 78 },
38 { 180, 160, 90, 80 },
39 { 180, 162, 92, 82 },
40 { 180, 164, 94, 84 },
41 { 180, 166, 96, 86 },
42 { 180, 168, 98, 88 },
43 { 180, 170, 100, 90 },
44 { 180, 171, 102, 90 },
45 { 180, 172, 104, 92 },
46 { 180, 173, 104, 92 },
47 { 145, 174, 104, 92 }, // handを閉じる。
48 { 145, 172, 104, 92 },
49 { 145, 171, 104, 92 },
50 { 145, 170, 104, 90 },
51 { 145, 170, 102, 90 },
52 { 145, 168, 100, 90 },
53 { 145, 166, 98, 88 },
54 { 145, 164, 96, 86 },
55 { 145, 162, 94, 84 },
56 { 145, 161, 94, 82 },
57 { 145, 160, 92, 80 },
58 { 145, 159, 90, 78 },
59 { 145, 158, 88, 76 },
60 { 145, 157, 86, 74 },
61 { 145, 156, 84, 74 },
62 { 145, 155, 82, 74 },
63 { 145, 154, 80, 74 },
64 { 145, 153, 78, 74 },
65 { 145, 152, 76, 74 },
66 { 145, 151, 74, 74 },
67 { 145, 150, 72, 74 },
68 { 145, 149, 70, 74 },
69 { 145, 148, 68, 74 },
70 { 145, 147, 66, 74 },
71 { 145, 146, 64, 74 },
72 { 145, 145, 62, 74 },
73 { 145, 144, 60, 74 },
74 { 145, 143, 58, 74 },
75 { 145, 142, 56, 74 },
76 { 145, 142, 54, 75 },
77 { 145, 141, 52, 75 },
78 { 145, 140, 50, 75 },
79 { 145, 138, 48, 80 },
80 { 145, 136, 46, 90 },
81 { 145, 134, 44, 100 },
82 { 145, 134, 42, 110 },
83 { 180, 133, 40, 116 }, // スタートポイントに戻るとHandを開いてビー玉を放す。
84 { 180, 133, 38, 116 },
85 },
86 { // Hole 2 motion data ホール2のモーションデータ
87 { 180, 133, 38, 116 }, // スタート位置
88 { 180, 133, 40, 110 },
89 { 180, 134, 42, 100 },
// 中省略
121 { 145, 159, 108, 47 }, // ホール2に到着Handを閉じてビー玉を掴む。
// 中省略
156 { 145, 134, 42, 110 },
157 { 180, 133, 40, 116 }, // スタート位置に戻戻るとHandを開いてビー玉を放す。
158 { 180, 133, 38, 116 },
159 },
160 { // Hole 3 motion data ホール3のモーションデータ
161 { 180, 133, 38, 116 }, // スタートポイント
162 { 180, 133, 40, 110 },
163 { 180, 132, 42, 100},
// 中省略
195 { 145, 112, 130, 29 }, // ホール3に到着Handを閉じてビー玉を掴む。
// 中省略
230 { 145, 132, 42, 110 },
231 { 180, 133, 40, 116 }, // スタート位置に戻戻るとHandを開いてビー玉を放す。
232 { 180, 133, 38, 116 }
233 }
234 };
235
236 void setup() {
237 Serial.begin(115200);
238 pinMode(PB0, INPUT); // Hole Sensor1
239 pinMode(PB1, INPUT); // Hole Sensor2
240 pinMode(PA4, INPUT); // Hole Sensor3
241 servo_0.attach(PB9, 500, 2500); // hand *pinMode(PWMピン、最小パルス幅、最大パルス幅)
242 servo_1.attach(PB8, 500, 2500); // arm1 上記のパルス幅を変更して個体差が補正できます。
243 servo_2.attach(PB7, 500, 2500); // arm2 *ここでは、同じ値を使用しています。
244 servo_3.attach(PB6, 500, 2500); // pan *詳しくは、Servo.hライブラリーを検索して下さい。
245 // initial write value スタート位置を初期値設定
246 servo_0.write(180), servo_1.write(133), servo_2.write(38), servo_3.write(116);
247 }
248
249 void loop() {
250 if (digitalRead(PB0) == LOW) { // Hole 1 ホール1のセンサーがONの場合
251 Motion_dat(1);
252 }
253 if (digitalRead(PB1) == LOW) { // Hole 2 ホール2のセンサーがONの場合
254 Motion_dat(2);
255 }
256 if (digitalRead(PA4) == LOW) { // Hole 3 ホール3のセンサーがONの場合
257 Motion_dat(3);
258 }
259 }
260
261 void Motion_dat(int hole) { // 配列データによりサーボモータ動かします。
262 for (int step = 0; step < STEP_MAX; step++){
263 servo_0.write(motion_table[hole-1][step][0]); // hand
264 servo_1.write(motion_table[hole-1][step][1]); // arm1
265 servo_2.write(motion_table[hole-1][step][2]); // arm2
266 servo_3.write(motion_table[hole-1][step][3]); // pan
267 delay(timeset);
268 }
269 }
最後までご覧頂きましてありがとうございます。
次回からRspberry pi Picoを掲載予定です。
皆さまの参考になれば幸いです。
by Paradise
スポンサーサイト
Marble Robot (マーブルロボット)その4 ソフトウェア編1
マーブルロボット その4 ソフトウェア編 1
2021年5月22日

マーブルロボットとマニピュレータが完成したら
アームロボットとマニピュレータをケーブルで接続してキャリブレーションを行いますが、アームロボットの
アーム取り付け位置をサーボモータの機械的中間点にセットしておきます。しかし、中には90度のテスト信号を
入力しても機械的中間点と大きくズレていて0度又は180度まで回らない不良品があるので注意して下さい。
1)サーボモータのキャリブレーション
マニピュレータを使ってアームロボットのサーボモータを設定しますが、前回に説明のマイコンSTM32へ
ブートローダが書き込まれ、ArduinoIDEが使える状態であることを前提とします。
先ず、次のテキストファイルを開きコピーしてArduinoIDEに張り付けてSTM32へ書き込みます。
MarbleRobotManipulator_1.txt
setupにArm1、Arm2、Panのサーボモータ初期角度を90度に設定してあるので、マニピュレータを接続前には
90度のテスト信号として使えます。
サーボモータSG90(MG90)の可動範囲は約180度、マニピュレータに使ったポテンションメータ(VR:
可変抵抗器)は約300度回ります。(サーボモータとマニピュレータの角度を合わせるにはアームロボットと
マニピュレータを同じ向きに並べて作業すると調整がし易いです)。
注意点:マニピュレータVRの取り付け方向やVR端子の電源極性の向きにより、左右又は上下に動かした時に
値の増減する方向が変わります。 また、アームロボットのサーボモータ取り付け方向によっても、左右又は
上下が逆の動きをします。
このような場合は、ハード的に変更しても良いが、後述のmap関数の書き方で対応出来ます。
では、サーボモータのPan(水平方向)の設定を例に説明します。
①サーボモータを機械的中間点にセットします。
②マニピュレータの水平方向も同様にVRの中間点に止めます。
③この状態でマイコンをONにしてArduinoIDEのシリアルモニターを開きます。
④するとシリアルモニターに各ポテンションメータの値(STM32のADCが12bitなので分解能が0~4095)を
val0~val3に、サーボモータへの指示角度(0~180)をscv0~scv3にリアルタイムに表示します。
シリアルモニター表示例

⑤この時にマニピュレータが中間点ならばval3が2048付近の値を示すと思います。
⑥次にマニピュレータを左右に回動かしてサーボモータの角度が0度と180度となる位置の値を記録します。
⑦記録した値をmap関数に記入します。下に私の例(2900~220)を示します。
例、scv3 = map(val3, 2900, 220, 0, 180);
val3の値2900~220を0~180に変換してscv3 としてサーボモータの角度値を出力しますが、サーボモータが
逆に動く場合は、0, 180を180,0と書き換えます。
また、2900~220の範囲外を次のif文により、0又は180に収めています。
if (scv3 >= 180) {
scv3 = 180;
} else if (scv3 <= 0) {
scv3 = 0;
}
同じ要領にてArm1とArm2の設定を行います。
但し、Hand Val0についてはポテンションメータではなくスイッチのONーOFFの状態をデジタルリードで
読み取り、開閉に対応した値をvol0へ出力します。
ここでは、予めVR(ポテンションメータ)を使ってHandの開け閉めを試した値を使っています。
if (digitalRead(PA0) == HIGH) {
val0 = 3300;
} else {
val0 = 4000;
}
この設定が完了するとマニピュレータの動きとサーボモータの動きが同期します。
但し、私の設定値がそのまま使えません。各々のセットに合わせた設定が必要です。
//アームロボットキャリブレーション用ソースコード
#include "Servo.h"
Servo servo_0; // hand
Servo servo_1; // arm1
Servo servo_2; // arm2
Servo servo_3; // pan
int val0, val1, val2, val3; // Manipulator Potension meter value
int scv0, scv1, scv2, scv3; // Servo control value
void setup() {
Serial.begin(115200);
servo_0.attach(PB9, 500, 2500); // hand *pinMode(PWMピン、最小パルス幅、最大パルス幅)
servo_1.attach(PB8, 500, 2500); // arm1 上記のパルス幅を変更して個体差が補正できます。
servo_2.attach(PB7, 500, 2500); // arm2 *ここでは、同じ値を使用しています。
servo_3.attach(PB6, 500, 2500); // pan *詳しくは、Servo.hライブラリーを参照して下さい。
servo_1.write(90); // Arm1 Servo
servo_2.write(90); // Arm2 Servo
servo_3.write(90); // Pan Servo
}
void loop() {
val1 = analogRead(PA1);
val2 = analogRead(PA2);
val3 = analogRead(PA3);
if (digitalRead(PA0) == HIGH) {
val0 = 3300;
} else {
val0 = 4000;
}
Serial.print("val0 = "), Serial.print(val0);
Serial.print(", val1 = "), Serial.print(val1);
Serial.print(", val2 = "), Serial.print(val2);
Serial.print(", val3 = "), Serial.println(val3);
scv0 = map(val0, 400, 4000, 0, 180); // hand Manipulator
scv1 = map(val1, 400, 3200, 0, 180); // Arm1 Manipulator
if (scv1 >= 180) {
scv1 = 180;
} else if (scv1 <= 0.0) {
scv1 = 0.0;
}
scv2 = map(val2, 2800, 500, 0, 180); // Arm2 Manipulator
if (scv2 >= 180) {
scv2 = 180;
} else if (scv2 <= 0) {
scv2 = 0;
}
scv3 = map(val3, 2900, 220, 0, 180); // pan Manipulator
if (scv3 >= 180) {
scv3 = 180;
} else if (scv3 <= 0) {
scv3 = 0;
}
servo_0.write(scv0); // Hand Servo
servo_1.write(scv1); // Arm1 Servo
servo_2.write(scv2); // Arm2 Servo
servo_3.write(scv3); // Pan Servo
Serial.print("scv0 = "), Serial.print(scv0);
Serial.print(", scv1 = "), Serial.print(scv1);
Serial.print(", scv2 = "), Serial.print(scv2);
Serial.print(", scv3 = "), Serial.println(scv3);
}
最後にもう一度動画をご覧下さい。
アームロボットがビー玉を忙しく運び、スムーズに循環する様子をお楽しみください。
次回はソフトウェア編2を掲載予定です。
by Paradise
2021年5月22日

マーブルロボットとマニピュレータが完成したら
アームロボットとマニピュレータをケーブルで接続してキャリブレーションを行いますが、アームロボットの
アーム取り付け位置をサーボモータの機械的中間点にセットしておきます。しかし、中には90度のテスト信号を
入力しても機械的中間点と大きくズレていて0度又は180度まで回らない不良品があるので注意して下さい。
1)サーボモータのキャリブレーション
マニピュレータを使ってアームロボットのサーボモータを設定しますが、前回に説明のマイコンSTM32へ
ブートローダが書き込まれ、ArduinoIDEが使える状態であることを前提とします。
先ず、次のテキストファイルを開きコピーしてArduinoIDEに張り付けてSTM32へ書き込みます。
MarbleRobotManipulator_1.txt
setupにArm1、Arm2、Panのサーボモータ初期角度を90度に設定してあるので、マニピュレータを接続前には
90度のテスト信号として使えます。
サーボモータSG90(MG90)の可動範囲は約180度、マニピュレータに使ったポテンションメータ(VR:
可変抵抗器)は約300度回ります。(サーボモータとマニピュレータの角度を合わせるにはアームロボットと
マニピュレータを同じ向きに並べて作業すると調整がし易いです)。
注意点:マニピュレータVRの取り付け方向やVR端子の電源極性の向きにより、左右又は上下に動かした時に
値の増減する方向が変わります。 また、アームロボットのサーボモータ取り付け方向によっても、左右又は
上下が逆の動きをします。
このような場合は、ハード的に変更しても良いが、後述のmap関数の書き方で対応出来ます。
では、サーボモータのPan(水平方向)の設定を例に説明します。
①サーボモータを機械的中間点にセットします。
②マニピュレータの水平方向も同様にVRの中間点に止めます。
③この状態でマイコンをONにしてArduinoIDEのシリアルモニターを開きます。
④するとシリアルモニターに各ポテンションメータの値(STM32のADCが12bitなので分解能が0~4095)を
val0~val3に、サーボモータへの指示角度(0~180)をscv0~scv3にリアルタイムに表示します。
シリアルモニター表示例

⑤この時にマニピュレータが中間点ならばval3が2048付近の値を示すと思います。
⑥次にマニピュレータを左右に回動かしてサーボモータの角度が0度と180度となる位置の値を記録します。
⑦記録した値をmap関数に記入します。下に私の例(2900~220)を示します。
例、scv3 = map(val3, 2900, 220, 0, 180);
val3の値2900~220を0~180に変換してscv3 としてサーボモータの角度値を出力しますが、サーボモータが
逆に動く場合は、0, 180を180,0と書き換えます。
また、2900~220の範囲外を次のif文により、0又は180に収めています。
if (scv3 >= 180) {
scv3 = 180;
} else if (scv3 <= 0) {
scv3 = 0;
}
同じ要領にてArm1とArm2の設定を行います。
但し、Hand Val0についてはポテンションメータではなくスイッチのONーOFFの状態をデジタルリードで
読み取り、開閉に対応した値をvol0へ出力します。
ここでは、予めVR(ポテンションメータ)を使ってHandの開け閉めを試した値を使っています。
if (digitalRead(PA0) == HIGH) {
val0 = 3300;
} else {
val0 = 4000;
}
この設定が完了するとマニピュレータの動きとサーボモータの動きが同期します。
但し、私の設定値がそのまま使えません。各々のセットに合わせた設定が必要です。
//アームロボットキャリブレーション用ソースコード
#include "Servo.h"
Servo servo_0; // hand
Servo servo_1; // arm1
Servo servo_2; // arm2
Servo servo_3; // pan
int val0, val1, val2, val3; // Manipulator Potension meter value
int scv0, scv1, scv2, scv3; // Servo control value
void setup() {
Serial.begin(115200);
servo_0.attach(PB9, 500, 2500); // hand *pinMode(PWMピン、最小パルス幅、最大パルス幅)
servo_1.attach(PB8, 500, 2500); // arm1 上記のパルス幅を変更して個体差が補正できます。
servo_2.attach(PB7, 500, 2500); // arm2 *ここでは、同じ値を使用しています。
servo_3.attach(PB6, 500, 2500); // pan *詳しくは、Servo.hライブラリーを参照して下さい。
servo_1.write(90); // Arm1 Servo
servo_2.write(90); // Arm2 Servo
servo_3.write(90); // Pan Servo
}
void loop() {
val1 = analogRead(PA1);
val2 = analogRead(PA2);
val3 = analogRead(PA3);
if (digitalRead(PA0) == HIGH) {
val0 = 3300;
} else {
val0 = 4000;
}
Serial.print("val0 = "), Serial.print(val0);
Serial.print(", val1 = "), Serial.print(val1);
Serial.print(", val2 = "), Serial.print(val2);
Serial.print(", val3 = "), Serial.println(val3);
scv0 = map(val0, 400, 4000, 0, 180); // hand Manipulator
scv1 = map(val1, 400, 3200, 0, 180); // Arm1 Manipulator
if (scv1 >= 180) {
scv1 = 180;
} else if (scv1 <= 0.0) {
scv1 = 0.0;
}
scv2 = map(val2, 2800, 500, 0, 180); // Arm2 Manipulator
if (scv2 >= 180) {
scv2 = 180;
} else if (scv2 <= 0) {
scv2 = 0;
}
scv3 = map(val3, 2900, 220, 0, 180); // pan Manipulator
if (scv3 >= 180) {
scv3 = 180;
} else if (scv3 <= 0) {
scv3 = 0;
}
servo_0.write(scv0); // Hand Servo
servo_1.write(scv1); // Arm1 Servo
servo_2.write(scv2); // Arm2 Servo
servo_3.write(scv3); // Pan Servo
Serial.print("scv0 = "), Serial.print(scv0);
Serial.print(", scv1 = "), Serial.print(scv1);
Serial.print(", scv2 = "), Serial.print(scv2);
Serial.print(", scv3 = "), Serial.println(scv3);
}
最後にもう一度動画をご覧下さい。
アームロボットがビー玉を忙しく運び、スムーズに循環する様子をお楽しみください。
次回はソフトウェア編2を掲載予定です。
by Paradise
Marble Robot (マーブルロボット)その3
コントロール部の説明
2021年5月16日
本体裏側にコントロール部をまとめました。

コントロール部の回路図
マイコンボードとフォトセンサーにアームロボットのインターフェースと電源バッテリーの簡単な回路です。
マイコンにはArduinoではなく、フラッシュメモリーの容量が大きいSTM32F103C8T6を使いましたが、Arduinoと
同じようにArduinoIDEにてプログラミングが出来ます。

マイコンボード
右がユニバーサル基板にSTM32F103とインターフェース用にコネクターを取り付けた様子です。
ここでは、STM32F103の基板への取り付けはソケットを使わずに必要端子のみを直付けしています。
インターフェース用の基板ソケットを各々設けています。
シリアル端子用:シリアルUSB変換基板を使ってブートローダーの書き込み時、または内蔵USBを使わない場合に使用。
変換基板の+5V、GND、RXD、TXDのみ使用。
サーボモータ用:マイコンボードとサーボモータ基板の接続用、GND、Hand、Arm1、Arm2、Panの5Pin。
センサー用:3個のセンサー出力と+3.3VとGNDの5Pin。
マニピュレータ用:プログラム作成時にサーボモータの角度取得時に使用、電源;+3.3V、GND、VR出力3本と
タッチスイッチ出力1本の6Pin。
電源用:単三タイプのニッケル水素電池充電池を4個を直列電池ボックスからサーボモータインタフェース基板と
マイコンボードへ供給 +5V、GND

STM32F103C8T6(Blue Pill)のピンアサインとブートローダーについて。
この製品はアマゾンで1個500円足らずで購入しました。2年前に買った分は、フラッシュメモリーが64KBでしたが、
今回購入した分は128KBでした。ピンアサインを参考に記します。
STM32F103C8T6は、通常購入した状態ではブートローダーが書き込まれていなく、自分で書き込む必要があります。
書き込みには、シリアルUSB変換ボード(数百円程度)が必要です。
私は、書き込み方法や手順をインドのAswinth Raj氏のサイトを参考にしました。最後のUSBドライバーのインストールが
完了すると、基板搭載のUSBソケットが使えるようになります。

マニピュレータ部
マーブルロボットでは、プログラムの作成時にのみ使いますが、マニピュレータの動きと同期してアームロボットを
動かすにはアームロボットの各関節間の長さと同じに作る事と、サーボモータの可動範囲とマニピュレータ・アームの
角度が合うようにポテンションメータ(VR)の使用領域をソフトウェアにて設定する必要があります。
ここでは、一般的な10KΩBタイプの丸型可変抵抗器を使いましたが、機械的回転角度は300°±5°です。
尚、STM32のADC分解能はArduinoの0~1023と違って0~4095なのでプログラム時に注意して下さい。
使い方と設定方法は、ソフトウェア編にて説明します。
私は開発用にマニピュレータ部にもマイコンを載せていますが、内蔵のマイコンにケーブルを接続すればOKです。

最後にもう一度動画をご覧下さい。
アームロボットがビー玉を忙しく運び、スムーズに循環する様子をお楽しみください。
次回はソフトウェアについて掲載予定です。
by Paradise
2021年5月16日
本体裏側にコントロール部をまとめました。

コントロール部の回路図
マイコンボードとフォトセンサーにアームロボットのインターフェースと電源バッテリーの簡単な回路です。
マイコンにはArduinoではなく、フラッシュメモリーの容量が大きいSTM32F103C8T6を使いましたが、Arduinoと
同じようにArduinoIDEにてプログラミングが出来ます。

マイコンボード
右がユニバーサル基板にSTM32F103とインターフェース用にコネクターを取り付けた様子です。
ここでは、STM32F103の基板への取り付けはソケットを使わずに必要端子のみを直付けしています。
インターフェース用の基板ソケットを各々設けています。
シリアル端子用:シリアルUSB変換基板を使ってブートローダーの書き込み時、または内蔵USBを使わない場合に使用。
変換基板の+5V、GND、RXD、TXDのみ使用。
サーボモータ用:マイコンボードとサーボモータ基板の接続用、GND、Hand、Arm1、Arm2、Panの5Pin。
センサー用:3個のセンサー出力と+3.3VとGNDの5Pin。
マニピュレータ用:プログラム作成時にサーボモータの角度取得時に使用、電源;+3.3V、GND、VR出力3本と
タッチスイッチ出力1本の6Pin。
電源用:単三タイプのニッケル水素電池充電池を4個を直列電池ボックスからサーボモータインタフェース基板と
マイコンボードへ供給 +5V、GND

STM32F103C8T6(Blue Pill)のピンアサインとブートローダーについて。
この製品はアマゾンで1個500円足らずで購入しました。2年前に買った分は、フラッシュメモリーが64KBでしたが、
今回購入した分は128KBでした。ピンアサインを参考に記します。
STM32F103C8T6は、通常購入した状態ではブートローダーが書き込まれていなく、自分で書き込む必要があります。
書き込みには、シリアルUSB変換ボード(数百円程度)が必要です。
私は、書き込み方法や手順をインドのAswinth Raj氏のサイトを参考にしました。最後のUSBドライバーのインストールが
完了すると、基板搭載のUSBソケットが使えるようになります。

マニピュレータ部
マーブルロボットでは、プログラムの作成時にのみ使いますが、マニピュレータの動きと同期してアームロボットを
動かすにはアームロボットの各関節間の長さと同じに作る事と、サーボモータの可動範囲とマニピュレータ・アームの
角度が合うようにポテンションメータ(VR)の使用領域をソフトウェアにて設定する必要があります。
ここでは、一般的な10KΩBタイプの丸型可変抵抗器を使いましたが、機械的回転角度は300°±5°です。
尚、STM32のADC分解能はArduinoの0~1023と違って0~4095なのでプログラム時に注意して下さい。
使い方と設定方法は、ソフトウェア編にて説明します。
私は開発用にマニピュレータ部にもマイコンを載せていますが、内蔵のマイコンにケーブルを接続すればOKです。

最後にもう一度動画をご覧下さい。
アームロボットがビー玉を忙しく運び、スムーズに循環する様子をお楽しみください。
次回はソフトウェアについて掲載予定です。
by Paradise
Marble Robot (マーブルロボット)その2
マーブルマシン部とアームロボットの製作例
2021年5月10日
画像や図はクリックすると拡大します。

マーブルマシン部の設計略図
今回もアクリル板の端材をCNC加工して部品を作りました。 アクリル板は、厚さ1㎜、2㎜、3㎜、5㎜を使います。
3個のビー玉が各スロープを一巡してホールに戻るまでの時間は、スロープの勾配が大きく関係します。
勾配が大き過ぎるとフェンスを乗り越えたりホールを素通りし、勾配が緩すぎるとセパレータに引っ掛かり止まります。
遅滞なくスムーズに動かすのは難しいと思いますが、その分作り甲斐があります。
尚、ビー玉の大きさは12.5㎜を使っています。

アームロボットの部品略図と組み立て図
サーボモータにはSG90を2個とメタルギアのMG90を使いました。
MG90を使った理由は、SG90のメインシャフトが遊びが多く「ぐらつき」が有るので負荷のかかるPanとアーム2に
使用しました。 先端の手(Hand)はビー玉専用のループ状としました。 Handの材料は書類バインダーの表紙
(厚さ1.6㎜)を使い、先端ループの内径が10㎜です。

本体内部について
本体の内部に制御基板やセンサー(フォトインタラプタ)とバッテリー電源を配置するのでスペースを確保します。
詳細は制御部で説明します。

フォトセンサーの取り付け例
今回使ったフォトインタラプタは、以前に友人から頂いたもので製品名が不明でしたがパナソニック製と判りました。
型番はCNZ1023(ON1023)で秋月電子で1個20円で購入できます。 この製品の仕様書ではVccが5Vですが、
私が試したところ3.3Vでも問題なく動作します。

マニピュレータ部の製作例
マニピュレータは、完成時には必要ありませんが、プログラムを作る時にサーボモータの角度情報の取得に
必要となります。 私はアクリル板をCNC加工して作りましたが、ベニヤ板などで簡単に作ることが出来ます。
但し、アームロボットの関節の長さと同じサイズに作る必要があるので注意して下さい。
この作品では、ビー玉を掴む手の開け閉めにサーボモータを使っていますが、単にON-OFFの動作なので、
ポテンションメータではなくタッチスイッチ(下画像第一関節の赤い板)を使いました。 詳細はソフト編で説明します。

マニピュレータ部の部品図
セットカラーには、2.5㎜の下穴にM3のタップ加工をします。

マニピュレータ部の組み立て図
各アームとVR(ポテンションメータ)の取り付けにt5アクリル板を加工したセットカラーをアクリル接着液で固定します。
また、VRのシャフトとセットカラーの固定はM3セットスクリューを使います。

最後にもう一度動画をご覧下さい。
アームロボットがビー玉を忙しく運び、スムーズに循環する様子をお楽しみください。
次回は制御回路を掲載の予定です。
by Paradise
2021年5月10日
画像や図はクリックすると拡大します。

マーブルマシン部の設計略図
今回もアクリル板の端材をCNC加工して部品を作りました。 アクリル板は、厚さ1㎜、2㎜、3㎜、5㎜を使います。
3個のビー玉が各スロープを一巡してホールに戻るまでの時間は、スロープの勾配が大きく関係します。
勾配が大き過ぎるとフェンスを乗り越えたりホールを素通りし、勾配が緩すぎるとセパレータに引っ掛かり止まります。
遅滞なくスムーズに動かすのは難しいと思いますが、その分作り甲斐があります。
尚、ビー玉の大きさは12.5㎜を使っています。

アームロボットの部品略図と組み立て図
サーボモータにはSG90を2個とメタルギアのMG90を使いました。
MG90を使った理由は、SG90のメインシャフトが遊びが多く「ぐらつき」が有るので負荷のかかるPanとアーム2に
使用しました。 先端の手(Hand)はビー玉専用のループ状としました。 Handの材料は書類バインダーの表紙
(厚さ1.6㎜)を使い、先端ループの内径が10㎜です。

本体内部について
本体の内部に制御基板やセンサー(フォトインタラプタ)とバッテリー電源を配置するのでスペースを確保します。
詳細は制御部で説明します。

フォトセンサーの取り付け例
今回使ったフォトインタラプタは、以前に友人から頂いたもので製品名が不明でしたがパナソニック製と判りました。
型番はCNZ1023(ON1023)で秋月電子で1個20円で購入できます。 この製品の仕様書ではVccが5Vですが、
私が試したところ3.3Vでも問題なく動作します。

マニピュレータ部の製作例
マニピュレータは、完成時には必要ありませんが、プログラムを作る時にサーボモータの角度情報の取得に
必要となります。 私はアクリル板をCNC加工して作りましたが、ベニヤ板などで簡単に作ることが出来ます。
但し、アームロボットの関節の長さと同じサイズに作る必要があるので注意して下さい。
この作品では、ビー玉を掴む手の開け閉めにサーボモータを使っていますが、単にON-OFFの動作なので、
ポテンションメータではなくタッチスイッチ(下画像第一関節の赤い板)を使いました。 詳細はソフト編で説明します。

マニピュレータ部の部品図
セットカラーには、2.5㎜の下穴にM3のタップ加工をします。

マニピュレータ部の組み立て図
各アームとVR(ポテンションメータ)の取り付けにt5アクリル板を加工したセットカラーをアクリル接着液で固定します。
また、VRのシャフトとセットカラーの固定はM3セットスクリューを使います。

最後にもう一度動画をご覧下さい。
アームロボットがビー玉を忙しく運び、スムーズに循環する様子をお楽しみください。
次回は制御回路を掲載の予定です。
by Paradise
Marble Robot (マーブルロボット)その1
マーブルロボットの動画が出来ましたのでご覧下さい。
2021年5月4日 (字幕は英語と日本語を切り替えれます)。
次回は製作と制御回路を掲載の予定です。
by Paradise
2021年5月4日 (字幕は英語と日本語を切り替えれます)。
次回は製作と制御回路を掲載の予定です。
by Paradise
次回プロジェクトMARBLE ROBOTのお知らせ
マーブルマシンとアームロボットを組み合わせたMARBLE ROBOTを作りました。
2021年5月1日完成
サーボモータを4個使用したアームロボットで、STM32F103マイコンにてコントロールしています。

これまでに木製とアクリル板製のマーブルマシンを数台作りましたが、今回はサーボモータを使ったアームロボットが
アーム先端の手(丸いわっか)でビー玉を拾い、上側のスロープ台へ運びます。
ビー玉がスロープを転がり、ジグザグスロープからセパレータ・スロープで行き先を選別され、下部の3ヶ所の穴(hole)
(画像でビー玉が止まってる場所)へ収まります。
holeには、フォトインタラプタを使ったセンサーを仕掛けていて、ビー玉がholeに入るとマイコンへ信号を送ります。
そしてアームロボットをそのholeへ移動させてビー玉を回収し、上側のスロープ台へと運びます。
holeが3ヶ所有り、同時に3個のビー玉を動かすのでアームロボットは休む暇もなく忙しく動きますが、ビー玉の
回収率は100パーセントです。

今回は画像による予告のみですが、次回は動作がよく判る動画をご覧頂きます。
また、製作図やソフトウェアも順次掲載の予定です。
by Paradise
2021年5月1日完成
サーボモータを4個使用したアームロボットで、STM32F103マイコンにてコントロールしています。

これまでに木製とアクリル板製のマーブルマシンを数台作りましたが、今回はサーボモータを使ったアームロボットが
アーム先端の手(丸いわっか)でビー玉を拾い、上側のスロープ台へ運びます。
ビー玉がスロープを転がり、ジグザグスロープからセパレータ・スロープで行き先を選別され、下部の3ヶ所の穴(hole)
(画像でビー玉が止まってる場所)へ収まります。
holeには、フォトインタラプタを使ったセンサーを仕掛けていて、ビー玉がholeに入るとマイコンへ信号を送ります。
そしてアームロボットをそのholeへ移動させてビー玉を回収し、上側のスロープ台へと運びます。
holeが3ヶ所有り、同時に3個のビー玉を動かすのでアームロボットは休む暇もなく忙しく動きますが、ビー玉の
回収率は100パーセントです。

今回は画像による予告のみですが、次回は動作がよく判る動画をご覧頂きます。
また、製作図やソフトウェアも順次掲載の予定です。
by Paradise