Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[WIP] add ROS interface for JINS MEME smart glass #454

Draft
wants to merge 1 commit into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
54 changes: 54 additions & 0 deletions jins_meme_ros/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
devel/
logs/
build/
bin/
lib/
msg_gen/
srv_gen/
msg/*Action.msg
msg/*ActionFeedback.msg
msg/*ActionGoal.msg
msg/*ActionResult.msg
msg/*Feedback.msg
msg/*Goal.msg
msg/*Result.msg
msg/_*.py
build_isolated/
devel_isolated/

# Generated by dynamic reconfigure
*.cfgc
/cfg/cpp/
/cfg/*.py

# Ignore generated docs
*.dox
*.wikidoc

# eclipse stuff
.project
.cproject

# qcreator stuff
CMakeLists.txt.user

srv/_*.py
*.pcd
*.pyc
qtcreator-*
*.user

/planning/cfg
/planning/docs
/planning/src

*~

# Emacs
.#*

# Catkin custom files
CATKIN_IGNORE
.vscode/*
node_modules/*
package-lock.json
16 changes: 16 additions & 0 deletions jins_meme_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
cmake_minimum_required(VERSION 3.0.2)
project(jins_meme_ros)

find_package(catkin REQUIRED COMPONENTS message_generation)

add_message_files(
FILES
CurrentData.msg
LogicIndexData.msg
)

generate_messages()

catkin_package(
CATKIN_DEPENDS message_runtime
)
18 changes: 18 additions & 0 deletions jins_meme_ros/msg/CurrentData.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
# https://jins-meme.github.io/sdkdoc2/basics/definition.html
int32 blinkSpeed # まばたき速度、閉眼時間(mSec) 0-400(通常90−180付近)
int32 blinkStrength # まばたき強度(uV-equiv) 0-1000(通常30−150付近)
int32 eyeMoveUp # 視線移動上(0: 動きなし, 1:極小-7:極大)
int32 eyeMoveDown # 視線移動下(0: 動きなし, 1:極小-7:極大)
int32 eyeMoveLeft # 視線移動左(0: 動きなし, 1:極小-7:極大)
int32 eyeMoveRight # 視線移動右(0: 動きなし, 1:極小-7:極大)
float32 roll # 姿勢角のロール成分(左右傾き)を示す度 -180.00 - 180.00
float32 pitch # 角度P(-180 - 180)
float32 yaw # 角度Y(0 - 360)
float32 accX # 加速度X(1G = 16)
float32 accY # 加速度Y(1G = 16)
float32 accZ # 加速度Z(1G = 16)
int32 walking # 歩行フラグ(0: 静止, 1: 一歩)
int32 noiseStatus # ノイズ状態(0: ノイズなし, 1: ノイズあり)
int32 fitError # 装着フラグ(0: 着用, 1: 非着用)
int32 powerLeft # バッテリーレベル(0: 充電中, 1:空-5:満充電)
int32 sequenceNumber # 0-255までの循環連番
66 changes: 66 additions & 0 deletions jins_meme_ros/msg/LogicIndexData.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
# https://jins-meme.github.io/sdkdoc2/basics/definition.html
string date # 計測日時 2000-01-01T00:00:00 - 2099-12-31T23:59:59
int32 stepCount # 歩数 0-255
int32 stepCadance # ケイデンス(ピッチ) 0-255
bool isStill # 静止(装着してない)判定 true: 非装着(静止) false: 装着中(非静止)
float32 noiseTime # ノイズ時間 0.00 - 15.00
bool isValid # 静止状態のデータ有効性(ノイズ3秒以下かつ歩数5歩以下) true: 有効 false: 無効
float32 xMean # 傾き平均X (度) -180.00-180.00
float32 xSD # 傾き標準偏差X (度) 0-655.36
float32 yMean # 傾き平均Y (度) -180.00-180.00
float32 ySD # 傾き標準偏差Y (度) 0-655.36
int32 pitchOnewayCount # Number(int) 頭部運動縦回数 0-255
int32 pitchRoundCount # ゆっくりな首の傾斜前後回数 0-255
int32 yawOnewayCount # 頭部運動横回数 0-255
int32 yawRoundCount # ゆっくりな首の傾斜左右回数 0-255
float32 xRightStepAmplitude # 歩行振動X(cm,右足) 0.00-16.00
float32 xLeftStepAmplitude # 歩行振動X(cm,左足) 0.00-16.00
float32 yRightStepAmplitude # 歩行振動Y(cm,右足) 0.00-16.00
float32 yLeftStepAmplitude # 歩行振動Y(cm,左足) 0.00-16.00
float32 zRightStepAmplitude # 歩行振動Z(cm,右足) 0.00-16.00
float32 zLeftStepAmplitude # 歩行振動Z(cm,左足) 0.00-16.00
float32 zRightStepAmplitudeCal # 歩行振動Z補正有(cm,右足) 0.00-20.00
float32 zLeftStepAmplitudeCal # 歩行振動Z補正有(cm,左足) 0.00-20.00
float32 maxRightStepAcceleration # Number(float) 最大着地強度平均 (G, 右足) 0.00-8.00
float32 maxLeftStepAcceleration # 最大着地強度平均 (G, 左足) 0.00-8.00
float32 sleepScoreStandard # 低覚醒スコア(通常時)、まばたき強さ・速度と一部まばたき間隔から「目がトロンとなっている状態」を指標化したもの 有効時: 0(覚醒高い)-100(眠い)、無効: -1
float32 sleepScore # 低覚醒スコア(運転時)、運転時の姿勢(まっすぐ前を向いている状態)でクレンジングし、精度を高めたもの 有効時: 0(覚醒高い)-100(眠い)、無効: -1
float32 focusScore # 没入スコア、まばたき間隔を利用し「ある一つのタスクへの注意が続いている状態」を指標化したもの 有効時: 0(没入度が低い)-100(没入度が高い)、無効: -1
float32 tensionScore # テンションスコア、まばたき強さを利用し「目が見開いている状態」を指標化したもの 有効時: 0(緊張が弱い)-100(緊張が強い)、無効: -1
float32 calmScore # 安定スコア、まばたき強さを利用し「外部・内部刺激を受けずに安定している状態」を指標化したもの 有効時: 0(落ち着いていない)-100(落ち着いている)、無効: -1
float32 distance # サブアプリ動作時 前回区間との移動距離(m) 0-5000
float32 latitude # サブアプリ動作時 緯度 -180 - 180
float32 longitude # サブアプリ動作時 経度 -90 - 90
int32 appMeasurementStatus # サブアプリの動作状況フラグ 0: 非APP測定 2: Run測定中 3: Run一時停止中 8: Drive測定中 12: Drive一時停止中 32: Focus測定中 48: Focus一時停止中
float32 nptMean # NPT(実効まばたき速度)平均 -0.999 - 0.999
float32 nptMedian # NPT(実効まばたき速度)中央値 -0.999 - 0.999
float32 nptSD # NPT標準偏差 0-0.999
float32 blinkWidthMean # まばたき速度平均(mSec) 0-300
float32 blinkStrengthTotal # まばたき強度合計(uV-equiv) 0-10000.0
float32 blinkStrengthMax # まばたき強度最大(uV-equiv) 0-1000.0
float32 blinkStrengthSD # まばたき強度標準偏差(uV-equiv) 0.00-1000.0
float32 blinkStrengthMean # まばたき強度平均 0-1000.0
float32 blinkIntervalTotal # まばたき間隔合計(s) 0-120.0
int32 blinkIntervalCount # まばたき間隔数 0-120
float32 blinkIntervalMean # まばたき間隔平均 0.00-60.00
int32 blinkCount # まばたき回数 0-120
int32 blinkCountRaw # まばたき回数生値 0-255
int32 eyeMoveUpCount # 視線移動上回数生値 0-255
int32 eyeMoveDownCount # 視線移動下回数生値 0-255
int32 eyeMoveRightCount # 視線移動右回数生値 0-255
int32 eyeMoveLeftCount # 視線移動左回数生値 0-255
uint32 cummulativeTime # 規格化累積時間(s) 0-4294967296
float32 blinkIntervalMeanWA # まばたき間隔平均 規格化値 0.00-60.00
float32 blinkStrengtnSDWA # まばたき強度標準偏差 規格化値 0.00-1000.0
float32 blinkStrengthMeanWA # まばたき強度平均 規格化値 0-1000.0
float32 nptMeanWA # NPT(実効まばたき速度)平均 規格化値 -0.999 - 0.999
float32 nptSDWA # NPT(実効まばたき速度)標準偏差 規格化値 0-0.999
float32 blinkWidthMeanWA # まばたき速度平均 規格化値 0-300
float32 nptScore # 覚醒サブ指標 NPTスコア 有効時: 0-100、無効: -1
float32 btsScore # 覚醒サブ指標 BTSスコア 有効時: 0-100、無効: -1
float32 lbsScore # 覚醒サブ指標 LBSスコア 有効時: 0-100、無効: -1
int32 legacyZone # RTアルゴリズム動作時 zone値 有効時: 0-100、無効: -1
int32 legacyFocus # RTアルゴリズム動作時 focus値 有効時: 0-100、無効: -1
int32 legacyCalm # RTアルゴリズム動作時 calm値 有効時: 0-100、無効: -1
int32 legacyPosture # RTアルゴリズム動作時 posture値 有効時: 0-100、無効: -1
string cursor # 次のレコードがある場合の取得開始位置
23 changes: 23 additions & 0 deletions jins_meme_ros/package.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
{
"name": "jins_meme_ros",
"version": "1.0.0",
"description": "",
"main": "index.js",
"scripts": {
"test": "echo \"Error: no test specified\" && exit 1"
},
"repository": {
"type": "git",
"url": "git+https://github.com/sktometometo/jins_meme_ros.git"
},
"author": "",
"license": "ISC",
"bugs": {
"url": "https://github.com/sktometometo/jins_meme_ros/issues"
},
"homepage": "https://github.com/sktometometo/jins_meme_ros#readme",
"dependencies": {
"rosnodejs": "^3.1.0",
"ws": "^8.13.0"
}
}
19 changes: 19 additions & 0 deletions jins_meme_ros/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0"?>
<package format="2">
<name>jins_meme_ros</name>
<version>0.0.0</version>
<description>The jins_meme_ros package</description>

<maintainer email="[email protected]">sktometometo</maintainer>

<license>TODO</license>

<build_depend>message_generation</build_depend>
<build_export_depend>message_generation</build_export_depend>
<exec_depend>message_runtime</exec_depend>
<buildtool_depend>catkin</buildtool_depend>


<export>
</export>
</package>
105 changes: 105 additions & 0 deletions jins_meme_ros/scripts/websocket_server.js
Original file line number Diff line number Diff line change
@@ -0,0 +1,105 @@
#!/usr/bin/env node
'use strict';

const rosnodejs = require('rosnodejs');
const jins_meme_ros = rosnodejs.require('jins_meme_ros').msg;

const server = require('ws').Server;
const ws_server = new server({ port: 5000 });


function main() {
rosnodejs.initNode('/').then((rosNode) => {
let pub_current_data = rosNode.advertise('current_data', jins_meme_ros.CurrentData);
let pub_logic_index_data = rosNode.advertise('logic_index_data', jins_meme_ros.LogicIndexData);
ws_server.on("connection", ws => {
rosnodejs.log.info("connected from client");
ws.on('message', function (message) {
if (message.indexOf("heartbeat") === -1) {
let data = JSON.parse(message);
if ("eyeMoveUp" in data) {
let msg = new jins_meme_ros.CurrentData();
msg.blinkSpeed = data["blinkSpeed"];
msg.blinkStrength = data["blinkStrength"];
msg.eyeMoveUp = data["eyeMoveUp"];
msg.eyeMoveDown = data["eyeMoveDown"];
msg.eyeMoveLeft = data["eyeMoveLeft"];
msg.eyeMoveRight = data["eyeMoveRight"];
msg.roll = data["roll"];
msg.pitch = data["pitch"];
msg.yaw = data["yaw"];
msg.accX = data["accX"];
msg.accY = data["accY"];
msg.accZ = data["accZ"];
msg.walking = data["walking"];
msg.noiseStatus = data["noiseStatus"];
msg.fitError = data["fitError"];
msg.powerLeft = data["powerLeft"];
msg.sequenceNumber = data["sequenceNumber"];
pub_current_data.publish(msg);
rosnodejs.log.info("published.");
} else if (false) {
let msg = new jins_meme_ros.LogicIndexData();
msg.date = data["date"];
msg.stepCount = data["stepCount"];
msg.blinkCountRaw = data["blinkCountRaw"];
msg.eyeMoveUpCount = data["eyeMoveUpCount"];
msg.eyeMoveDownCount = data["eyeMoveDownCount"];
msg.eyeMoveRightCount = data["eyeMoveRightCount"];
msg.eyeMoveLeftCount = data["eyeMoveLeftCount"];
msg.isStill = data["isStill"];
msg.xMean = data["xMean"];
msg.xSD = data["xSD"];
msg.yMean = data["yMean"];
msg.ySD = data["ySD"];
msg.pitchOnewayCount = data["pitchOnewayCount"];
msg.pitchRoundCount = data["pitchRoundCount"];
msg.yawOnewayCount = data["yawOnewayCount"];
msg.yawRoundCount = data["yawRoundCount"];
msg.xRightStepAmplitude = data["xRightStepAmplitude"];
msg.xLeftStepAmplitude = data["xLeftStepAmplitude"];
msg.yRightStepAmplitude = data["yRightStepAmplitude"];
msg.yLeftStepAmplitude = data["yLeftStepAmplitude"];
msg.zRightStepAmplitude = data["zRightStepAmplitude"];
msg.zLeftStepAmplitude = data["zLeftStepAmplitude"];
msg.zRightStepAmplitudeCal = data["zRightStepAmplitudeCal"];
msg.zLeftStepAmplitudeCal = data["zLeftStepAmplitudeCal"];
msg.maxRightStepAcceleration = data["maxRightStepAcceleration"];
msg.maxLeftStepAcceleration = data["maxLeftStepAcceleration"];
msg.stepCadence = data["stepCadence"];
msg.blinkIntervalMean = data["blinkIntervalMean"];
msg.blinkStrengthMean = data["blinkStrengthMean"];
msg.blinkStrengthSD = data["blinkStrengthSD"];
msg.blinkWidthMean = data["blinkWidthMean"];
msg.nptMean = data["nptMean"];
msg.nptSD = data["nptSD"];
msg.blinkCount = data["blinkCount"];
msg.blinkIntervalCount = data["blinkIntervalCount"];
msg.blinkIntervalTotal = data["blinkIntervalTotal"];
msg.blinkStrengthTotal = data["blinkStrengthTotal"];
msg.blinkStrengthMax = data["blinkStrengthMax"];
msg.nptMedian = data["nptMedian"];
msg.noiseTime = data["noiseTime"];
msg.isValid = data["isValid"];
msg.sleepScore = data["sleepScore"];
msg.focusScore = data["focusScore"];
msg.tensionScore = data["tensionScore"];
msg.calmScore = data["calmScore"];
msg.sleepScoreStandard = data["sleepScoreStandard"];
pub_logic_index_data.publish(msg);
rosnodejs.log.info("published.");
} else {
//メッセージを出力
console.info(data);
}
} else {
rosnodejs.log.info("heatbeat: %s", message);
}
});
});
});
}

if (require.main === module) {
main()
}