目的
昨年のSPRESENSEコンテスト締め切りの約10日前となる2024年1月20日、JAXAが制作した小型月着陸実証機SLIMが日本初となる月面への軟着陸に成功しました。SLIMにはLEV-1とLEV-2という超小型の月面探査ロボットが搭載されており、LEV-2が撮影したSLIMの「逆立ち写真」は2024年の宇宙開発ベストショットの一つだと思います。
その写真を撮影したLEV-2(愛称はSORA-Q)は、JAXA、タカラトミー、ソニーグループ、同志社大学の共同開発により制作されており、制御にはSPRESENSEが使われました。
このプロジェクトでは、タカラトミーから発売されたLEV-2の実寸大スケールモデルであるSORA-Q Flagship Modelを改造し、本物と同様にSPRESENSEで制御します。
また、本物と同様に自律走行させて搭載カメラのイメージを用いてSLIMのダミーモデルを検出、撮影画像をサーバへ自動送信する機能を実装します。
この記事ではSORA-Q(本物)とSORA-Q Flagship Modelについてそれぞれ言及しますが、区別するためにSORA-Q(本物)をLEV-2、SORA-Q Flagship ModelをSORA-Qと呼びます。
結果
改造の結果、自律走行によりSLIMダミーモデルを検出し、サーバへ写真を送信することに成功しました!
システム構成
SORA-Q Flagship Modelの改造後の構成は下図の通りです。
・車輪駆動用のコアレスモータと車輪位相測定用のフォトリフレクタはオリジナル部品のまま流用しています。
・メインボードはSPRESENSEメインボードに置き換え、モータードライバとしてDRV8835を追加しました。
・カメラはSPRESENSEカメラCXD5602PWBCAM2Wに変更しました。
・通信用にはiS110Bを使用し、WiFi通信機能を追加しました。
・データの送信先にはNode-RED上に立てたHTTPサーバ及びMQTTブローカーを使用しました。
SORA-Q
タカラトミーさんのSORA-Q Flagship Modelを使いました。
メインボード
制御にはSPRESENSEメインボードを使用しています。
電源には3.7V LiPoバッテリーを使用し、メインボードの電源入力端子に直接入力しています。SORA-Qの筐体内に収めるために、GNSSアンテナ部をカットしています。この処理はLEV-2でも行われているそうです。
カメラ基板もボディに干渉する為、一部カットしています。
SORA-Qの筐体には、オリジナルの基板を固定する形状などがあり、SPRESENSEを収めるのが難しいため、筐体の下部パーツを再設計して3Dプリンタ出力部品に交換しています。
カメラ
カメラにはSPRESENSEの標準カメラCXD5602PWBCAM2Wを使用しました。
SORA-Qは、カメラ制御兼無線モジュールを搭載した小型のボードでカメラ制御を行っていますが、詳細不明のためSPRESENSE標準カメラを使用しています。
LEV-2は前後2台のカメラを搭載していますが、簡単のためSORA-Qと同じく1台としました。
カメラボードが大きくカメラ筐体に収まらず、はみ出した状態で固定できるカメラ筐体を再設計して3Dプリンタ出力パーツに交換しています。また、カメラ接続用のFPCケーブルも標準の60mmのケーブルから100mmのケーブルに変更して延長しました。
Wi-Fiモジュール
無線接続用にIDY社のWi-Fi Add-onボード iS110Bを使用し、サーバとWi-Fi接続しています。
LEV-2とLEV-1間はBluetooth通信しているそうですが、簡単のためWi-Fi接続としました。
SORA-Qは機体上部のカメラボードに通信モジュールを搭載していますが、これも実装困難のため本体筐体内のメインボード上に搭載しました。モーター直下ということもあり通信環境としては劣悪ですが、不安定ながらも通信可能です。
モータードライバ
モータードライバにはDRV8835を用い、Pololuのブレイクアウトボードを使用しました。ロジック電圧は2~7Vですが、1.8Vでも正常に動作してくれています。
DRV8835は空転可能なMODE 0と空転設定のないMODE 1がありますが、SORA-Qの変形制御には空転可能な方が都合がよいためMODE 0で運用しています。
Node-RED
SORA-Qからの通信はNode-RED上のHTTPサーバとMQTTブローカにて受けました。ノートPCにWi-Fiホットスポットを立て、SORA-Qを直接接続しています。
学習データ取得用カメラ
学習データ取得にはSPRESENSEにILI9341搭載ディスプレイを接続してカメラとして使用するデモをほぼそのまま利用しました。
部品表
SORA-Q改造用
部品 | 個数 | 備考 |
---|---|---|
SORA-Q Flagship Model | 1 | |
SPRESENSE メインボード | 1 | |
SPRESENSE カメラボード | 1 | |
Wi-Fi Add-onボード iS110B | 1 | |
ユニバーサル基板 | 1 | |
0805(2012)表面実装抵抗 33 | 2 | |
0805(2012)表面実装抵抗 1K | 2 | |
SHコネクタ 2Pin | 3 | |
SHコネクタ 3Pin | 2 | |
SHコネクタfemaleコンタクト | 適量 | |
SHコネクタハウジング 2Pin | 1 | |
LiPoバッテリー | 1 | |
UEW線 | 適量 |
学習用画像収集用カメラ
部品 | 個数 | 備考 |
---|---|---|
SPRESENSE メインボード | 1 | |
SPRESENSE 拡張ボード | ||
SPRESENSE カメラボード | 1 | |
ILI9341搭載2.8インチSPI制御タッチパネル付TFT液晶 MSP2807 | 1 |
3Dプリンタ部品
カメラ筐体及び本体下部筐体には3Dプリンタ部品を使用しました。GitHubhttps://github.com/airpocket-soundman/SORA-Q)でデータを公開しています。
自作基板回路図
モータードライバ、モーター、フォトリフレクタ、バッテリー等の接続のための基板を制作しました。基板はユニバーサル基板を切り出してUEW線で配線しています。
NNCによる物体検出
このプロジェクトではNNCを用いた機械学習を行い、SLIMを検出する物体認識モデルを制作しました。
機械学習のためにはSLIMのスケールモデルを制作しています。写真や適当な人形などでお茶を濁すことも可能でしたが、せっかくLEV-2を作るのだから本物(みたいな)のSLIMを検出してみたい!という欲求を抑えられず相応の工数を使っています(相当省略したにもかかわらずSORA-Qを改造するよりも多い)
単純にSLIMの模型を作って愛でたいという欲求も大きかったのですが、エッジで物体検出を行うにあたり一方向の形状しか見えない写真では簡単すぎる、という理由もあります。物体検出の学習モデルを作るにあたり、一方向からだけ見た画像を学習させるのは非常に簡単ですが、上下反対になったり、裏表で見え方の異なるものを学習するためにはよりたくさんの学習用データが必要になり、精度も下がりがちです。
実際のSLIMプロジェクトでも予定とは異なる姿勢で着陸したため、SORA-Qから見えるSLIMの姿は予定とは大きく異なるものでした。本物のSORA-Qは、いわゆる機械学習による物体検出ではなく古典的なCVを用いて断熱フィルムの「金色の物体」を検出したそうですが、これは限られたリソースと月面という特異な環境に最適な方法として選択されたものです。
今回のプロジェクトではSPRESENSEの特長をより生かすためにも、NNCを用いてCNNモデルを制作し、多方面から撮影したSLIMの画像を用いて学習を進めました。
データセット
データセットにはSLIMの6方向から撮影しそれらを0,90,180,270°回転させた合計24クラスとSLIMの写っていないクラスの合計25クラスの画像を用いました。各クラス100~150枚程度を使用しています。
入力画像は28×28ピクセル、グレースケールとしました。
モデル
SPRESENSEのメモリ空間の制限があるため、モデルは最小クラスのCNNとしました。1層のCNNと2層のCNNでフィルタ数及びカーネルサイズを変更してS,M,Lの3水準設定しました。
プログラム完成後にメモリ空き容量を確認したところ2層CNNモデルは容量不足であった為、1層のLargeモデルを採用しました。
Conv層 | モデルサイズ | フィルタ数 | カーネルシェイプ | データサイズ |
---|---|---|---|---|
1層 | Small | 10 | 7,7 | 28KB |
1層 | Midium | 16 | 7,7 | 44KB |
1層 | Large | 16 | 5,5 | 59KB |
2層 | Small | 10 | 7,7 | 120KB |
2層 | Midium | 16 | 7,7 | 177KB |
2層 | Large | 16 | 5,5 | 221KB |
コード
main.ino
char version[] = "Ver.elchicka";
#include <GS2200Hal.h>
#include <HttpGs2200.h>
#include <MqttGs2200.h>
#include <SDHCI.h>
#include <TelitWiFi.h>
#include <stdio.h> /* for sprintf */
#include <Camera.h>
#include "config.h"
#include <Flash.h>
#include <DNNRT.h>
#define CONSOLE_BAUDRATE 57600
#define TOTAL_PICTURE_COUNT 1
#define PICTURE_INTERVAL 1000
#define FIRST_INTERVAL 3000
#define SUBSCRIBE_TIMEOUT 60000 //ms
#define START_TIMER 10000 //ms
#define AIN1 A2 //左車輪エンコーダ
#define AIN2 A3 //右車輪エンコーダ
#define IN1_LEFT 19 //左車輪出力
#define IN1_RIGHT 21 //右車輪出力
#define IN2_LEFT 18 //左車輪方向
#define IN2_RIGHT 20 //右車輪方向
#define PHOTO_REFLECTOR_THRETHOLD_LEFT 100
#define PHOTO_REFLECTOR_THRETHOLD_RIGHT 100
// イメージ設定
#define DNN_IMG_W 28
#define DNN_IMG_H 28
#define CAM_IMG_W 320
#define CAM_IMG_H 240
#define CAM_CLIP_X 96//96
#define CAM_CLIP_Y 0//64
#define CAM_CLIP_W 224//112 //DNN_IMGのn倍であること(clipAndResizeImageByHWの制約)
#define CAM_CLIP_H 224//112 //DNN_IMGのn倍であること(clipAndResizeImageByHWの制約)
#define LINE_THICKNESS 5
#define RGB565(r, g, b) (((r & 0x1F) << 11) | ((g & 0x3F) << 5) | (b & 0x1F))
//DNNクラス関係設定
float threshold = 0.2;
DNNRT dnnrt;
DNNVariable input(DNN_IMG_W*DNN_IMG_H);
CamErr err;
String gStrResult = "?";
String maxLabel = "?";
int targetArea = 0;
int maxIndex = 24;
float maxOutput = 0.0;
//推論時間計測用
unsigned long startMicros; // 処理開始時間を記録する変数
unsigned long endMicros; // 処理終了時間を記録する変数
unsigned long elapsedTime; // 処理時間を記録する変数
//static uint8_t const label[2]= {0,1};
static String const label[25]= {"Back_R0", "Back_R1", "Back_R2", "Back_R3",
"Bottom_R0", "Bottom_R1", "Bottom_R2", "Bottom_R3",
"Front_R0", "Front_R1", "Front_R2", "Front_R3",
"Left_R0", "Left_R1", "Left_R2", "Left_R3",
"Right_R0", "Right_R1", "Right_R2", "Right_R3",
"Top_R0", "Top_R1", "Top_R2", "Top_R3",
"empty"};
//画像クロップ領域指定
struct ClipRect {
int x;
int y;
int width;
int height;
};
struct ClipRectSet {
ClipRect clips[17]; // 5つのクロップ領域を格納する配列
};
ClipRectSet clipSet = {
{
{ 0, 0, 224, 224}, // 0:large 1
{ 96, 0, 224, 224}, // 1:large 2
{ 0, 0, 112, 112}, // 2:small 1
{ 0, 56, 112, 112}, // 3:small 2
{ 0, 112, 112, 112}, // 4:small 3
{ 56, 0, 112, 112}, // 5:small 4
{ 56, 56, 112, 112}, // 6:small 5
{ 56, 112, 112, 112}, // 7:small 6
{112, 0, 112, 112}, // 8:small 7
{112, 56, 112, 112}, // 9:small 8
{112, 112, 112, 112}, // 10:small 9
{168, 0, 112, 112}, // 11:small 10
{168, 56, 112, 112}, // 12:small 11
{168, 112, 112, 112}, // 13:small 12
{208, 0, 112, 112}, // 14:small 13
{208, 56, 112, 112}, // 15:small 14
{208, 112, 112, 112}, // 16:small 15
}
};
//通信用設定
const uint16_t RECEIVE_PACKET_SIZE = 1500;
uint8_t Receive_Data[RECEIVE_PACKET_SIZE] = { 0 };
//dnn設定
char flashPath[] = "data/slim.nnb";
char flashFolder[] = "data/";
char nnbFile[] = "model.nnb";
bool doInferrence = false;
bool nnb_copy = true;
// auto start on/off
bool autoStart = false;
// test mode on/off
bool nnbFilePost = false; //NNBファイルをhttp postしてチェック
bool analogReadTest = false;
bool driveTest = false;
bool selectedImageOnly = true;
bool imagePost = false;
bool detectedSLIM = false;
bool autoSerch = true; //SLIM探索を行う
bool waitInferrence = true; //推論を待つ
// out put mode on/off
bool photo_reflector_out = false;
bool photo_reflector_left = false;
bool photo_reflector_right = false;
//MQTTデータパース用変数
String param1, param2, param3, param4, param5, param6;
//WiFiモジュール関連
TelitWiFi gs2200;
TWIFI_Params gsparams;
HttpGs2200 theHttpGs2200(&gs2200);
HTTPGS2200_HostParams httpHostParams; // HTTPサーバ接続用のホストパラメータ
SDClass theSD;
MqttGs2200 theMqttGs2200(&gs2200);
MQTTGS2200_HostParams mqttHostParams; // MQTT接続のホストパラメータ
bool served = false;
MQTTGS2200_Mqtt mqtt;
//モータハンドラ
void motor_handler(int left_speed, int right_speed){
char buffer[30]; // 十分なサイズのバッファを用意
snprintf(buffer, sizeof(buffer), "SET left: %3d, Right: %3d", left_speed, right_speed);
Serial.println(buffer);
if (left_speed == 0){
digitalWrite(IN1_LEFT, LOW);
digitalWrite(IN2_LEFT, LOW);
} else if (left_speed < 0) {
analogWrite(IN1_LEFT, map(abs(left_speed), 0, 100, 0, 255));
digitalWrite(IN2_LEFT, LOW);
} else if (left_speed > 0) {
analogWrite(IN2_LEFT, map(abs(left_speed), 0, 100, 0, 255));
digitalWrite(IN1_LEFT, LOW);
}
if (right_speed == 0){
digitalWrite(IN1_RIGHT, LOW);
digitalWrite(IN2_RIGHT, LOW);
} else if (right_speed > 0) {
analogWrite(IN1_RIGHT, map(abs(right_speed), 0, 100, 0, 255));
digitalWrite(IN2_RIGHT, LOW);
} else if (right_speed < 0) {
analogWrite(IN2_RIGHT, map(abs(right_speed), 0, 100, 0, 255));
digitalWrite(IN1_RIGHT, LOW);
}
}
//フォトリフレクタ読込
void read_photo_reflector(){
photo_reflector_left = (analogRead(A2) >= PHOTO_REFLECTOR_THRETHOLD_LEFT);
photo_reflector_right = (analogRead(A3) >= PHOTO_REFLECTOR_THRETHOLD_RIGHT);
//Serial.println("read photo reflector");
if (photo_reflector_out){
char buffer[50];
sprintf(buffer, "photo reflector value LEFT = %d / RIGHT = %d", photo_reflector_left, photo_reflector_right);
Serial.println(buffer);
}
}
//車輪格納ロック
void lockWheels(){
Serial.println("lock wheels");
motor_handler( -75, -75);
delay(300);
motor_handler( 0, 0);
}
//車輪格納ロック解除
void unlockWheels(){
Serial.println("unlock wheels");
motor_handler( 75, 75);
delay(400);
motor_handler( 0, 0);
}
//MQTT受信データパース
void splitString(String input, String &var1, String &var2, String &var3, String &var4, String &var5, String &var6) {
int startIndex = 0;
int commaIndex;
int varCount = 0;
while ((commaIndex = input.indexOf(',', startIndex)) != -1 && varCount < 5) {
if (varCount == 0) {
var1 = input.substring(startIndex, commaIndex);
} else if (varCount == 1) {
var2 = input.substring(startIndex, commaIndex);
} else if (varCount == 2) {
var3 = input.substring(startIndex, commaIndex);
} else if (varCount == 3) {
var4 = input.substring(startIndex, commaIndex);
} else if (varCount == 4) {
var5 = input.substring(startIndex, commaIndex);
}
startIndex = commaIndex + 1;
varCount++;
}
// 最後の変数に残りの部分を格納
if (varCount < 6) {
var6 = input.substring(startIndex);
} else {
var6 = ""; // 余った部分がない場合
}
}
//MQTT受信処理
void checkMQTTtopic(){
String data;
/* just in case something from GS2200 */
while (gs2200.available()) {
if (false == theMqttGs2200.receive(data)) {
served = false; // quite the loop
break;
}
Serial.println("Recieve data: " + data);
// dataをパース
splitString(data, param1, param2, param3, param4, param5, param6);
Serial.println("param 1: " + param1);
Serial.println("param 2: " + param2);
Serial.println("param 3: " + param3);
Serial.println("param 4: " + param4);
Serial.println("param 5: " + param5);
Serial.println("param 6: " + param6);
// param1の値によってlockwheelsまたはunlockWheelsを実行
if (param1 == "lockWheels") {
lockWheels();
} else if (param1 == "unlockWheels") {
unlockWheels();
} else if (param1 == "autoON"){
autoSerch = true;
} else if (param1 == "autoOFF"){
autoSerch = false;
}
}
}
//microSDに model.nnb が存在するとき、推論用モデルをflashメモリにコピーする
void move_nnbFile() {
Serial.println("\n////////////////// nnb file /////////////////");
if (nnb_copy) {
File readFile = theSD.open(nnbFile, FILE_READ);
uint32_t file_size = readFile.size();
Serial.print("SD data file size = ");
Serial.println(file_size);
char *body = (char *)malloc(file_size);
if (body == NULL) {
Serial.println("メモリ確保に失敗しました");
return;
}
int index = 0;
while (readFile.available()) {
body[index++] = readFile.read();
}
readFile.close();
Flash.mkdir(flashFolder);
if (Flash.exists(flashPath)) {
Flash.remove(flashPath); // ファイルを削除
}
File writeFile = Flash.open(flashPath, FILE_WRITE);
if (writeFile) {
Serial.println("nnb fileをフラッシュメモリに書き込み中...");
size_t written = writeFile.write((uint8_t*)body, file_size);
if (written != file_size) {
Serial.println("ファイルの書き込みに失敗しました");
} else {
Serial.println("nnb fileをフラッシュメモリへ書き込み完了");
}
writeFile.close();
// フラッシュメモリに保存されたファイルのサイズを表示
File flashFile = Flash.open(flashPath, FILE_READ);
if (flashFile) {
uint32_t flashFileSize = flashFile.size();
Serial.print("フラッシュメモリのファイルサイズ = ");
Serial.println(flashFileSize);
flashFile.close();
} else {
Serial.println("フラッシュメモリのファイルオープンに失敗しました");
}
} else {
Serial.println("フラッシュメモリのファイルオープンに失敗しました");
}
free(body);
} else {
Serial.println("move nnb file passed.\n");
}
Serial.println("\n////////////////// nnb file end //////////////////////");
}
//http リクエストパース
void parse_httpresponse(char *message) {
char *p;
if ((p = strstr(message, "200 OK\r\n")) != NULL) {
ConsolePrintf("Response : %s\r\n", p + 8);
}
}
//Cameraクラスエラー表示
void printError(enum CamErr err) {
Serial.print("Error: ");
switch (err) {
case CAM_ERR_NO_DEVICE:
Serial.println("No Device");
break;
case CAM_ERR_ILLEGAL_DEVERR:
Serial.println("Illegal device error");
break;
case CAM_ERR_ALREADY_INITIALIZED:
Serial.println("Already initialized");
break;
case CAM_ERR_NOT_INITIALIZED:
Serial.println("Not initialized");
break;
case CAM_ERR_NOT_STILL_INITIALIZED:
Serial.println("Still picture not initialized");
break;
case CAM_ERR_CANT_CREATE_THREAD:
Serial.println("Failed to create thread");
break;
case CAM_ERR_INVALID_PARAM:
Serial.println("Invalid parameter");
break;
case CAM_ERR_NO_MEMORY:
Serial.println("No memory");
break;
case CAM_ERR_USR_INUSED:
Serial.println("Buffer already in use");
break;
case CAM_ERR_NOT_PERMITTED:
Serial.println("Operation not permitted");
break;
default:
break;
}
}
//http post
bool custom_post(const char *url_path, const char *body, uint32_t size) {
char size_string[10];
snprintf(size_string, sizeof(size_string), "%d", size);
theHttpGs2200.config(HTTP_HEADER_CONTENT_LENGTH, size_string);
//Serial.println("Size");
//Serial.println(size_string);
bool result = false;
result = theHttpGs2200.connect();
WiFi_InitESCBuffer();
result = theHttpGs2200.send(HTTP_METHOD_POST, 10, url_path, body, size);
return result;
}
//イメージをpost
void uploadImage(uint16_t* imgBuffer, size_t imageSize) {
Serial.print("imgBuffer is available: ");
Serial.println(imgBuffer != nullptr); // imgBufferがnullでないか確認
Serial.print("Image size: ");
Serial.println(imageSize);
bool result = custom_post(HTTP_POST_PATH, (const uint8_t*)imgBuffer, imageSize);
if (false == result) {
Serial.println("Post Failed");
}
result = false;
do {
result = theHttpGs2200.receive(5000);
if (result) {
theHttpGs2200.read_data(Receive_Data, RECEIVE_PACKET_SIZE);
ConsolePrintf("%s", (char *)(Receive_Data));
} else {
// AT+HTTPSEND command is done
Serial.println("\r\n");
}
} while (result);
result = theHttpGs2200.end();
}
/* カメラ撮影とhttp request postのテスト*/
void camImagePost(){
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"image\":\"%s\"}", "image sending.");
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
Serial.println("==== start Camera Image Post Test");
int take_picture_count = 0;
while (take_picture_count < TOTAL_PICTURE_COUNT) {
Serial.println("call takePicture()");
CamImage img = theCamera.takePicture();
Serial.println("======image info =========== @ cam Image post");
//printPixInfomation(img);
if (img.isAvailable()) {
uint16_t* imgBuffer = (uint16_t*)img.getImgBuff();
size_t imageSize = img.getImgSize();
uploadImage(imgBuffer, imageSize);
} else {
Serial.println("Failed to take picture");
}
take_picture_count++;
}
//theCamera.end();
Serial.println("==== cam Image Post test is finished.\n");
imagePost = false;
}
//推論プリプロセス
void preprocessImage(CamImage& img, DNNVariable& input, const ClipRect& clip) {
if (CAM_CLIP_X + CAM_CLIP_W > CAM_IMG_W || CAM_CLIP_Y + CAM_CLIP_H > CAM_IMG_H) {
Serial.println("Error: Clip region exceeds image boundaries.");
}
CamImage small;
CamErr err = img.clipAndResizeImageByHW(small,
clip.x, clip.y,
clip.x + clip.width - 1,
clip.y + clip.height - 1,
DNN_IMG_W, DNN_IMG_H);
if (err != CAM_ERR_SUCCESS) {
printError(err);
}
if (!small.isAvailable()) {
Serial.println("Error: Clip and Resize failed.");
return;
}
err = small.convertPixFormat(CAM_IMAGE_PIX_FMT_RGB565);
if (err != CAM_ERR_SUCCESS) {
printError(err);
}
uint16_t* tmp = (uint16_t*)small.getImgBuff();
// DNNに入力する輝度データの計算
float* dnnbuf = input.data();
float f_max = 0.0;
for (int n = 0; n < DNN_IMG_H * DNN_IMG_W; ++n) {
uint16_t pixel = tmp[n];
// RGB成分を抽出
float red = (float)((pixel & 0xF800) >> 11) * (255.0 / 31.0); // 5ビット赤
float green = (float)((pixel & 0x07E0) >> 5) * (255.0 / 63.0); // 6ビット緑
float blue = (float)(pixel & 0x001F) * (255.0 / 31.0); // 5ビット青
// 輝度を計算
dnnbuf[n] = 0.299 * red + 0.587 * green + 0.114 * blue;
// 最大値を記録(正規化に使用)
if (dnnbuf[n] > f_max) f_max = dnnbuf[n];
}
// 正規化処理
if (f_max == 0) {
Serial.println("Error: Max value is zero, normalization failed.");
return;
}
// 正規化
for (int n = 0; n < DNN_IMG_W * DNN_IMG_H; ++n) {
dnnbuf[n] /= f_max;
}
}
//イメージデータ情報確認
void printPixInfomation(CamImage& img) {
// ピクセルフォーマットを取得して文字列に変換
int pixFormat = img.getPixFormat(); // 画像オブジェクトからピクセルフォーマットを取得
char format[5]; // 4文字 + 終端文字('\0')
format[0] = pixFormat & 0xFF; // 最下位バイト
format[1] = (pixFormat >> 8) & 0xFF;
format[2] = (pixFormat >> 16) & 0xFF;
format[3] = (pixFormat >> 24) & 0xFF; // 最上位バイト
format[4] = '\0'; // 終端文字
// 画像幅、高さ、サイズ、バッファサイズを取得
int width = img.getWidth();
int height = img.getHeight();
size_t imgSize = img.getImgSize();
size_t bufferSize = img.getImgBuffSize();
// 情報をシリアル出力
Serial.println("==== Image Info ====");
Serial.print("Pixel format: ");
Serial.println(format);
Serial.print("Image width: ");
Serial.println(width);
Serial.print("Image height: ");
Serial.println(height);
Serial.print("Image size (bytes): ");
Serial.println(imgSize);
Serial.print("Buffer size (bytes): ");
Serial.println(bufferSize);
Serial.println("====================");
}
// wifiセットアップ
void GS2200wifiSetup(){
pinMode(LED0, OUTPUT);
digitalWrite(LED0, LOW);
#if defined(iS110_TYPEA)
Init_GS2200_SPI_type(iS110B_TypeA);
#elif defined(iS110_TYPEB)
Init_GS2200_SPI_type(iS110B_TypeB);
#elif defined(iS110_TYPEC)
Init_GS2200_SPI_type(iS110B_TypeC);
#else
#error "No valid device type defined. Please define iS110_TYPEA, iS110_TYPEB, or iS110_TYPEC."
#endif
gsparams.mode = ATCMD_MODE_STATION;
gsparams.psave = ATCMD_PSAVE_DEFAULT;
if (gs2200.begin(gsparams)) {
Serial.println("GS2200 Initilization Fails");
while (1)
;
}
/* GS2200 Association to AP */
if (gs2200.activate_station(AP_SSID, PASSPHRASE)) {
Serial.println("Association Fails");
while (1)
;
}
httpHostParams.host = (char *)HTTP_SRVR_IP;
httpHostParams.port = (char *)HTTP_PORT;
theHttpGs2200.begin(&httpHostParams);
Serial.println("Start HTTP Client");
theHttpGs2200.config(HTTP_HEADER_HOST, HTTP_SRVR_IP);
theHttpGs2200.config(HTTP_HEADER_CONTENT_TYPE, "application/octet-stream");
mqttHostParams.host = (char *)MQTT_SRVR; // MQTTサーバのホスト名
mqttHostParams.port = (char *)MQTT_PORT; // MQTTサーバのポート番号
mqttHostParams.clientID = (char *)MQTT_CLI_ID; // MQTTクライアントID
mqttHostParams.userName = NULL; // ユーザー名(使用しない場合はNULL)
mqttHostParams.password = NULL; // パスワード(使用しない場合はNULL)
theMqttGs2200.begin(&mqttHostParams); // MQTTクライアントを初期化
ConsoleLog( "Start MQTT Client");
if (false == theMqttGs2200.connect()) {
return;
}
ConsoleLog( "Start to receive MQTT Message");
// Prepare for the next chunck of incoming data
WiFi_InitESCBuffer();
// Start the loop to receive the data
strncpy(mqtt.params.topic, MQTT_TOPIC1 , sizeof(mqtt.params.topic));
mqtt.params.QoS = 0;
mqtt.params.retain = 0;
if (true == theMqttGs2200.subscribe(&mqtt)) {
ConsolePrintf( "Subscribed! \n" );
}
strncpy(mqtt.params.topic, MQTT_TOPIC2, sizeof(mqtt.params.topic));
mqtt.params.QoS = 0;
mqtt.params.retain = 0;
}
// MQTTメッセージ送信
void sendMqttMessage(const char* label, float probability, int targetArea, int maxIndex) {
if (maxIndex == 24){
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"result\":\"%s\"}", "not detected.");
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
}
else {
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"result\":\"%s\"}", "Detected SLIM!!");
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
// targetArea用メッセージの準備
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"area\":\"%d\"}", targetArea);
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
// label用メッセージの準備
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"label\":\"%s\"}", label);
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
// probability用メッセージの準備
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"probability\":%f}", probability);
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
}
}
//カメラストリーミングコールバック
void CamCB(CamImage img){
if (!doInferrence) {
return;
}
waitInferrence = true;
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"status\":\"%s\"}", "Taking photos.");
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
Serial.println("\nCamCB Start ++++++++++++++++++ <<@CamCB>>");
//変数初期化
gStrResult = "?";
maxLabel = "?";
targetArea = 0;
maxIndex = 24;
maxOutput = 0.0;
if (!img.isAvailable()) {
Serial.println("Image is not available. Try again");
return;
}
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"status\":\"%s\"}", "Inference");
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
for (int i = 0; i < 17; i++) {
preprocessImage(img, input, clipSet.clips[i]);
startMicros = millis();
dnnrt.inputVariable(input, 0);
dnnrt.forward();
int size = dnnrt.outputSize(0);
DNNVariable output = dnnrt.outputVariable(0);
endMicros = millis();
elapsedTime = endMicros - startMicros;
// text描画
int index = output.maxIndex();
if (i == 0){
targetArea = i;
maxIndex = index;
maxOutput = output[index];
maxLabel = String(label[index]);
}
else{
if (maxIndex == 24){
if (index != 24){
targetArea = i;
maxIndex = index;
maxOutput = output[index];
maxLabel = String(label[index]);
}
}
else {
if (output[index] > maxOutput && index != 24){
targetArea = i;
maxIndex = index;
maxOutput = output[index];
maxLabel = String(label[index]);
}
}
}
if (output[index] >= threshold) {
gStrResult = "index:" + String(index) + " " + String(label[index]) + ":" + String(output[index]) + " / targetArea:" + String(targetArea) +" / maxIndex:" + String(maxIndex) + " / maxOutput:" + String(maxOutput);
} else {
gStrResult = "not identify";
}
Serial.print("index:");
Serial.print(index);
Serial.print(" / ");
Serial.print("-->area:");
Serial.print(i);
Serial.print(" ");
Serial.println(gStrResult);
}
Serial.println("\n****total score======");
Serial.print(" targetArea:");
Serial.println(targetArea);
Serial.print(" maxIndex :");
Serial.println(maxIndex);
Serial.println(" label :" + String(maxLabel));
Serial.println(" prbability:" + String(maxOutput));
Serial.println("****=================");
sendMqttMessage(maxLabel.c_str(), maxOutput, targetArea, maxIndex);
if (selectedImageOnly){
if (maxIndex != 24){
imagePost = true;
}
}
else {
imagePost = false;
}
doInferrence = false;
waitInferrence = false;
delay(2000);
}
//セットアップ
void setup() {
Serial.begin(CONSOLE_BAUDRATE);
while (!Serial) {
;
}
Serial.println(version);
/* Initialize SD */
Serial.println("theSD.begin()");
if(!theSD.begin()) {
Serial.println("SD card mount failed");
nnb_copy = false;
}
/* Initialize SD */
if(!Flash.begin()) {
Serial.println("Flash card mount failed");
}
// ディレクトリを開く
File root = Flash.open("/data");
if (!root || !root.isDirectory()) {
Serial.println("Failed to open directory /data");
return;
}
//SDカード接続時はnnbFile更新
move_nnbFile();
File nnbfile = Flash.open(flashPath);
//File nnbfile = theSD.open("model.nnb");
int ret = dnnrt.begin(nnbfile);
if (ret < 0) {
Serial.println("dnnrt.begin failed" + String(ret));
return;
}
//Pin initialize
pinMode(IN2_LEFT, OUTPUT);
pinMode(IN2_RIGHT, OUTPUT);
pinMode(IN1_LEFT, OUTPUT);
pinMode(IN1_RIGHT, OUTPUT);
digitalWrite(LED0, LOW);
GS2200wifiSetup();
Serial.println("Prepare camera");
err = theCamera.begin();
if (err != CAM_ERR_SUCCESS) {
printError(err);
}
Serial.println("Set Auto white balance parameter");
err = theCamera.setAutoWhiteBalanceMode(CAM_WHITE_BALANCE_DAYLIGHT);
if (err != CAM_ERR_SUCCESS) {
printError(err);
}
Serial.println("Set still picture format");
err = theCamera.setStillPictureImageFormat(
CAM_IMGSIZE_QVGA_H, //320
CAM_IMGSIZE_QVGA_V, //240
CAM_IMAGE_PIX_FMT_JPG
);
if (err != CAM_ERR_SUCCESS) {
printError(err);
}
digitalWrite(LED0, HIGH); // turn on LED
move_nnbFile();
err = theCamera.startStreaming(true, CamCB);
if (err != CAM_ERR_SUCCESS) {
printError(err);
}
delay(20000);
lockWheels();
delay(15000);
unlockWheels();
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"status\":\"%s\"}", "SLIM ready.");
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
delay(3000);
doInferrence = true;
}
//メインループ
void loop() {
delay(FIRST_INTERVAL); /* wait for predefined seconds to take still picture. */
Serial.println("");
Serial.println("loop");
Serial.println("");
checkMQTTtopic();
if (autoSerch){
if (imagePost == true){
camImagePost();
}
Serial.println(maxLabel);
Serial.println(maxOutput);
if (!detectedSLIM && !waitInferrence ){
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"status\":\"%s\"}", "Moving");
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
motor_handler( 25, 50);
delay(1000);
motor_handler( 0, 0);
snprintf(mqtt.params.message, sizeof(mqtt.params.message), "{\"status\":\"%s\"}", "Movement ended.");
printf("Sending JSON: %s\n", mqtt.params.message);
mqtt.params.len = strlen(mqtt.params.message);
theMqttGs2200.publish(&mqtt);
doInferrence = true;
}
}
}
config.h
/*
* config.h - WiFi Configration Header
*
* This work is free software; you can redistribute it and/or modify it under the terms
* of the GNU Lesser General Public License as published by the Free Software Foundation;
* either version 2.1 of the License, or (at your option) any later version.
*
* This work is distributed in the hope that it will be useful, but without any warranty;
* without even the implied warranty of merchantability or fitness for a particular
* purpose. See the GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License along with
* this work; if not, write to the Free Software Foundation,
* Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef _CONFIG_H_
#define _CONFIG_H_
/*-------------------------------------------------------------------------*
* Configration
*-------------------------------------------------------------------------*/
// is110のRev設定
#define iS110_TYPEA //is110_TYPEA, is110_TYPEB, is110_TYPEC,
#define BASE //接続先のパターンを選択
#ifdef BASE
#define AP_SSID "your SSID"
#define PASSPHRASE "your PASS"
#define HTTP_SRVR_IP "HTTP server IP"
#define MQTT_SRVR "MQTT server IP"
#else
#error "No configuration defined. Please define HOME, WORK, or NOTE."
#endif
#define HTTP_PORT "1880"
#define HTTP_GET_PATH "/getdata"
#define HTTP_POST_PATH "/postdata"
#define MQTT_PORT "1883"
#define MQTT_CLI_ID "Telit_Device_pub"
#define MQTT_TOPIC1 "fromNodeRed"
#define MQTT_TOPIC2 "fromSORAQ"
#endif /*_CONFIG_H_*/
Node-RED
[
{
"id": "12cc179dfe3cb70c",
"type": "tab",
"label": "フロー 1",
"disabled": false,
"info": "",
"env": []
},
{
"id": "fc3c4c32c297df8f",
"type": "mqtt out",
"z": "12cc179dfe3cb70c",
"name": "",
"topic": "fromNodeRed",
"qos": "",
"retain": "",
"respTopic": "",
"contentType": "",
"userProps": "",
"correl": "",
"expiry": "",
"broker": "d2d5e28c77a52aa0",
"x": 400,
"y": 320,
"wires": []
},
{
"id": "bc2fd1af7223a29d",
"type": "inject",
"z": "12cc179dfe3cb70c",
"name": "lock wheels",
"props": [
{
"p": "payload"
},
{
"p": "topic",
"vt": "str"
}
],
"repeat": "",
"crontab": "",
"once": false,
"onceDelay": 0.1,
"topic": "",
"payload": "lockWheels,1,2,h,d,1",
"payloadType": "str",
"x": 150,
"y": 200,
"wires": [
[
"fc3c4c32c297df8f"
]
]
},
{
"id": "704da9817f809a8c",
"type": "http in",
"z": "12cc179dfe3cb70c",
"name": "",
"url": "/postdata",
"method": "post",
"upload": false,
"swaggerDoc": "",
"x": 140,
"y": 480,
"wires": [
[
"36a22490187daea2",
"3daf8a88f7caceb9",
"57cda11c135647c0"
]
]
},
{
"id": "57cda11c135647c0",
"type": "image viewer",
"z": "12cc179dfe3cb70c",
"name": "",
"width": "640",
"data": "payload",
"dataType": "msg",
"active": true,
"x": 350,
"y": 520,
"wires": [
[]
]
},
{
"id": "36a22490187daea2",
"type": "change",
"z": "12cc179dfe3cb70c",
"name": "",
"rules": [
{
"t": "set",
"p": "payload",
"pt": "msg",
"to": "data recieved",
"tot": "str"
}
],
"action": "",
"property": "",
"from": "",
"to": "",
"reg": false,
"x": 380,
"y": 480,
"wires": [
[
"0c83261f66763654"
]
]
},
{
"id": "0c83261f66763654",
"type": "http response",
"z": "12cc179dfe3cb70c",
"name": "",
"statusCode": "",
"headers": {},
"x": 590,
"y": 480,
"wires": []
},
{
"id": "3daf8a88f7caceb9",
"type": "debug",
"z": "12cc179dfe3cb70c",
"name": "debug 26",
"active": true,
"tosidebar": true,
"console": false,
"tostatus": false,
"complete": "payload",
"targetType": "msg",
"statusVal": "",
"statusType": "auto",
"x": 360,
"y": 440,
"wires": []
},
{
"id": "dab23ee7f8e989db",
"type": "inject",
"z": "12cc179dfe3cb70c",
"name": "unlock wheels",
"props": [
{
"p": "payload"
},
{
"p": "topic",
"vt": "str"
}
],
"repeat": "",
"crontab": "",
"once": false,
"onceDelay": 0.1,
"topic": "",
"payload": "unlockWheels,1,2,h,d,1",
"payloadType": "str",
"x": 150,
"y": 240,
"wires": [
[
"fc3c4c32c297df8f"
]
]
},
{
"id": "80951ddca26bc32c",
"type": "mqtt in",
"z": "12cc179dfe3cb70c",
"name": "",
"topic": "fromSORAQ",
"qos": "2",
"datatype": "auto-detect",
"broker": "d2d5e28c77a52aa0",
"nl": false,
"rap": true,
"rh": 0,
"inputs": 0,
"x": 590,
"y": 320,
"wires": [
[
"55d51fe18becb213"
]
]
},
{
"id": "6b9161809341cd90",
"type": "debug",
"z": "12cc179dfe3cb70c",
"name": "debug 27",
"active": true,
"tosidebar": true,
"console": false,
"tostatus": false,
"complete": "false",
"statusVal": "",
"statusType": "auto",
"x": 960,
"y": 300,
"wires": []
},
{
"id": "55d51fe18becb213",
"type": "switch",
"z": "12cc179dfe3cb70c",
"name": "",
"property": "payload.label",
"propertyType": "msg",
"rules": [
{
"t": "neq",
"v": "empty",
"vt": "str"
},
{
"t": "eq",
"v": "empty",
"vt": "str"
}
],
"checkall": "true",
"repair": false,
"outputs": 2,
"x": 770,
"y": 320,
"wires": [
[
"6b9161809341cd90"
],
[
"5e16274106d452e2"
]
]
},
{
"id": "5e16274106d452e2",
"type": "debug",
"z": "12cc179dfe3cb70c",
"name": "debug 28",
"active": true,
"tosidebar": true,
"console": false,
"tostatus": false,
"complete": "false",
"statusVal": "",
"statusType": "auto",
"x": 960,
"y": 340,
"wires": []
},
{
"id": "51270f8465095a29",
"type": "inject",
"z": "12cc179dfe3cb70c",
"name": "auto serch mode ON",
"props": [
{
"p": "payload"
},
{
"p": "topic",
"vt": "str"
}
],
"repeat": "",
"crontab": "",
"once": false,
"onceDelay": 0.1,
"topic": "",
"payload": "autoON,1,2,h,d,1",
"payloadType": "str",
"x": 170,
"y": 320,
"wires": [
[
"fc3c4c32c297df8f"
]
]
},
{
"id": "0af648ffdd9030fc",
"type": "inject",
"z": "12cc179dfe3cb70c",
"name": "auto serch mode OFF",
"props": [
{
"p": "payload"
},
{
"p": "topic",
"vt": "str"
}
],
"repeat": "",
"crontab": "",
"once": false,
"onceDelay": 0.1,
"topic": "",
"payload": "autoOFF,13444,29390,hello,dfa,128",
"payloadType": "str",
"x": 180,
"y": 360,
"wires": [
[
"fc3c4c32c297df8f"
]
]
},
{
"id": "ea0db7581c55561a",
"type": "aedes broker",
"z": "12cc179dfe3cb70c",
"name": "",
"mqtt_port": 1883,
"mqtt_ws_bind": "port",
"mqtt_ws_port": "",
"mqtt_ws_path": "",
"cert": "",
"key": "",
"certname": "",
"keyname": "",
"persistence_bind": "memory",
"dburl": "",
"usetls": false,
"x": 150,
"y": 100,
"wires": [
[],
[]
]
},
{
"id": "d2d5e28c77a52aa0",
"type": "mqtt-broker",
"name": "central_server",
"broker": "localhost",
"port": "1883",
"clientid": "",
"autoConnect": true,
"usetls": false,
"protocolVersion": "4",
"keepalive": "60",
"cleansession": true,
"autoUnsubscribe": true,
"birthTopic": "",
"birthQos": "0",
"birthRetain": "false",
"birthPayload": "",
"birthMsg": {},
"closeTopic": "",
"closeQos": "0",
"closeRetain": "false",
"closePayload": "",
"closeMsg": {},
"willTopic": "",
"willQos": "0",
"willRetain": "false",
"willPayload": "",
"willMsg": {},
"userProps": "",
"sessionExpiry": ""
}
]
おまけ SLIMスケールモデル制作!
SLIMのスケールモデルはJAXAが公開している3Dモデルをベースとして3Dプリントしています。しかしながら、このモデルは3Dプリント向けのデータではないため、出力するためには大幅に手直しが必要で、手直ししたとしても出力困難な形状を多く含みます。
今回は3Dモデル上での修正は行わず、そのまま出力したモデルの欠落部のみを修正、追加工するものとしました。
そのまま出力
そのまま出力したSLIMの姿です。
出力用のモデルに変換する際、スラスタやPVパネル、一部の着陸脚や分光カメラなどが消えてしまいました。
無理のない厚み、形状で再設計して追加する必要があります。
追加工① スラスタ
スラスタは宇宙機らしさを表現する最重要パーツです。メインスイラスタ2本とアポジモーター12本を再設計して出力の上エッジ部を研磨して薄肉化ししました
メインスラスタは着脱可能で、実際の月着陸時の一本脱落状態を再現可能です。
追加工② PVパネル
SLIMのデザイン上もっとも特徴的な、推進剤タンクを避けて湾曲したPVパネルです。精密さを出すためには取付ブラケット形状なども再現したかったのですが、工数削減のためにオミットしました(TT)
個々のPVセルの塗分けなども大変なので、コピー用紙にカラー印刷して貼りつけ、光沢スプレー塗布でそれっぽさを出しています。
追加工③ その他部品
月面観測用分光カメラや着陸レーダーアンテナなど、3Dプリント時に欠損した部品を再設計して取り付けています。
外観イメージはほぼほぼ再現できました。
完成
おわりに
昨年のSPRESENSEコンテストのエントリー用記事を書いているさなか、SLIMの月面着陸のニュースを見ました。SLIM着陸成功までの大冒険に感動し、さらにその見事な写真を撮ったLEV-2の中ではSPRESENSEが動いているのだと思うととてもわくわくしました。
以前から、この改造ネタはあたためていたmしたが、コンテストへのエントリーの機会やモニター提供によるご支援がなければ実現が難しかったと思います。
貴重な機会をいただきありがとうございました。
投稿者の人気記事
-
airpocket
さんが
2025/01/21
に
編集
をしました。
(メッセージ: 初版)
-
airpocket
さんが
2025/01/21
に
編集
をしました。
-
airpocket
さんが
2025/01/21
に
編集
をしました。
-
airpocket
さんが
2025/01/21
に
編集
をしました。
-
airpocket
さんが
2025/01/21
に
編集
をしました。
-
airpocket
さんが
2025/01/22
に
編集
をしました。
-
airpocket
さんが
2025/01/22
に
編集
をしました。
-
airpocket
さんが
2025/01/22
に
編集
をしました。
-
airpocket
さんが
2025/01/22
に
編集
をしました。
ログインしてコメントを投稿する