diff --git a/eus_caffe/CMakeLists.txt b/eus_caffe/CMakeLists.txt new file mode 100644 index 000000000..0c5fc7cc7 --- /dev/null +++ b/eus_caffe/CMakeLists.txt @@ -0,0 +1,58 @@ +project(eus_caffe) + +cmake_minimum_required(VERSION 2.4.6) + +find_package(catkin COMPONENTS cmake_modules) +## find_package(OMPL REQUIRED) + +MESSAGE(" -- install caffe") +execute_process(COMMAND cmake -E chdir ${PROJECT_SOURCE_DIR} bash make.sh) +set(CAFFE_ROOT_DIR ${PROJECT_SOURCE_DIR}/3rdparty/caffe) +# execute_process(COMMAND locate caffe +# COMMAND grep -e "/caffe$" +# COMMAND head -1 +# OUTPUT_VARIABLE CAFFE_ROOT_DIR +# OUTPUT_STRIP_TRAILING_WHITESPACE +# ) +MESSAGE(" -- find caffe: {CAFFE_ROOT_DIR}") + +include_directories(${PROJECT_SOURCE_DIR}/src) +include_directories(${PROJECT_SOURCE_DIR}/3rdparty/include) +include_directories(${CAFFE_ROOT_DIR}/include) +include_directories(${CAFFE_ROOT_DIR}/.build_release/src) + +set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +set(CMAKE_CXX_FLAGS "-DCPU_ONLY -std=c++0x") + +catkin_package() + +## add_executable(eus_caffe_test src/test.cpp) +## TARGET_LINK_LIBRARIES(eus_caffe_test /home/noda/prog/euslib/demo/s-noda/tmp-ros-package/caffe/.build_release/lib/libcaffe.so /usr/local/lib/libglog.so.0) + +MESSAGE(" -- build caffe") + +add_library(eus_caffe SHARED src/eus_caffe_lib.cpp) +target_link_libraries(eus_caffe ${CAFFE_ROOT_DIR}/.build_release/lib/libcaffe.so) +target_link_libraries(eus_caffe ${PROJECT_SOURCE_DIR}/3rdparty/glog-0.3.3/.libs/libglog.so) +target_link_libraries(eus_caffe ${PROJECT_SOURCE_DIR}/3rdparty/mdb/libraries/liblmdb/liblmdb.so) +## target_link_libraries(eus_caffe ${CAFFE_ROOT_DIR}/.build_release/lib/libcaffe.so ${CAFFE_ROOT_DIR}/3rdparty/glog-0.3.3/.libs/libglog.so.0 /usr/local/cuda-7.0/lib64/libcudart.so.7.0 /usr/local/cuda-7.0/lib64/libcublas.so.7.0 /usr/local/cuda-7.0/lib64/libcurand.so.7.0) +## target_link_libraries(eus_caffe ${CAFFE_ROOT_DIR}/.build_release/lib/libcaffe.so) +# target_link_libraries(eus_caffe ${CAFFE_ROOT_DIR}/3rdparty/glog-0.3.3/.libs/libglog.so.0) +# target_link_libraries(eus_caffe /usr/local/cuda-7.0/lib64/libcudart.so.7.0) +# target_link_libraries(eus_caffe /usr/local/cuda-7.0/lib64/libcublas.so.7.0) +# target_link_libraries(eus_caffe /usr/local/cuda-7.0/lib64/libcurand.so.7.0) + +add_library(eus_caffe_db SHARED src/eus_caffe_db_lib.cpp) +target_link_libraries(eus_caffe_db ${CAFFE_ROOT_DIR}/.build_release/lib/libcaffe.so) +target_link_libraries(eus_caffe_db ${PROJECT_SOURCE_DIR}/3rdparty/glog-0.3.3/.libs/libglog.so) +target_link_libraries(eus_caffe_db ${PROJECT_SOURCE_DIR}/3rdparty/mdb/libraries/liblmdb/liblmdb.so) +##target_link_libraries(eus_caffe_db ${CAFFE_ROOT_DIR}/3rdparty/glog-0.3.3/.libs/libglog.so.0) +## target_link_libraries(eus_caffe_db ${CAFFE_ROOT_DIR}/.build_release/lib/libcaffe.so ${CAFFE_ROOT_DIR}/3rdparty/glog-0.3.3/.libs/libglog.so.0 /usr/local/cuda-7.0/lib64/libcudart.so.7.0 /usr/local/cuda-7.0/lib64/libcublas.so.7.0 /usr/local/cuda-7.0/lib64/libcurand.so.7.0) + +add_library(eus_log SHARED src/eus_log_lib.cpp) + +# execute_process(COMMAND ln -s ${CAFFE_ROOT_DIR}/3rdparty/glog-0.3.3/.libs/libglog.so.0 ${CATKIN_DEVEL_PREFIX}/lib) +# execute_process(COMMAND ln -s ${CAFFE_ROOT_DIR}/3rdparty/mdb/libraries/liblmdb/liblmdb.so ${CATKIN_DEVEL_PREFIX}/lib) +# execute_process(COMMAND ln -s ${CAFFE_ROOT_DIR}/.build_release/lib/libcaffe.so ${CATKIN_DEVEL_PREFIX}/lib) diff --git a/eus_caffe/README.md b/eus_caffe/README.md new file mode 100644 index 000000000..84bd3e81a --- /dev/null +++ b/eus_caffe/README.md @@ -0,0 +1,21 @@ +# eus_caffe + +euslisp wrapper of caffe deep learning package. + +## install + +`catkin build eus_caffe;` + +## demo + +``` +roscd eus_caffe; +cd sample/linear_equation; +roseus learn.l +(setq *teacher* (gen+3x-2y+4-data :size 3200)) ;; sample 3x-2y+4=0 +(caffe::learn :solver "linear_equation.prototxt" :size 3200 :idata (car *teacher*) :ddata (cadr *teacher*)) +(caffe::gen-test-net :netproto "predict_linear_equation_net.prototxt" :caffemodel "linear_equation_iter_100000.caffemodel") +(caffe::calc-forward-double :input (float-vector 0 0)) ;; +3*0-2*0+4 = 4 +(caffe::calc-forward-double :input (float-vector 0 2)) ;; +3*0-2*2+4 = 0 +(caffe::calc-forward-double :input (float-vector 2 5)) ;; +3*2-2*5+4 = 0 +``` diff --git a/eus_caffe/euslisp/eus-caffe-db.l b/eus_caffe/euslisp/eus-caffe-db.l new file mode 100644 index 000000000..95a6d78ca --- /dev/null +++ b/eus_caffe/euslisp/eus-caffe-db.l @@ -0,0 +1,293 @@ +#!/usr/bin/env roseus + +(require "eus-plugin-util.l") + +(if (not (find-package "CAFFE")) (make-package "CAFFE")) +(In-package "CAFFE") + +(defvar *eus-caffe-db-plugin* (user::gen-plugin-obj "libeus_caffe_db.so")) + +(defforeign db-set-id *eus-caffe-db-plugin* "eus_caffe_db_set_id" (:integer) :integer) +(defforeign _db-open *eus-caffe-db-plugin* "eus_caffe_db_open" (:string :string :integer) :integer) +(defforeign db-reopen *eus-caffe-db-plugin* "eus_caffe_db_reopen" () :integer) +(defforeign _db-put *eus-caffe-db-plugin* "eus_caffe_db_put" (:integer :integer :integer :integer :string :string :integer) :integer) +(defforeign _db-put-double *eus-caffe-db-plugin* "eus_caffe_db_put_double" (:integer :integer :integer :integer :string :string :integer) :integer) +(defforeign db-commit *eus-caffe-db-plugin* "eus_caffe_db_commit" () :integer) +(defforeign db-close *eus-caffe-db-plugin* "eus_caffe_db_close" () :integer) +(defforeign db-read *eus-caffe-db-plugin* "eus_caffe_db_read" (:integer) :integer) +(defforeign db-read-pos *eus-caffe-db-plugin* "eus_caffe_db_read_pos" (:integer) :integer) +(defforeign db-dump *eus-caffe-db-plugin* "eus_caffe_db_dump" () :integer) +(defforeign db-get-size *eus-caffe-db-plugin* "eus_caffe_db_get_size" () :integer) +(defforeign _db-get-shape *eus-caffe-db-plugin* "eus_caffe_db_get_shape" (:string) :integer) +(defforeign _db-get-key *eus-caffe-db-plugin* "eus_caffe_db_get_key" (:string) :integer) +(defforeign db-get-label *eus-caffe-db-plugin* "eus_caffe_db_get_label" () :integer) +(defforeign _db-get-data *eus-caffe-db-plugin* "eus_caffe_db_get_data" (:string) :integer) +(defforeign _db-get-float-data *eus-caffe-db-plugin* "eus_caffe_db_get_float_data" (:string) :integer) +(defforeign db-get-key-size *eus-caffe-db-plugin* "eus_caffe_db_get_key_size" () :integer) +(defforeign db-get-data-size *eus-caffe-db-plugin* "eus_caffe_db_get_data_size" () :integer) +(defforeign db-get-float-data-size *eus-caffe-db-plugin* "eus_caffe_db_get_float_data_size" () :integer) + +(defun zero-string + (i &optional + (length 5) + (ret (instantiate string length)) + (istr (format nil "~A" i))) + (dotimes (j length) + (setf (aref ret j) + (if (>= j (- length (length istr))) + (aref istr (min (length istr) + (- j (- length (length istr))))) + #\0))) + ret) + +(defun db-open + (&key (dtype "lmdb") (path "test") (mode #\r)) + (_db-open dtype path mode)) + +(defun db-put + (&key (channels 1) (width 1) (height 1) (label 1) (id_str "000") (data "")) + (_db-put channels width height label id_str data (length data))) + +(defun db-put-double + (&key (channels 1) (width 1) (height 1) (label 1) (id_str "000") (data (float-vector 0))) + (_db-put-double channels width height label id_str data (length data))) + +(defun db-get-key + (&key (ret (instantiate string (db-get-key-size)))) + (_db-get-key ret) + ret) + +(defun db-get-data + (&key (ret (instantiate string (db-get-data-size)))) + (_db-get-data ret) + ret) + +(defun db-get-float-data + (&key (ret (instantiate float-vector (db-get-float-data-size)))) + (_db-get-float-data ret) + ret) + +(defun db-get-shape + (&key (ret (instantiate float-vector 3))) + (_db-get-shape ret) + ret) + +(defun db-swap-fast + (id1 id2 + &key + ;; (step 300) + (pos 0) + (size (db-get-size)) + ;; (id1 (random step)) + ;; (id2 (random step)) + (pos1 (mod (+ pos id1) size)) + (pos2 (mod (+ pos1 id2) size)) + (pos-list) + (max-pos-list-size 10000) + key1 val1 cval1 shape1 label1 + key2 val2 cval2 shape2 label2) + (cond + ((or ;; (>= (+ pos id1 id2) size) + (find pos1 pos-list) + (find pos2 pos-list) + (> (length pos-list) max-pos-list-size)) + ;; (return-from db-swap-fast pos-list) + ;; (db-commit) + (db-reopen) + (setq pos 0) + (setq pos1 (mod (+ pos id1) size)) + (setq pos2 (mod (+ pos1 id2) size)) + (setq pos-list nil))) + ;; + (db-read id1) + (setq key1 (copy-seq (db-get-key))) + (setq cval1 (copy-seq (db-get-data))) + (setq val1 (copy-seq (db-get-float-data))) + (setq shape1 (coerce (copy-seq (db-get-shape)) integer-vector)) + (setq label1 (db-get-label)) + ;; + (db-read id2) + (setq key2 (copy-seq (db-get-key))) + (setq cval2 (copy-seq (db-get-data))) + (setq val2 (copy-seq (db-get-float-data))) + (setq shape2 (coerce (copy-seq (db-get-shape)) integer-vector)) + (setq label2 (db-get-label)) + ;; + (apply + (if (and cval2 (plusp (length cval2))) 'db-put 'db-put-double) + (list :channels (aref shape2 0) :width (aref shape2 1) :height (aref shape2 2) + :label label2 :id_str key1 + :data + (if (and cval2 (plusp (length cval2))) cval2 val2))) + (apply + (if (and cval1 (plusp (length cval1))) 'db-put 'db-put-double) + (list :channels (aref shape1 0) :width (aref shape1 1) :height (aref shape1 2) + :label label1 :id_str key2 + :data + (if (and cval1 (plusp (length cval1))) cval1 val1))) + (append (list pos1 pos2) pos-list) + ) + +(defun db-random-swap-fast + (_cnt + &key + (step 300) + (id1) (id2) + (size (db-get-size)) + (pos-list nil) + (pos 0) + (id-list '(0 1)) buf) + (dotimes (i _cnt) + (setq id1 (+ 1 (random step))) + (setq id2 (+ 1 (random step))) + (dolist (id id-list) + (db-set-id id) + (setq buf (db-swap-fast id1 id2 :pos pos :size size :pos-list pos-list)) + ) + (setq pos-list buf) + ;; (format t "swap ~A <-> ~A~%" (car pos-list) (cadr pos-list)) + (setq pos (cadr pos-list)) + )) + +(defun db-swap + (id1 id2 &key + key1 val1 cval1 shape1 label1 + key2 val2 cval2 shape2 label2) + ;; + (db-read-pos id1) + (setq key1 (copy-seq (db-get-key))) + (setq cval1 (copy-seq (db-get-data))) + (setq val1 (copy-seq (db-get-float-data))) + (setq shape1 (coerce (copy-seq (db-get-shape)) integer-vector)) + (setq label1 (db-get-label)) + ;; + (db-read-pos id2) + (setq key2 (copy-seq (db-get-key))) + (setq cval2 (copy-seq (db-get-data))) + (setq val2 (copy-seq (db-get-float-data))) + (setq shape2 (coerce (copy-seq (db-get-shape)) integer-vector)) + (setq label2 (db-get-label)) + ;; + (apply + (if (and cval2 (plusp (length cval2))) 'db-put 'db-put-double) + (list :channels (aref shape2 0) :width (aref shape2 1) :height (aref shape2 2) + :label label2 :id_str key1 + :data + (if (and cval2 (plusp (length cval2))) cval2 val2))) + (apply + (if (and cval1 (plusp (length cval1))) 'db-put 'db-put-double) + (list :channels (aref shape1 0) :width (aref shape1 1) :height (aref shape1 2) + :label label1 :id_str key2 + :data + (if (and cval1 (plusp (length cval1))) cval1 val1)))) + +(defun db-random-swap + (_cnt + &key + (size (db-get-size)) + (id-list '(0 1))) + (labels ((_db-random-swap + (_cnt + &key + (size (db-get-size)) + (cnt (min _cnt (/ 1000 2) (/ size 2))) + (id-vector + (let* ((l (user::random-sample-indices (* cnt 2) :max size)) + (v (coerce l integer-vector))) + (user::random-vector-swap v :cnt (* 2 cnt)))) + (id-list '(0 1))) + (dotimes (i cnt) + (setq rand1 (aref id-vector (+ 0 (* 2 i)))) + (setq rand2 (aref id-vector (+ 1 (* 2 i)))) + (dolist (id id-list) + (db-set-id id) + (db-swap rand1 rand2) + )) + cnt)) + (while (> (setq _cnt (- _cnt (_db-random-swap _cnt :size size :id-list id-list))) 0) + (dolist (id id-list) + (db-set-id id) + (db-commit))))) + + +#| + +(unix::system "rm -rf hoge fuga") +(caffe::db-set-id 0) +(caffe::db-open :path "hoge" :mode #\n) +(caffe::db-set-id 1) +(caffe::db-open :path "fuga" :mode #\n) +(dotimes (i 100000) + (caffe::db-set-id 0) + (caffe::db-put + :channels i :width i :height i :label i :id_str (format nil "~A" i) + :data (format nil "hoge~A" i)) + (caffe::db-set-id 1) + (caffe::db-put-double + :channels i :width i :height i :label i :id_str (format nil "~A" i) + :data (float-vector i))) +(caffe::db-set-id 0) +(caffe::db-close) +(caffe::db-set-id 1) +(caffe::db-close) + +(caffe::db-set-id 0) +(caffe::db-open :path "hoge" :mode #\w) +(caffe::db-set-id 1) +(caffe::db-open :path "fuga" :mode #\w) +(let* ((ret) buf1 buf2) + (dotimes (i 10) + (caffe::db-set-id 0) + (caffe::db-read 1) + (setq buf1 (caffe::db-get-data)) + (caffe::db-set-id 1) + (caffe::db-read 1) + (setq buf2 (aref (caffe::db-get-float-data) 0)) + (push (list buf2 buf1) ret) + ) + (print ret) + (print (mapcar + #'(lambda (val) + (count-if #'(lambda (val2) (eq (car val) (car val2))) ret)) + ret)) + ) +(caffe::db-set-id 0) +(caffe::db-close) +(caffe::db-set-id 1) +(caffe::db-close) + +(caffe::db-set-id 0) +(caffe::db-open :path "hoge" :mode #\w) +(caffe::db-set-id 1) +(caffe::db-open :path "fuga" :mode #\w) +;; (bench (caffe::db-random-swap 10000 :id-list '(0 1))) +(bench (caffe::db-random-swap-fast 10000 :id-list '(0 1) :step 10000)) +(caffe::db-set-id 0) +(caffe::db-close) +(caffe::db-set-id 1) +(caffe::db-close) + +(caffe::db-set-id 0) +(caffe::db-open :path "hoge" :mode #\r) +(caffe::db-set-id 1) +(caffe::db-open :path "fuga" :mode #\r) +(let* ((ret) buf1 buf2) + (dotimes (i 1000) + (caffe::db-set-id 0) + (caffe::db-read 1) + (setq buf1 (caffe::db-get-data)) + (caffe::db-set-id 1) + (caffe::db-read 1) + (setq buf2 (aref (caffe::db-get-float-data) 0)) + (push (list buf2 buf1) ret) + ) + (print ret) + (print (mapcar + #'(lambda (val) + (count-if #'(lambda (val2) (eq (car val) (car val2))) ret)) + ret)) + ) +(caffe::db-set-id 0) +(caffe::db-close) +(caffe::db-set-id 1) +(caffe::db-close) diff --git a/eus_caffe/euslisp/eus-caffe.l b/eus_caffe/euslisp/eus-caffe.l new file mode 100644 index 000000000..98e583b9d --- /dev/null +++ b/eus_caffe/euslisp/eus-caffe.l @@ -0,0 +1,172 @@ +#!/usr/bin/env roseus + +;; (require "eus-log.l") +(require "eus-plugin-util.l") + +(if (not (find-package "CAFFE")) (make-package "CAFFE")) +(In-package "CAFFE") + +(defvar *eus-caffe-plugin* (user::gen-plugin-obj "libeus_caffe.so")) + +(defforeign output-log *eus-caffe-plugin* "eus_caffe_output_log" (:integer) :integer) +(defforeign _get_layer_blob_data *eus-caffe-plugin* "eus_caffe_get_layer_blob_data" (:string :integer :string :integer) :integer) +(defforeign _get_train_net_layer_blob_data *eus-caffe-plugin* "eus_caffe_get_train_net_layer_blob_data" (:string :integer :string :integer) :integer) +(defforeign get-blob-count *eus-caffe-plugin* "eus_caffe_get_blob_count" (:string) :integer) +(defforeign get-train-net-blob-count *eus-caffe-plugin* "eus_caffe_get_train_net_blob_count" (:string) :integer) +(defforeign _get_blob_data *eus-caffe-plugin* "eus_caffe_get_blob_data" (:string :string :integer) :integer) +(defforeign _get_train_net_blob_data *eus-caffe-plugin* "eus_caffe_get_train_net_blob_data" (:string :string :integer) :integer) +(defforeign _get_input_blob_data *eus-caffe-plugin* "eus_caffe_get_input_blob_data" (:integer :string :integer) :integer) +;; +(defforeign _create_solver *eus-caffe-plugin* "eus_caffe_create_solver" (:string :string) :integer) +(defforeign _reset_memory_layer *eus-caffe-plugin* "eus_caffe_reset_memory_layer" (:string :integer :string :string) :integer) +(defforeign _initialize_solver *eus-caffe-plugin* "eus_caffe_initialize_solver" (:integer :integer :string :string :string :string) :integer) +(defforeign _learn *eus-caffe-plugin* "eus_caffe_learn" () :float) +(defforeign _calc_forward *eus-caffe-plugin* "eus_caffe_calc_forward" (:integer :integer :integer :integer :integer :string :integer :string) :integer) +(defforeign _calc_forward_double *eus-caffe-plugin* "eus_caffe_calc_forward_double" (:integer :integer :integer :integer :integer :string :integer :string) :integer) +(defforeign _memory_calc_forward *eus-caffe-plugin* "eus_caffe_memory_calc_forward" (:integer :integer :string :string :string) :integer) +(defforeign _gen_test_net *eus-caffe-plugin* "eus_caffe_gen_test_net" (:string :string) :integer) + +(defun gen-net-image + (&key + (caffe-root + (format nil "~A/3rdparty/caffe" (ros::rospack-find "eus_caffe"))) + (net-path "net2.prototxt") + (out-path "/tmp/net.png") + (eog-open? t) + ) + ;; PYTHONPATH=$PYTHONPATH:`pwd` python draw_net.py train_val.prototxt net.png --rankdir "TB" + (unix:system + (format nil "PYTHONPATH=$PYTHONPATH:~A/python python ~A/python/draw_net.py ~A ~A --rankdir \"TB\"" + caffe-root caffe-root net-path out-path)) + (if eog-open? + (unix:system (format nil "eog ~A &" out-path))) + out-path) + +(defun get-blob-data + (&key + (name "ip") + (ret (instantiate float-vector 32))) + (_get_blob_data name ret (length ret)) + ret) + +(defun get-train-net-blob-data + (&key + (name "ip") + (ret (instantiate float-vector 32))) + (_get_train_net_blob_data name ret (length ret)) + ret) + +(defun get-layer-blob-data + (&key + (name "ip") + (blob_id 0) + (ret (instantiate float-vector 32))) + (_get_layer_blob_data name blob_id ret (length ret)) + ret) + +(defun get-train-net-layer-blob-data + (&key + (name "ip") + (blob_id 0) + (ret (instantiate float-vector 32))) + (_get_train_net_layer_blob_data name blob_id ret (length ret)) + ret) + +(defun get-input-blob-data + (&key + (id 0) + (ret (instantiate float-vector 32))) + (_get_input_blob_data id ret (length ret)) + ret) + +(defun calc-forward + (&key + (isize 2) + (osize 1) + (num 1) + (channels isize) + (width 1) + (height 1) + (input (instantiate string isize)) + (output (instantiate float-vector osize))) + (_calc_forward num channels width height + (length input) input (length output) output) + output) + +(defun calc-forward-double + (&key + (isize 2) + (osize 1) + (num 1) + (channels isize) + (width 1) + (height 1) + (input (instantiate float-vector isize)) + (output (instantiate float-vector osize))) + (_calc_forward_double + num channels width height + (length input) input (length output) output) + output) + +(defun memory-calc-forward + (&key + (isize 32) + (osize 1) + (input (instantiate float-vector isize)) + (output (instantiate float-vector osize)) + (idummy (instantiate float-vector (length input)))) + (_memory_calc_forward isize osize input output idummy) + output) + +(defun create-solver + (&key + (solver "solver.prototxt") + (solverstate "")) + (_create_solver solver solverstate)) + +(defun reset-memory-layer + (&key + (name "input") + (size 3200) + (data (instantiate float-vector (* 1 size))) + (label (instantiate float-vector size))) + (_reset_memory_layer name size data label)) + +(defun initialize-solver + (&key + (solver "solver.prototxt") + (solverstate "") + (size 3200) + (dsize size) + (isize size) + (idata (instantiate float-vector isize)) + (ddata (instantiate float-vector dsize)) + (iclass (instantiate float-vector size)) + (dclass (instantiate float-vector size)) + ) + (create-solver :solver solver :solverstate solverstate) + (_initialize_solver (length iclass) (length dclass) + idata ddata iclass dclass) + ;; (_learn) + ) + +(defun learn + (&rest + args + &key + (initialize? t) + (timer (instance user::mtimer :init)) + (log (format nil "caffe_~A.log" (car (unix::gettimeofday)))) + ret + &allow-other-keys + ) + ;; (if log (cpplog::change-output-stream log)) + (if initialize? (apply 'initialize-solver args)) + (setq ret (_learn)) + (if timer (format t "time: ~A~%" (setq timer (send timer :stop)))) + ;; (if log (cpplog::change-output-stream "")) + ret) + +(defun gen-test-net + (&key (netproto "") (caffemodel "")) + (_gen_test_net netproto caffemodel)) diff --git a/eus_caffe/euslisp/eus-log.l b/eus_caffe/euslisp/eus-log.l new file mode 100644 index 000000000..7072e5aac --- /dev/null +++ b/eus_caffe/euslisp/eus-log.l @@ -0,0 +1,29 @@ +#!/usr/bin/env roseus + +(require "eus-plugin-util.l") + +(if (not (find-package "CPPLOG")) (make-package "CPPLOG")) +(In-package "CPPLOG") + +(defvar *eus-log-plugin* (user::gen-plugin-obj "libeus_log.so")) + +(defforeign _change_output_stream *eus-log-plugin* "log_change_output_stream" (:string :integer) :integer) +(defforeign echo *eus-log-plugin* "log_test_echo" (:string) :integer) +(defforeign size-vector *eus-log-plugin* "size_vector" (:string) :integer) +(defforeign _write-vector *eus-log-plugin* "write_vector" (:string :string :integer) :integer) +(defforeign _read-vector *eus-log-plugin* "read_vector" (:string :string :integer) :integer) + +(defun change-output-stream (str) + (if (null str) (setq str "")) + (format t "cpplog::change-output-stream -> ~A~%" + (if (eq (length str) 0) "std::cout" str)) + (_change_output_stream str (length str))) + +(defun write-vector (path vec) (_write-vector path vec (length vec))) +(defun read-vector + (path + &key + (size (size-vector path)) + (vec (instantiate float-vector size))) + (_read-vector path vec (length vec)) + vec) diff --git a/eus_caffe/euslisp/eus-plugin-util.l b/eus_caffe/euslisp/eus-plugin-util.l new file mode 100644 index 000000000..01a43de52 --- /dev/null +++ b/eus_caffe/euslisp/eus-plugin-util.l @@ -0,0 +1,68 @@ +#!/usr/bin/env roseus + +(defun gen-plugin-obj + (libname) + (labels + ((library_search + (str &key + (depth 0) + colon-pos lib-path) + (format t " [~A] target=" depth) + (cond + ((eq (length str) 0) + (format t "~% ~A not found~%" libname) + (exit -1)) + ((and (setq colon-pos (or (position #\: str) (length str))) + (setq lib-path (subseq str 0 colon-pos)) + (setq lib-path + (if (eq (aref lib-path (- (length lib-path) 1)) #\/) + (subseq lib-path 0 (- (length lib-path) 1)) + lib-path)) + (probe-file (setq lib-path + (print (format nil "~A/~A" lib-path libname))))) + (load-foreign lib-path)) + (t + (library_search (subseq str (min (length str) (+ colon-pos 1))) + :depth (+ depth 1)))))) + (library_search (format nil "~A:~A/lib" + (unix:getenv "LD_LIBRARY_PATH") + (read-line (piped-fork "pwd")))))) + + +(defun random-sample-indices + (size + &key + (min 0) + (max (* size 10)) + (val) + size1 size2 + ) + (cond + ((eq size 0) nil) + ((eq max min) + ;; (format t "impossible bacause size=0 vs ~A~%" + ;; size) + nil) + (t + (setq val (+ min (random (- max min)))) + (setq size1 + (round + (* (- size 1) + (/ (- val min) (- max min 1.0))))) + (append + (random-sample-indices + size1 :min min :max val) + (list val) + (random-sample-indices + (- (- size 1) size1) :min (+ val 1) :max max)) + ))) + +(defun random-vector-swap + (vec &key (cnt 1)) + (dotimes (i cnt) + (let* ((id1 (random (length vec))) + (id2 (random (length vec))) + (buf (aref vec id1))) + (setf (aref vec id1) (aref vec id2)) + (setf (aref vec id2) buf))) + vec) diff --git a/eus_caffe/euslisp/image-util.l b/eus_caffe/euslisp/image-util.l new file mode 100644 index 000000000..3e4f2f8e8 --- /dev/null +++ b/eus_caffe/euslisp/image-util.l @@ -0,0 +1,121 @@ +#!/usr/bin/env roseus + +(defun convert-from-caffe-image + (img + &key + (width (send img :width)) + (height (send img :height)) + ;; (str-buf (instantiate string (length (send img :entity)))) + (ret-img (instance image::color-image24 :init width height)) + (str-buf (send ret-img :entity)) + ) + (dotimes (h height) + (dotimes (w width) + (setf (aref str-buf (+ (* (+ (* h width) w) 3) 0)) + (aref (send img :entity) (+ (* h width) w))) + (setf (aref str-buf (+ (* (+ (* h width) w) 3) 1)) + (aref (send img :entity) (+ (* width height) (* h width) w))) + (setf (aref str-buf (+ (* (+ (* h width) w) 3) 2)) + (aref (send img :entity) (+ (* 2 width height) (* h width) w))) + )) + (or ret-img str-buf) + ) + +(defun convert-to-caffe-image + (img + &key + (width (send img :width)) + (height (send img :height)) + ;; (str-buf (instantiate string (length (send img :entity)))) + (ret-img (instance image::color-image24 :init width height)) + (str-buf (send ret-img :entity)) + ) + (let* ((did -1) (buf (send img :entity))) + (dotimes (c (send img :byte-depth)) + (dotimes (i (* (send img :width) (send img :height))) + (setf (aref str-buf (incf did)) + (aref buf (+ (* i (send img :byte-depth)) c)))))) + (or ret-img str-buf)) + +(defun check-color-image24-size + (img) + (cond + ((eq (length (send img :entity)) + (* (send img :width) (send img :height) + (send img :byte-depth))) + img) + ((eq (length (send img :entity)) + (* (send img :width) (send img :height))) + (format t "[check-color-image24-size] monochronized color image detected~%") + (instance image::color-image24 :init + (send img :width) (send img :height) + (let* ((str-buf (instantiate string + (* 3 (send img :width) + (send img :height))))) + (dotimes (i (* (send img :width) (send img :height))) + (dotimes (j 3) + (setf (aref str-buf (+ j (* 3 i))) + (aref (send img :entity) i)))) + str-buf))) + (t + (format t "[check-color-image24-size] invalid image ~A x ~A x ~A~%" + (send img :byte-depth) (send img :width) (send img :height)) + nil) + )) + +(defun test-caffe-image + nil + (let* ((img0 (check-color-image24-size + (img::read-image-file "test.png"))) + (img-caffe (convert-to-caffe-image img0)) + (img (convert-from-caffe-image img-caffe))) + (img::write-image-file "img_to_caffe.png" img-caffe) + (img::write-image-file "img_from_caffe.png" img) + (list img0 img-caffe img))) + +#| + +(setq img0 (instance image::color-image24 :init 32 32 (caffe::db-get-data))) +(setq str-buf (instantiate string (* 32 32 3))) +(img::write-image-file "test0.png" img0) +(dotimes (h 32) + (dotimes (w 32) + ;; (dotimes (c 3) + (setf (aref str-buf (+ (* (+ (* h 32) w) 3) 0)) + (aref (send img0 :entity) (+ (* h 32) w))) + (setf (aref str-buf (+ (* (+ (* h 32) w) 3) 1)) + (aref (send img0 :entity) (+ (* 32 32) (* h 32) w))) + (setf (aref str-buf (+ (* (+ (* h 32) w) 3) 2)) + (aref (send img0 :entity) (+ (* 2 32 32) (* h 32) w))) + )) +(img::write-image-file "test.png" (setq img (instance image::color-image24 :init 32 32 (Copy-seq str-buf)))) +(img::write-image-file "test?.png" (setq img? (instance image::color-image24 :init 32 32 (concatenate string (send (send img :blue) :entity) (send (send img :green) :entity) (send (send img :red) :entity))))) +;; +;; (let* ((r (send img :red)) (g (send img :green)) (b (send img :blue)) +;; (id 0)) +;; (dotimes (i (length (send r :entity))) +;; (setf (aref str-buf id) (aref (send r :entity) i)) +;; (incf id)) +;; (dotimes (i (length (send g :entity))) +;; (setf (aref str-buf id) (aref (send g :entity) i)) +;; (incf id)) +;; (dotimes (i (length (send b :entity))) +;; (setf (aref str-buf id) (aref (send b :entity) i)) +;; (incf id)) +;; ) +(let* ((did -1) (buf (send img :entity))) + (dotimes (c (send img :byte-depth)) + (dotimes (i (* (send img :width) (send img :height))) + (setf (aref str-buf (incf did)) + (aref buf (+ (* i (send img :byte-depth)) c)))))) +;; (dotimes (h (send img :height)) +;; (dotimes (w (send img :width)) +;; (dotimes (c (send img :byte-depth)) +;; (setf (aref str-buf +;; (+ (* c (send img :width) (send img :height)) +;; (* h (send img :width)) w)) +;; (aref (send img :entity) +;; (+ (* (+ (* h (send img :width)) w) +;; (send img :byte-depth)) c)))))) +(img::write-image-file "test2.png" (setq img2 (instance image::color-image24 :init 32 32 (copy-seq str-buf)))) +;; diff --git a/eus_caffe/euslisp/net.prototxt b/eus_caffe/euslisp/net.prototxt new file mode 100644 index 000000000..601eff6e2 --- /dev/null +++ b/eus_caffe/euslisp/net.prototxt @@ -0,0 +1,122 @@ +name: "sample_net" +layer { + name: "input" + type: "MemoryData" + top: "input" + top: "dummy_label1" + memory_data_param { + batch_size: 32 + channels: 2 + height: 1 + width: 1 + } +} +layer { + name: "ip" + type: "InnerProduct" + bottom: "input" + top: "ip" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 50 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode1neuron" + type: "Sigmoid" + bottom: "ip" + top: "encode1neuron" +} +layer { + name: "middle1" + type: "InnerProduct" + bottom: "encode1neuron" + top: "middle1" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 10 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode2neuron" + type: "Sigmoid" + bottom: "middle1" + top: "encode2neuron" +} +layer { + name: "output" + type: "InnerProduct" + bottom: "encode2neuron" + top: "output" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 1 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "target" + type: "MemoryData" + top: "target" + top: "dummy_label2" + memory_data_param { + batch_size: 32 + channels: 1 + height: 1 + width: 1 + } +} +layer { + name: "loss" + type: "EuclideanLoss" + bottom: "output" + bottom: "target" + top: "loss" +} diff --git a/eus_caffe/euslisp/solver.prototxt b/eus_caffe/euslisp/solver.prototxt new file mode 100644 index 000000000..b0ecc86bc --- /dev/null +++ b/eus_caffe/euslisp/solver.prototxt @@ -0,0 +1,10 @@ +net: "net.prototxt" +solver_type: SGD +base_lr: 0.01 +lr_policy: "step" +gamma: 0.9 +stepsize: 10000 ## learning rate update: base_lr *= gamma, in every stepsize calcuration +max_iter: 100000 +momentum: 0.9 +display: 10000 +snapshot_prefix: "sample" diff --git a/eus_caffe/make.sh b/eus_caffe/make.sh new file mode 100755 index 000000000..65d804c38 --- /dev/null +++ b/eus_caffe/make.sh @@ -0,0 +1,119 @@ +#!/usr/bin/env bash + +DIR_3rdparty=""; +## DIR_ROOT=""; +DIR_CAFFE=""; +LOG_HEAD="_/_/_/_/_/_/_/_/_/"; + +function _mlog () { + echo $LOG_HEAD; + echo $1; + echo $LOG_HEAD; +} + +if [ ! -e "3rdparty" ]; +then + _mlog "gen 3rdparty dir"; + mkdir 3rdparty; +fi +cd 3rdparty; +DIR_3rdparty=`pwd`; + +if [ ! -e "caffe" ]; +then + ## + ## + cd $DIR_3rdparty; + _mlog "download caffe"; + wget https://github.com/BVLC/caffe/archive/d362894887af9dca8581906b2284f5be81dbd403.zip + unzip d362894887af9dca8581906b2284f5be81dbd403.zip; + mv caffe-d362894887af9dca8581906b2284f5be81dbd403 caffe; + ## mv caffe-master caffe; + ## git clone https://github.com/BVLC/caffe.git; + cd caffe; + DIR_CAFFE=`pwd`; + ## + ## sudo apt-get install libprotobuf-dev libleveldb-dev libsnappy-dev libopencv-dev libboost-all-dev libhdf5-serial-dev libatlas-base-dev; ## move to rosdep + ## + ## mkdir 3rdparty; + ## cd 3rdparty; + ## DIR_3rdparty=`pwd`; + ## + ## gflags + cd $DIR_3rdparty; + _mlog "download gflag"; + wget https://github.com/gflags/gflags/archive/d4e971c10b1557292b5371807a23921d15e7fece.zip; + unzip d4e971c10b1557292b5371807a23921d15e7fece.zip; + mv gflags-d4e971c10b1557292b5371807a23921d15e7fece gflags; + cd gflags; + _mlog "build gflag"; + mkdir build && cd build + export CXXFLAGS="-fPIC" && cmake .. && make VERBOSE=1 + ## make && make install + make; + _mlog "done gflag"; + ## + ## glog + cd $DIR_3rdparty; + _mlog "download glog"; + ## wget https://google-glog.googlecode.com/files/glog-0.3.3.tar.gz + wget https://github.com/google/glog/archive/0b0b022be1c9c9139955af578fe477529d4b7b3c.zip; + mv 0b0b022be1c9c9139955af578fe477529d4b7b3c.zip glog-0.3.3.zip; + unzip glog-0.3.3.zip; + mv glog-0b0b022be1c9c9139955af578fe477529d4b7b3c glog-0.3.3; + cd glog-0.3.3; + _mlog "build glog"; + ./configure --with-gflags=${DIR_3rdparty}/gflags/build; + make; + ## make && make install; + _mlog "done glog"; + ## + ## lmdb + cd $DIR_3rdparty; + _mlog "download lmdb"; + wget https://github.com/LMDB/lmdb/archive/7e476e4983cfba45cefe793b8bd6e13c486b3989.zip; + unzip 7e476e4983cfba45cefe793b8bd6e13c486b3989.zip; + mv lmdb-7e476e4983cfba45cefe793b8bd6e13c486b3989 mdb; + cd mdb/libraries/liblmdb; + _mlog "build lmdb"; + make; + ## make && make install + _mlog "done lmdb"; + ## + cd $DIR_3rdparty; + _mlog "gen include/lib dir"; + mkdir lib; + for d in "${DIR_3rdparty}/gflags/build/lib" "${DIR_3rdparty}/mdb/libraries/liblmdb" "${DIR_3rdparty}/glog-0.3.3/.libs"; + do + ln -s $d/* lib; + done + ## + mkdir include; + for d in "${DIR_3rdparty}/gflags/build/include" "${DIR_3rdparty}/mdb/libraries/liblmdb" "${DIR_3rdparty}/glog-0.3.3/src"; + do + ln -s $d/* include; + done + ## + cd $DIR_CAFFE; + if [ ! -e "Makefile.config" ]; + then + _mlog "gen caffe build config"; + cat Makefile.config.example | sed -e "s#/usr/local/lib#/opt/ros/${ROS_DISTRO}/lib /usr/local/lib ${DIR_3rdparty}/lib#g" | sed -e "s#/usr/local/include#/opt/ros/${ROS_DISTRO}/include /usr/local/include ${DIR_3rdparty}/include#g" | sed -e "s/# CUSTOM_CXX := g++/CUSTOM_CXX := g++/g" > Makefile.config; + ## cat Makefile.config.example | sed -e "s#/usr/local/lib#/usr/local/lib ${DIR_ROOT}/3rdparty/gflags/build/lib ${DIR_ROOT}/3rdparty/mdb/libraries/liblmdb ${DIR_ROOT}/3rdparty/glog-0\.3\.3/\.libs#g" | sed -e "s#/usr/local/include#/usr/local/include ${DIR_ROOT}/3rdparty/gflags/build/include ${DIR_ROOT}/3rdparty/mdb/libraries/liblmdb ${DIR_ROOT}/3rdparty/glog-0\.3\.3/src#g" | sed -e "s/# CUSTOM_CXX := g++/CUSTOM_CXX := g++/g" > Makefile.config; + cat Makefile.config; + fi + _mlog "build caffe"; + CPU_ONLY=1 make; + # ## python + if [ "$PYCAFFE_INSTALL" ]; + then + # wget -O- http://neuro.debian.net/lists/precise.jp.libre | sudo tee /etc/apt/sources.list.d/neurodebian.sources.list; + # sudo apt-key adv --recv-keys --keyserver hkp://pgp.mit.edu:80 0xA5D32F012649A5A9; + # sudo aptitude install python-skimage; + sudo apt-get install python-pip + for req in $(cat python/requirements.txt); do sudo pip install $req; done + CPU_ONLY=1 make pycaffe; + fi + ## + _mlog "done caffe"; +fi diff --git a/eus_caffe/package.xml b/eus_caffe/package.xml new file mode 100644 index 000000000..210de8695 --- /dev/null +++ b/eus_caffe/package.xml @@ -0,0 +1,28 @@ + + + eus_caffe + + eus_caffe package + + 0.0.1 + Noda Shintaro + BSD + + catkin + euslisp + cmake_modules + protobuf-dev + snappy + boost + hdf5 + atlas + leveldb + cv_bridge + + + euslisp + diff --git a/eus_caffe/sample/db_sample/learn.l b/eus_caffe/sample/db_sample/learn.l new file mode 100644 index 000000000..7361bcf90 --- /dev/null +++ b/eus_caffe/sample/db_sample/learn.l @@ -0,0 +1,61 @@ + +(require "package://eus_caffe/euslisp/eus-caffe.l") +(require "package://eus_caffe/euslisp/eus-caffe-db.l") + +(defun gen-linear-equation-db + (&key + (target-path "target_lmdb_linear_equation") + (input-path "input_lmdb_linear_equation") + (size 3200) + (dscale 1) + (iscale 2) + (dsize (* dscale size)) + (isize (* iscale size)) + ) + (caffe::db-set-id 0) + (if (not (zerop (caffe::db-open :dtype "lmdb" :path target-path :mode #\n))) + (return-from gen-linear-equation-db (print 'db-open-failed))) + (caffe::db-set-id 1) + (if (not (zerop (caffe::db-open :dtype "lmdb" :path input-path :mode #\n))) + (return-from gen-linear-equation-db (print 'db-open-failed))) + ;; + (let* ((dbuf (instantiate float-vector dscale)) + (ibuf (instantiate float-vector iscale))) + (dotimes (i size) + (let* ((x (* 10 (- (random 2.0) 1.0))) + (y (* 10 (- (random 2.0) 1.0)))) + (setf (aref ibuf 0) x) + (setf (aref ibuf 1) y) + (setf (aref dbuf 0) (+ (* 3 x) (* -2 y) 4)) + ;; + (caffe::db-set-id 0) + (caffe::db-put-double + :channels dscale :width 1 :height 1 :label 0 + :id_str (caffe::zero-string i) :data dbuf) + ;; + (caffe::db-set-id 1) + (caffe::db-put-double + :channels iscale :width 1 :height 1 :label 0 + :id_str (caffe::zero-string i) :data ibuf) + ))) + (caffe::db-set-id 0) (caffe::db-close) + (caffe::db-set-id 1) (caffe::db-close) + ) + +(defun db-learn + nil + ;; (caffe::_create_solver "linear_equation_db.prototxt" "") + ;; (caffe::_learn) + (caffe::learn :solver "linear_equation_db.prototxt" :size 0) + ;; test + (caffe::gen-test-net :netproto "linear_equation_db_net_predict.prototxt" + ;; :caffemodel "sample_iter_100000.caffemodel" + ) + (format t " -- check net state~% ~A->~A~% ~A->~A~% ~A->~A~%" + (float-vector 0 0) + (caffe::calc-forward-double :input (float-vector 0 0) :isize 2 :osize 1) + (float-vector 0 2) + (caffe::calc-forward-double :input (float-vector 0 2) :isize 2 :osize 1) + (float-vector 2 5) + (caffe::calc-forward-double :input (float-vector 2 5) :isize 2 :osize 1)) + ) diff --git a/eus_caffe/sample/db_sample/linear_equation_db.prototxt b/eus_caffe/sample/db_sample/linear_equation_db.prototxt new file mode 100644 index 000000000..2de9ff041 --- /dev/null +++ b/eus_caffe/sample/db_sample/linear_equation_db.prototxt @@ -0,0 +1,11 @@ +net: "linear_equation_db_net.prototxt" +solver_type: SGD +base_lr: 0.01 +lr_policy: "step" +gamma: 0.9 +stepsize: 10000 ## learning rate update: base_lr *= gamma, in every stepsize calcuration +max_iter: 30000 +momentum: 0.9 +display: 10000 +snapshot_prefix: "linear_equation_db" +solver_mode: CPU diff --git a/eus_caffe/sample/db_sample/linear_equation_db_net.prototxt b/eus_caffe/sample/db_sample/linear_equation_db_net.prototxt new file mode 100644 index 000000000..ab7a78554 --- /dev/null +++ b/eus_caffe/sample/db_sample/linear_equation_db_net.prototxt @@ -0,0 +1,130 @@ +name: "linear_equation_net" +layer { + name: "input" + type: "Data" + top: "input" + transform_param { + scale: 1.0 + } + include { + phase: TRAIN + } + data_param { + source: "input_lmdb_linear_equation" + batch_size: 32 + backend: LMDB + } +} +layer { + name: "ip" + type: "InnerProduct" + bottom: "input" + top: "ip" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 50 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode1neuron" + type: "Sigmoid" + bottom: "ip" + top: "encode1neuron" +} +layer { + name: "middle1" + type: "InnerProduct" + bottom: "encode1neuron" + top: "middle1" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 10 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode2neuron" + type: "Sigmoid" + bottom: "middle1" + top: "encode2neuron" +} +layer { + name: "output" + type: "InnerProduct" + bottom: "encode2neuron" + top: "output" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 1 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "target" + type: "Data" + top: "target" + transform_param { + scale: 1.0 + } + include { + phase: TRAIN + } + data_param { + source: "target_lmdb_linear_equation" + batch_size: 32 + backend: LMDB + } +} +layer { + name: "loss" + type: "EuclideanLoss" + bottom: "output" + bottom: "target" + top: "loss" +} diff --git a/eus_caffe/sample/db_sample/linear_equation_db_net_predict.prototxt b/eus_caffe/sample/db_sample/linear_equation_db_net_predict.prototxt new file mode 100644 index 000000000..3ebe49344 --- /dev/null +++ b/eus_caffe/sample/db_sample/linear_equation_db_net_predict.prototxt @@ -0,0 +1,96 @@ +name: "linear_equation_net" +input: "input" +input_dim: 1 ## num +input_dim: 2 ## channel +input_dim: 1 ## w +input_dim: 1 ## h +layer { + name: "ip" + type: "InnerProduct" + bottom: "input" + top: "ip" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 50 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode1neuron" + type: "Sigmoid" + bottom: "ip" + top: "encode1neuron" +} +layer { + name: "middle1" + type: "InnerProduct" + bottom: "encode1neuron" + top: "middle1" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 10 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode2neuron" + type: "Sigmoid" + bottom: "middle1" + top: "encode2neuron" +} +layer { + name: "output" + type: "InnerProduct" + bottom: "encode2neuron" + top: "output" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 1 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} diff --git a/eus_caffe/sample/image_ik/image_potentio_map.prototxt b/eus_caffe/sample/image_ik/image_potentio_map.prototxt new file mode 100644 index 000000000..d4c358437 --- /dev/null +++ b/eus_caffe/sample/image_ik/image_potentio_map.prototxt @@ -0,0 +1,173 @@ +name: "image_potentio_map" +layer { + name: "input" + type: "Data" + top: "input" + top: "label" + include { + phase: TRAIN + } + transform_param { + scale: 1.0 ##0.003922 + } + data_param { + source: "input_lmdb_robot_image" + batch_size: 10 ## must be same as target one + backend: LMDB + } +} +layer { + name: "conv1" + type: "Convolution" + bottom: "input" + top: "conv1" + param { + lr_mult: 1 + } + param { + lr_mult: 2 + } + convolution_param { + num_output: 64 + pad: 4 + kernel_size: 5 + stride: 1 + weight_filler { + type: "gaussian" + std: 0.0001 + } + bias_filler { + type: "constant" + } + } +} +layer { + name: "relu1" + type: "ReLU" + bottom: "conv1" + top: "relu1" +} +layer { + name: "pool1" + type: "Pooling" + bottom: "relu1" + top: "pool1" + pooling_param { + pool: MAX + kernel_size: 3 + stride: 2 + } +} +layer { + name: "norm1" + type: "LRN" + bottom: "pool1" + top: "norm1" + lrn_param { + local_size: 3 + alpha: 5e-05 + beta: 0.75 + norm_region: WITHIN_CHANNEL + } +} +layer { + name: "conv2" + type: "Convolution" + bottom: "norm1" + top: "conv2" + param { + lr_mult: 1 + } + param { + lr_mult: 2 + } + convolution_param { + num_output: 128 + pad: 2 + kernel_size: 3 + stride: 1 + weight_filler { + type: "gaussian" + std: 0.0001 + } + bias_filler { + type: "constant" + } + } +} +layer { + name: "relu2" + type: "ReLU" + bottom: "conv2" + top: "relu2" +} +layer { + name: "pool2" + type: "Pooling" + bottom: "relu2" + top: "pool2" + pooling_param { + pool: MAX + kernel_size: 3 + stride: 2 + } +} +layer { + name: "norm2" + type: "LRN" + bottom: "pool2" + top: "norm2" + lrn_param { + local_size: 3 + alpha: 5e-05 + beta: 0.75 + norm_region: WITHIN_CHANNEL + } +} +layer { + name: "ip1" + type: "InnerProduct" + bottom: "norm2" + top: "output" + param { + lr_mult: 1 + decay_mult: 250 + } + param { + lr_mult: 2 + decay_mult: 0 + } + inner_product_param { + num_output: 15 + weight_filler { + type: "gaussian" + std: 0.01 + } + bias_filler { + type: "constant" + } + } +} +layer { + name: "target" + type: "Data" + top: "target" + transform_param { + scale: 0.017453 + } + include { + phase: TRAIN + } + data_param { + source: "target_lmdb_joint_angle" + batch_size: 10 + backend: LMDB + } +} +layer { + name: "loss" + type: "EuclideanLoss" + bottom: "output" + bottom: "target" + top: "loss" +} diff --git a/eus_caffe/sample/image_ik/image_potentio_map_predict.prototxt b/eus_caffe/sample/image_ik/image_potentio_map_predict.prototxt new file mode 100644 index 000000000..7f5639dfd --- /dev/null +++ b/eus_caffe/sample/image_ik/image_potentio_map_predict.prototxt @@ -0,0 +1,138 @@ +name: "image_potentio_map_predict" +input: "input" +input_dim: 1 ## num +input_dim: 1 ## channel +input_dim: 32 ## w +input_dim: 32 ## h +layer { + name: "conv1" + type: "Convolution" + bottom: "input" + top: "conv1" + param { + lr_mult: 1 + } + param { + lr_mult: 2 + } + convolution_param { + num_output: 64 + pad: 4 + kernel_size: 5 + stride: 1 + weight_filler { + type: "gaussian" + std: 0.0001 + } + bias_filler { + type: "constant" + } + } +} +layer { + name: "relu1" + type: "ReLU" + bottom: "conv1" + top: "relu1" +} +layer { + name: "pool1" + type: "Pooling" + bottom: "relu1" + top: "pool1" + pooling_param { + pool: MAX + kernel_size: 3 + stride: 2 + } +} +layer { + name: "norm1" + type: "LRN" + bottom: "pool1" + top: "norm1" + lrn_param { + local_size: 3 + alpha: 5e-05 + beta: 0.75 + norm_region: WITHIN_CHANNEL + } +} +layer { + name: "conv2" + type: "Convolution" + bottom: "norm1" + top: "conv2" + param { + lr_mult: 1 + } + param { + lr_mult: 2 + } + convolution_param { + num_output: 128 + pad: 2 + kernel_size: 3 + stride: 1 + weight_filler { + type: "gaussian" + std: 0.0001 + } + bias_filler { + type: "constant" + } + } +} +layer { + name: "relu2" + type: "ReLU" + bottom: "conv2" + top: "relu2" +} +layer { + name: "pool2" + type: "Pooling" + bottom: "relu2" + top: "pool2" + pooling_param { + pool: MAX + kernel_size: 3 + stride: 2 + } +} +layer { + name: "norm2" + type: "LRN" + bottom: "pool2" + top: "norm2" + lrn_param { + local_size: 3 + alpha: 5e-05 + beta: 0.75 + norm_region: WITHIN_CHANNEL + } +} +layer { + name: "ip1" + type: "InnerProduct" + bottom: "norm2" + top: "output" + param { + lr_mult: 1 + decay_mult: 250 + } + param { + lr_mult: 2 + decay_mult: 0 + } + inner_product_param { + num_output: 15 + weight_filler { + type: "gaussian" + std: 0.01 + } + bias_filler { + type: "constant" + } + } +} diff --git a/eus_caffe/sample/image_ik/image_potentio_map_solver.prototxt b/eus_caffe/sample/image_ik/image_potentio_map_solver.prototxt new file mode 100644 index 000000000..26ea1c8bb --- /dev/null +++ b/eus_caffe/sample/image_ik/image_potentio_map_solver.prototxt @@ -0,0 +1,18 @@ +net: "image_potentio_map.prototxt" +solver_type: SGD +base_lr: 0.001 +lr_policy: "step" +gamma: 0.9 +stepsize: 1000 ## learning rate update: base_lr *= gamma, in every stepsize calcuration +max_iter: 5000 +momentum: 0.9 +display: 10 +snapshot_prefix: "cnn" +## base_lr: 0.001 +## momentum: 0.9 +## lr_policy: "fixed" +## display: 5 +## max_iter: 4000 +## snapshot: 4000 +## snapshot_prefix: "cnn" +solver_mode: CPU diff --git a/eus_caffe/sample/image_ik/learn.l b/eus_caffe/sample/image_ik/learn.l new file mode 100644 index 000000000..5348229dd --- /dev/null +++ b/eus_caffe/sample/image_ik/learn.l @@ -0,0 +1,224 @@ +(require "package://eus_caffe/euslisp/eus-caffe.l") +(require "package://eus_caffe/euslisp/eus-caffe-db.l") + +(defvar *robot* + (cond + ((probe-file (ros::resolve-ros-path "package://peppereus/pepper.l")) + (require :hrp2jsk-utils "package://peppereus/pepper.l") + (pepper)) + ((probe-file (ros::resolve-ros-path "package://euslisp/jskeus/irteus/demo/sample-robot-model.l")) + (require "package://euslisp/jskeus/irteus/demo/sample-robot-model.l") + (instance sample-robot :init)) + (t (throw :robot-not-found nil)))) + +(objects (list *robot*)) +(send *robot* :transform (send (send *robot* :link "Tibia") :transformation (make-coords)) :local) +(send *irtviewer* :change-background (float-vector 0 0 0)) +(send *irtviewer* :viewer :viewing :look #f(4000 -10 -80) #F(0 0 300)) +(send *viewer* :draw-objects) + +(send-all (send *robot* :torso :joint-list) :min-angle -10) +(send-all (send *robot* :torso :joint-list) :max-angle +10) + +(defun read-mono-image + (path) + (let* ((img (img::read-image-file path)) + (buf (instantiate string (* (send img :width) + (send img :height))))) + (dotimes (x (send img :width)) + (dotimes (y (send img :height)) + (setf (elt buf (+ x (* y (send img :width)))) + (/ + (+ + (elt (send img :entity) + (+ 0 (* 3 (+ x (* y (send img :width)))))) + (elt (send img :entity) + (+ 1 (* 3 (+ x (* y (send img :width)))))) + (elt (send img :entity) + (+ 2 (* 3 (+ x (* y (send img :width))))))) + 3) + ))) + (instance image::grayscale-image :init + (send img :width) (send img :height) buf))) + +(defun get-gl-mono-image + (&key (x 0) (y 0) z + (view (send *viewer* :viewsurface)) + (width (send view :get-val 'x::width)) + (height (send view :get-val 'x::height)) + (worg (send view :get-val 'x::width)) + (horg (send view :get-val 'x::height)) + (wscale (/ (* 1.0 worg) width)) + (hscale (/ (* 1.0 horg) height)) + ((:imagebuf imgbuf) (make-string (* worg horg 3)))) + (let () + (send view :makecurrent) + (gl::glReadBuffer gl::GL_BACK) + (gl::glPixelStorei gl::GL_PACK_ALIGNMENT 1) + (gl::glReadPixels x y worg horg gl::GL_RGB gl::GL_UNSIGNED_BYTE imgbuf) + ;; transpose + (let ((b (make-string (* width height))) zv) + (dotimes (_x width) + (dotimes (_y height) + (setq zv 0) + (setq x (floor (* wscale _x))) + (setq y (floor (* hscale _y))) + (dotimes (_z 3) + (setq zv (+ zv (elt imgbuf (+ (* y worg 3) (* x 3) _z))))) + (setf (elt b (+ (* (- height _y 1) width) _x)) + (round (/ zv 3))) + )) + (instance image::grayscale-image :init width height b)) + )) +;; (img::write-image-file "test.jpg" (get-gl-mono-image :width 320 :height 320)) + +(defvar *mean-mono-image* + (if (probe-file "image/mean.jpg") (read-mono-image "image/mean.jpg") + (progn + (unix:system "mkdir image") + (img::write-image-file + "image/mean.jpg" (get-gl-mono-image :width 32 :height 32)) + (read-mono-image "image/mean.jpg")))) + +(defun image-minus + (&optional + (img1 (get-gl-mono-image :width 32 :height 32)) + (img2 *mean-mono-image*)) + (scale 1 ;;(/ 1.0 255) + (map float-vector '- (send img1 :entity) (send img2 :entity)))) + +(defun float-vector2image-string + (data) + (let* ((min *inf*) (max *-inf*)) + (dotimes (i (length data)) + (if (< (aref data i) min) (setq min (aref data i))) + (if (> (aref data i) max) (setq max (aref data i)))) + (map string + #'(lambda (d) (round (/ (* 255.0 (- d min)) (- max min)))) + data))) + +(defun gen-random-ik-learning-data + (&key + (sample-points 100) + (joint-list (send *robot* :joint-list)) + ;; + (target-path "target_lmdb_joint_angle") + (input-path "input_lmdb_robot_image") + (image-path "image") + (width 32) (height 32) + img + ) + (caffe::db-set-id 0) + (if (not (zerop (caffe::db-open :dtype "lmdb" :path target-path :mode #\n))) + (return-from gen-linear-equation-db (print 'db-open-failed))) + (caffe::db-set-id 1) + (if (not (zerop (caffe::db-open :dtype "lmdb" :path input-path :mode #\n))) + (return-from gen-linear-equation-db (print 'db-open-failed))) + (if (not (probe-file image-path)) + (unix::system (format nil "mkdir ~A" image-path))) + ;; + (dotimes (i sample-points) + (dolist (j joint-list) + (send j :joint-angle + (+ (send j :min-angle) + (* (random 1.0) + (- (send j :max-angle) (send j :min-angle)))))) + (send-all (send *robot* :links) :worldcoords) + (send *robot* :newcoords (make-coords)) + (send *robot* :transform (send (send (send *robot* :link "Tibia") :worldcoords) :transformation (make-coords)) :local) + (send *viewer* :draw-objects) + (setq img (get-gl-mono-image :width width :height height)) + (img::write-image-file (format nil "~A/~A.jpg" image-path i) img) + ;; + (caffe::db-set-id 0) + (caffe::db-put-double + :channels (length joint-list) :width 1 :height 1 :label 0 + :id_str (caffe::zero-string i) + :data (coerce (send-all joint-list :joint-angle) float-vector)) + ;; + (caffe::db-set-id 1) + (caffe::db-put-double + :channels 1 :width width :height height :label 0 + :id_str (caffe::zero-string i) :data (image-minus img *mean-mono-image*)) ;;(send img :entity)) + ) + ;; + (caffe::db-set-id 0) (caffe::db-close) + (caffe::db-set-id 1) (caffe::db-close) + ) + +(defun db-image-ik-learn + nil + ;; (caffe::_create_solver "linear_equation_db.prototxt" "") + ;; (caffe::_learn) + (caffe::learn :solver "image_potentio_map_solver.prototxt" :size 0) + ;; test + ;; (caffe::gen-test-net :netproto "cnn_predict.prototxt" + ;; ;; :caffemodel "sample_iter_100000.caffemodel" + ;; ) + ;; (format t " -- check net state~% ~A->~A~% ~A->~A~% ~A->~A~%" + ;; (float-vector 0 0) + ;; (caffe::calc-forward :input (float-vector 0 0) :isize 2 :osize 1) + ;; (float-vector 0 2) + ;; (caffe::calc-forward :input (float-vector 0 2) :isize 2 :osize 1) + ;; (float-vector 2 5) + ;; (caffe::calc-forward :input (float-vector 2 5) :isize 2 :osize 1)) + ) + +#| + +(caffe::gen-test-net :netproto "cnn_predict.prototxt" :caffemodel "cnn_iter_5000.caffemodel") + +(caffe::db-open :path "target_lmdb_joint_angle") +(setq a (list (caffe::db-get-float-data) + (progn (caffe::db-read 1) (caffe::db-get-float-data)) + (progn (caffe::db-read 1) (caffe::db-get-float-data)))) +(caffe::db-close) + +(caffe::db-open :path "input_lmdb_robot_image") +(setq b_ (list (caffe::db-get-data) + (progn (caffe::db-read 1) (caffe::db-get-data)) + (progn (caffe::db-read 1) (caffe::db-get-data)))) +(caffe::db-close) + +(setq b + (mapcar + #'(lambda (av) + (send *robot* :angle-vector (copy-seq av)) + (send *robot* :newcoords (make-coords)) + (send *robot* :transform (send (send (send *robot* :link "Tibia") :worldcoords) :transformation (make-coords)) :local) + (send *viewer* :draw-objects) + (let* ((img (get-gl-mono-image :width 32 :height 32)) + (ret + (caffe::calc-forward-double + :isize (* 32 32) :osize 15 + :num 1 :channels 1 :width 32 :height 32 + :input ;; (map float-vector 'identity (send img :entity)) + (image-minus) + ))) + (setq ret (map float-vector 'rad2deg ret)) + (format t "vs ---------~%~A~%~A~%" av ret) + (read-line) + ret)) + a)) + +(caffe::get-blob-data :name "conv1" :ret (instantiate float-vector (* 32 32))) + +(defun gen-blob-image + (&key + (name "conv1") + (width 32) + (height 32) + (count 64) + (data (caffe::get-blob-data :name name + :ret (instantiate float-vector (* width height count)))) + (sdata ;;(map string '(lambda (v) (round (* v 255))) data))) + (float-vector2image-string data))) + (unix:system "mkdir /tmp/caffe") + (dotimes (i count) + (setq img (instance image::grayscale-image :init width height + (subseq sdata (* i width height) (* (+ 1 i) width height)))) + (img::write-image-file (format nil "/tmp/caffe/~A~A.jpg" name (caffe::zero-string i)) img) + )) + +(caffe::get-blob-data :name "pool3" :ret (instantiate float-vector 32)) +(caffe::gen-net-image :net-path "cnn.prototxt") diff --git a/eus_caffe/sample/image_ik/mimic-pepper.l b/eus_caffe/sample/image_ik/mimic-pepper.l new file mode 100755 index 000000000..15c2890d8 --- /dev/null +++ b/eus_caffe/sample/image_ik/mimic-pepper.l @@ -0,0 +1,96 @@ +#!/usr/bin/env roseus + +(require "db-ik-learn.l") + +(defun gen-small-mono-image + (img + &key (x 0) (y 0) z + (width 32) + (height 32) + (worg (send img :width)) + (horg (send img :height)) + (wscale (/ (* 1.0 worg) width)) + (hscale (/ (* 1.0 horg) height)) + ((:imagebuf imgbuf) (send img :entity))) + (let ((b (make-string (* width height))) zv) + (dotimes (_x width) + (dotimes (_y height) + (setq zv 0) + (setq x (floor (* wscale _x))) + (setq y (floor (* hscale _y))) + (dotimes (_z 3) + (setq zv (+ zv (elt imgbuf (+ (* y worg 3) (* x 3) _z))))) + (setf (elt b (+ (* (- height _y 1) width) _x)) + (round (/ zv 3))) + )) + (instance image::grayscale-image :init width height b)) + ) + + +(defun image-callback + (msg) + (setq a msg) + (let* ((img (instance image::color-image24 :init + (send msg :width) + (send msg :height) + (send msg :data))) + (mimg (gen-small-mono-image img)) + (ret + (caffe::calc-forward-double + :isize (* 32 32) :osize 15 + :num 1 :channels 1 :width 32 :height 32 + :input ;;(image-minus mimg) + (map float-vector 'identity (send mimg :entity)) + ))) + (ros::publish "/mimic_pepper/input_image" + (instance sensor_msgs::image :init :width 32 :height 32 + :step 32 :encoding "mono8" :data (send mimg :entity))) + (setq ret (map float-vector 'rad2deg ret)) + (send *robot* :angle-vector ret) + (send-all (send *robot* :links) :worldcoords) + (send *robot* :newcoords (make-coords)) + (send *robot* :transform (send (send (send *robot* :link "Tibia") :worldcoords) :transformation (make-coords)) :local) + (send *viewer* :draw-objects) + (x::window-main-one) + )) + +(ros::roseus "mimic_pepper") +(ros::subscribe "/usb_cam/image_raw" ;;"mimic_pepper/camera_image" + sensor_msgs::Image + #'image-callback) +(ros::advertise "/mimic_pepper/input_image" ;;"mimic_pepper/camera_image" + sensor_msgs::Image) + +(caffe::gen-test-net + :netproto "cnn_predict.prototxt" + :caffemodel "cnn_iter_5000.caffemodel") + +(ros::rate 3) +(do-until-key + (if (not (ros::ok)) (return-from nil)) + (ros::spin-once) + (ros::sleep)) + +#| + +rosrun usb_cam usb_cam_node +rosrun image_view image_viewimage:=/mimic_pepper/input_image + +(send *robot* :reset-pose) +(send *robot* :newcoords (make-coords)) +(send *robot* :transform (send (send (send *robot* :link "Tibia") :worldcoords) :transformation (make-coords)) :local) + +(send *viewer* :draw-objects) +(let* ((img (get-gl-mono-image :width 32 :height 32)) + (ret + (caffe::calc-forward-double + :isize (* 32 32) :osize 15 + :num 1 :channels 1 :width 32 :height 32 + :input ;; (map float-vector 'identity (send img :entity)) + (image-minus) + ))) + (send *robot* :angle-vector (setq ret (map float-vector 'rad2deg ret))) + (send *robot* :newcoords (make-coords)) + (send *robot* :transform (send (send (send *robot* :link "Tibia") :worldcoords) :transformation (make-coords)) :local) + (send *viewer* :draw-objects) + ret) diff --git a/eus_caffe/sample/linear_equation/learn.l b/eus_caffe/sample/linear_equation/learn.l new file mode 100644 index 000000000..d481220dd --- /dev/null +++ b/eus_caffe/sample/linear_equation/learn.l @@ -0,0 +1,65 @@ +#!/usr/bin/env roseus + +(require "package://eus_caffe/euslisp/eus-caffe.l") + +(defun gen+3x-2y+4-data + (&key (size 3200) (isize (* size 2)) (dsize size)) + (let* ((idata (instantiate float-vector isize)) + (ddata (instantiate float-vector dsize))) + (dotimes (i size) + (let* ((x (* 10 (- (random 2.0) 1.0))) + (y (* 10 (- (random 2.0) 1.0)))) + (setf (aref idata (* i 2)) x) + (setf (aref idata (+ 1 (* i 2))) y) + (setf (aref ddata i) (+ (* 3 x) (* -2 y) 4)) + )) + (list idata ddata))) + +(defun linear-equation-test + (&key + (solver "linear_equation.prototxt") + (size 3200) + (dsize size) + (isize (* 2 size)) + (idata) + (ddata) + (iclass (instantiate float-vector size)) ;; dummy + (dclass iclass) + ) + (cond + ((or (not idata) (not ddata)) + (setq idata (gen+3x-2y+4-data)) + (setq ddata (nth 1 idata)) + (setq idata (nth 0 idata)))) + ;; + (caffe::learn :solver solver + :isize size + :dsize size + :idata idata + :ddata ddata + :iclass iclass + :dclass dclass) + ;; + (format t " -- check net state~% ~A->~A~% ~A->~A~% ~A->~A~%" + (float-vector 0 0) + (caffe::memory-calc-forward :input (float-vector 0 0) :osize 1) + (float-vector 0 2) + (caffe::memory-calc-forward :input (float-vector 0 2) :osize 1) + (float-vector 2 5) + (caffe::memory-calc-forward :input (float-vector 2 5) :osize 1)) + ) + +(defun unix-command-line + (cmd) + (let* ((p (piped-fork cmd)) + (ret (read-line p nil))) + (close p) + ret)) + +(defun smart-initialize-net + nil + (let* ((caffemodel (unix-command-line "ls -t | grep -e \"caffemodel$\" | head -n 1"))) + (warning-message 6 "load caffe model ~A~%" caffemodel) + (caffe::gen-test-net :netproto "predict_linear_equation_net.prototxt" + :caffemodel caffemodel)) + ) diff --git a/eus_caffe/sample/linear_equation/linear_equation.prototxt b/eus_caffe/sample/linear_equation/linear_equation.prototxt new file mode 100644 index 000000000..631cf83f4 --- /dev/null +++ b/eus_caffe/sample/linear_equation/linear_equation.prototxt @@ -0,0 +1,12 @@ +net: "linear_equation_net.prototxt" +solver_type: SGD +base_lr: 0.01 +lr_policy: "step" +gamma: 0.9 +stepsize: 10000 ## learning rate update: base_lr *= gamma, in every stepsize calcuration +max_iter: 100000 +## snapshot: 100000 +momentum: 0.9 +display: 10000 +snapshot_prefix: "linear_equation" +solver_mode: CPU diff --git a/eus_caffe/sample/linear_equation/linear_equation_net.prototxt b/eus_caffe/sample/linear_equation/linear_equation_net.prototxt new file mode 100644 index 000000000..c910b6fd7 --- /dev/null +++ b/eus_caffe/sample/linear_equation/linear_equation_net.prototxt @@ -0,0 +1,122 @@ +name: "linear_equation_net" +layer { + name: "input" + type: "MemoryData" + top: "input" + top: "dummy_label1" + memory_data_param { + batch_size: 32 + channels: 2 + height: 1 + width: 1 + } +} +layer { + name: "ip" + type: "InnerProduct" + bottom: "input" + top: "ip" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 50 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode1neuron" + type: "Sigmoid" + bottom: "ip" + top: "encode1neuron" +} +layer { + name: "middle1" + type: "InnerProduct" + bottom: "encode1neuron" + top: "middle1" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 10 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode2neuron" + type: "Sigmoid" + bottom: "middle1" + top: "encode2neuron" +} +layer { + name: "output" + type: "InnerProduct" + bottom: "encode2neuron" + top: "output" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 1 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "target" + type: "MemoryData" + top: "target" + top: "dummy_label2" + memory_data_param { + batch_size: 32 + channels: 1 + height: 1 + width: 1 + } +} +layer { + name: "loss" + type: "EuclideanLoss" + bottom: "output" + bottom: "target" + top: "loss" +} diff --git a/eus_caffe/sample/linear_equation/predict_linear_equation_net.prototxt b/eus_caffe/sample/linear_equation/predict_linear_equation_net.prototxt new file mode 100644 index 000000000..f74b581e8 --- /dev/null +++ b/eus_caffe/sample/linear_equation/predict_linear_equation_net.prototxt @@ -0,0 +1,96 @@ +name: "predict_linear_equation_net" +input: "input" +input_dim: 1 ## num +input_dim: 2 ## channel +input_dim: 1 ## w +input_dim: 1 ## h +layer { + name: "ip" + type: "InnerProduct" + bottom: "input" + top: "ip" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 50 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode1neuron" + type: "Sigmoid" + bottom: "ip" + top: "encode1neuron" +} +layer { + name: "middle1" + type: "InnerProduct" + bottom: "encode1neuron" + top: "middle1" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 10 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} +layer { + name: "encode2neuron" + type: "Sigmoid" + bottom: "middle1" + top: "encode2neuron" +} +layer { + name: "output" + type: "InnerProduct" + bottom: "encode2neuron" + top: "output" + param { + lr_mult: 1 + decay_mult: 1 + } + param { + lr_mult: 1 + decay_mult: 0 + } + inner_product_param { + num_output: 1 + weight_filler { + type: "gaussian" + std: 1 + sparse: 1 + } + bias_filler { + type: "constant" + value: 0 + } + } +} diff --git a/eus_caffe/sh/cuda_run.sh b/eus_caffe/sh/cuda_run.sh new file mode 100755 index 000000000..e689e7f0c --- /dev/null +++ b/eus_caffe/sh/cuda_run.sh @@ -0,0 +1,3 @@ +#!/usr/bin/env bash + +sudo /usr/local/cuda-7.0/samples/bin/x86_64/linux/release/vectorAdd diff --git a/eus_caffe/sh/graph.sh b/eus_caffe/sh/graph.sh new file mode 100755 index 000000000..812b8caeb --- /dev/null +++ b/eus_caffe/sh/graph.sh @@ -0,0 +1,35 @@ +#!/usr/bin/env bash + +function gen_loss_graph(){ + log=$1; + xtics_size=1; + last_x=`tail ${log} --lines=1000 | grep -e "^.\+Iteration \([0-9]\+\), loss = \([0-9\.]\+\)$" | tail -1 | sed -e "s/^.\+Iteration \([0-9]\+\), loss = \([0-9\.]\+\)$/\\1/g"`; + xtics_scale=`echo "${last_x} / ${xtics_size}" | bc`; + ## gen log data for graph + echo "output data -> /tmp/${log}.dat"; + echo -n "" > /tmp/${log}.dat ; ID=0; + cat ${log} | grep -e "^.\+Iteration \([0-9]\+\), loss = \([0-9\.]\+\)$" | sed -e "s/^.\+Iteration \([0-9]\+\), loss = \([0-9\.]\+\)$/\\1 \\2/g" | while read d; do + id=`echo ${d} | sed -e "s/^\(.\+\) .\+$/\\1/g"`; + val=`echo ${d} | sed -e "s/^.\+ \(.\+\)$/\\1/g"`; + id2=`echo "$id / ${xtics_scale}" | bc -l`; + echo $id2 $val >> /tmp/${log}.dat ; ID=`expr $ID + 1`; + done + echo " --- output data done, start plotting"; + ## + gnuplot < +#include +#include +#include + +#include + +class eus_caffe_db{ +private: + std::shared_ptr db_; + std::shared_ptr txn_; + std::shared_ptr cursor_; + caffe::Datum datum_; + std::string db_type_; std::string db_path_; int db_mode_; + int put_cnt; + // int size; + +public: + eus_caffe_db(){ + this->put_cnt=0; + // this->size = -1; + } + ~eus_caffe_db(){ + this->close(); + } + + int open(const char* db_type, const char* path, int m){ + // + this->db_type_.assign(db_type); + this->db_path_.assign(path); + this->db_mode_ = m; + std::cout << "db open: " << this->db_path_ << "(" << this->db_type_ << ")" << std::endl; + // + struct stat buf; + caffe::db::Mode mode; + int file_exist = stat(path, &buf); + switch ( m ){ + case 'n': mode = caffe::db::NEW; break; + case 'w': mode = caffe::db::WRITE; break; + case 'r': mode = caffe::db::READ; break; + default: + std::cout << "unknown mode character " << m << std::endl; + std::cout << " -- read mode" << std::endl; + mode = caffe::db::READ; + } + // file check + if (mode == caffe::db::NEW && path && file_exist==0){ + std::cout << "unable to create file " << path << std::endl; + return 1; + } else if ((mode == caffe::db::WRITE || mode == caffe::db::READ) && file_exist!=0){ + std::cout << "unable to read file " << path << std::endl; + return 1; + } + // + // db open + if ( this->db_ ){ + this->db_.reset(caffe::db::GetDB(db_type)); + } else { + this->db_ = std::shared_ptr(caffe::db::GetDB(db_type)); + } + this->db_->Open(path, mode); + // + // transaction initialize, -> auto initialize in put function + // if ( mode == caffe::db::NEW || mode == caffe::db::WRITE ){ + // if ( this->txn_ ){ + // this->txn_.reset(this->db_->NewTransaction()); + // } else { + // this->txn_ = std::shared_ptr(this->db_->NewTransaction()); + // } + // } else { // read mode + // if ( this->txn_ ) { + // this->txn_.reset(); + // this->txn_ = NULL; + // } + // } + // + // cursor initialize + if ( mode == caffe::db::READ || mode == caffe::db::WRITE ){ + if ( this->cursor_ ){ + this->cursor_.reset(this->db_->NewCursor()); + } else { + this->cursor_ = std::shared_ptr(this->db_->NewCursor()); + } + this->read(0); + } else { + if ( this->cursor_ ) { + this->cursor_.reset(); + this->cursor_ = NULL; + } + } + // + return 0; + } + + int close(){ + if ( this->txn_ ) { + std::cout << " -- transaction close" << std::endl; + if ( this->put_cnt != 0 ) this->txn_->Commit(); + this->txn_.reset(); + this->txn_ = NULL; + // this->commit(); + } + if ( this->cursor_ ) { + std::cout << " -- cursor close" << std::endl; + this->cursor_.reset(); + this->cursor_ = NULL; + } + if ( this->db_ ) { + std::cout << " -- db close" << std::endl; + this->db_->Close(); + this->db_.reset(); + this->db_ = NULL; + } + return 0; + } + + int reopen(){ + this->close(); + this->open(this->db_type_.c_str(), this->db_path_.c_str(), this->db_mode_); + return 0; + } + + int get_data_size(){ + assert(this->cursor_); + return this->datum_.data().size(); + } + + int get_float_data_size(){ + assert(this->cursor_); + return this->datum_.float_data_size(); + } + + int get_key_size(){ + assert(this->cursor_); + return this->cursor_->key().size(); + } + + int get_data(char* buf){ + assert(this->cursor_); + const std::string& val = this->datum_.data(); + for ( int i=0; icursor_); + for ( int i=0; idatum_.float_data_size() ; i++ ){ + buf[i] = this->datum_.float_data(i); + } + return this->datum_.float_data_size(); + } + + int get_key(char* buf){ + assert(this->cursor_); + const std::string& val = this->cursor_->key(); + for ( int i=0; icursor_); + return this->datum_.label(); + } + + int get_shape(double* ret){ + assert(this->cursor_); + ret[0] = this->datum_.channels(); + ret[1] = this->datum_.width(); + ret[2] = this->datum_.height(); + return 0; + } + + int dump_datum(){ + assert(this->cursor_); + std::cout << "key : " << this->cursor_->key() << std::endl; + std::cout << "label: " << this->datum_.label() << std::endl; + std::cout << "data : " << this->datum_.data() << std::endl; + std::cout << "fdata: " << "("; + for ( int i=0; idatum_.float_data_size() ; i++ ){ + std::cout << this->datum_.float_data(i) ; + if ( i < this->datum_.float_data_size()-1 ){ + std::cout << ", " ; + } + } + std::cout << ")" << std::endl; + std::cout << "size :" + // << this->datum_.num() << " x " + << this->datum_.channels() << " x " + << this->datum_.width() << " x " + << this->datum_.height() << std::endl; + return 0; + } + + int read_pos(int pos){ + assert(this->cursor_); + this->cursor_->SeekToFirst(); + return this->read(pos); + } + + int read(int step){ + assert(this->cursor_); + for ( int i=0; icursor_->Next(); + if (!this->cursor_->valid()) { + std::cout << " cursor seak to first" << std::endl; + this->cursor_->SeekToFirst(); + } + } + this->datum_.ParseFromString(this->cursor_->value()); + return 0; + } + + int get_size(){ + assert(this->cursor_); + this->cursor_->SeekToFirst(); + int ret = 0; + while ( this->cursor_->valid() ){ + this->cursor_->Next(); + ret++; + } + this->cursor_->SeekToFirst(); + this->datum_.ParseFromString(this->cursor_->value()); + return ret; + } + + int _put(int chan, int width, int height, int label, char* key, char* data, int data_max, double* float_data, int float_data_max){ + //assert(this->txn_); + if ( ! this->txn_ ){ + this->txn_ = std::shared_ptr(this->db_->NewTransaction()); + this->put_cnt = 0; + } + // + this->datum_.set_channels(chan); + this->datum_.set_height(width); + this->datum_.set_width(height); + this->datum_.set_label(label); + if ( data && data_max > 0 ){ + this->datum_.set_data(data, data_max); + } else { + this->datum_.clear_data(); + } + if ( float_data && float_data_max > 0 ){ + this->datum_.clear_float_data(); + for ( int i=0 ; idatum_.add_float_data((float)float_data[i]); + } + } else { + this->datum_.clear_float_data(); + } + std::string datum_str; + this->datum_.SerializeToString(&datum_str); + this->txn_->Put(key, datum_str); + if ( ++this->put_cnt % 100000 == 0 ) this->commit(); + return 0; + } + + int commit(){ + assert(this->txn_); + std::cout << "db commit size=" << this->put_cnt << std::endl; + // + int ret = this->put_cnt; + if ( this->put_cnt != 0 ){ + this->txn_->Commit(); + this->put_cnt = 0; + // this->txn_.reset(this->db_->NewTransaction()); + this->txn_.reset(); + this->txn_ = NULL; + } else { + std::cout << " -- empty transaction, skipped" << std::endl; + } + return ret; + } + + int put(int chan, int width, int height, int label, char* key, char* data, int data_max){ + return this->_put(chan,width,height,label,key,data,data_max,NULL,0); + } + + int put_double(int chan, int width, int height, int label, char* key, double* data, int data_max){ + return this->_put(chan,width,height,label,key,NULL,0,data,data_max); + } + +}; + +// for euslisp + +int ecdv_id=0; +std::vector > ecdv(1, std::shared_ptr(new eus_caffe_db)); +std::shared_ptr ecd = ecdv[0]; + +extern "C" { + int eus_caffe_db_set_id(int id){ + ecdv_id = id; + for ( int i=ecdv.size() ; i<=id ; i++ ) { + std::cout << "eus_caffe expand db size -> " << (i+1) << std::endl; + ecdv.push_back(std::shared_ptr(new eus_caffe_db)); + } + ecd = ecdv[ecdv_id]; + // std::cout << "eus_caffe db_set_id " << id << std::endl; + return 0; + } +} + +extern "C" { + int eus_caffe_db_open(char* db_type, char* path, int mode){ return ecd->open(db_type, path, mode); } + int eus_caffe_db_close(){ return ecd->close() ; } + int eus_caffe_db_reopen(){ return ecd->reopen() ; } + int eus_caffe_db_put(int chan, int width, int height, int label, char* id_str, char* data, int data_max){ return ecd->put(chan,width,height,label,id_str,data,data_max); } + int eus_caffe_db_put_double(int chan, int width, int height, int label, char* id_str, double* data, int data_max){ return ecd->put_double(chan,width,height,label,id_str,data,data_max); } + int eus_caffe_db_commit(){ return ecd->commit() ; } + int eus_caffe_db_read(int step){ return ecd->read(step) ; } + int eus_caffe_db_read_pos(int pos){ return ecd->read_pos(pos) ; } + int eus_caffe_db_dump(){ return ecd->dump_datum() ; } + int eus_caffe_db_get_size(){ return ecd->get_size() ; } + int eus_caffe_db_get_shape(double* ret){ return ecd->get_shape(ret) ; } + int eus_caffe_db_get_data(char* ret){ return ecd->get_data(ret) ; } + int eus_caffe_db_get_label(){ return ecd->get_label() ; } + int eus_caffe_db_get_float_data(double* ret){ return ecd->get_float_data(ret) ; } + int eus_caffe_db_get_key(char* ret){ return ecd->get_key(ret) ; } + int eus_caffe_db_get_data_size(){ return ecd->get_data_size() ; } + int eus_caffe_db_get_float_data_size(){ return ecd->get_float_data_size() ; } + int eus_caffe_db_get_key_size(){ return ecd->get_key_size() ; } +} diff --git a/eus_caffe/src/eus_caffe_lib.cpp b/eus_caffe/src/eus_caffe_lib.cpp new file mode 100644 index 000000000..0a2be4e90 --- /dev/null +++ b/eus_caffe/src/eus_caffe_lib.cpp @@ -0,0 +1,286 @@ +#include +#include +#include +#include +#include +#include +#include + +class eus_caffe { +private: + caffe::SolverParameter solver_param; + boost::shared_ptr> solver; + boost::shared_ptr> test_net; + bool output_log; + +public: + eus_caffe() { this->output_log = true; } + + bool set_output_log(bool val) { this->output_log = val; } + + template bool _check(boost::shared_ptr val, std::string name){ + if (! val) { + if (this->output_log) std::cout << name << " is NULL" << std::endl; + return false; + } else { + return true; + } + } + + int get_blob_count (boost::shared_ptr > blob) { + if ( ! this->_check(blob, "blob") ) return -1 ; + return blob->count(); + } + + int get_blob_count(boost::shared_ptr> net, char* name) { + if ( ! this->_check(net, "net") ) return -1 ; + return this->get_blob_count( net->blob_by_name(name)); + } + + int get_blob_count(char* name){ + return this->get_blob_count(this->test_net, name); + } + + int get_train_net_blob_count (char* name) { + if ( ! this->_check(this->solver, "solver") ) return -1 ; + boost::shared_ptr> net = this->solver->net(); + return this->get_blob_count( net, name); + } + + int get_blob_data (boost::shared_ptr > blob, double* ret, int osize) { + if ( ! this->_check(blob, "blob") ) return -1 ; + if (this->output_log) std::cout << "[i E " << blob->count() << "] = "<< " ("; + if ( osize < 0 || osize > blob->count() ) osize = blob->count(); + for ( int i=0; icpu_data()[i]; + if ( osize < 64 && this->output_log) std::cout << ret[i] << " "; + } + if ( blob->count() >= 64 && this->output_log) std::cout << "..."; + if (this->output_log) std::cout << ")" << std::endl; + return 0; + } + + int get_blob_data (boost::shared_ptr> net, char* name, double* ret, int osize) { + if ( ! this->_check(net, "net") ) return -1 ; + return this->get_blob_data( net->blob_by_name(name), ret, osize); + } + + int get_train_net_blob_data (char* name, double* ret, int osize) { + if ( ! this->_check(this->solver, "solver") ) return -1 ; + boost::shared_ptr> net = this->solver->net(); + return this->get_blob_data( net, name, ret, osize); + } + + int get_blob_data (char* name, double* ret, int osize) { + return this->get_blob_data( this->test_net, name, ret, osize); + } + + int get_layer_blob_data (boost::shared_ptr> net, char* name, int blob_id, double* ret, int osize) { + if ( ! this->_check(net, "net") ) return -1 ; + const boost::shared_ptr> layer = net->layer_by_name(name); + std::vector>> ip_blobs = layer->blobs(); + if (this->output_log) std::cout << "<" << layer->type() << ">" << name << "[" << blob_id << "<" << ip_blobs.size() << "]" ; + if ( ip_blobs.size() <= blob_id ){ + if (this->output_log) std::cout << std::endl; + if (this->output_log) std::cout << " --- too large blob_id" << std::endl; + return -1; + } + return this->get_blob_data(ip_blobs[blob_id], ret, osize); + } + + int get_layer_blob_data (char* name, int blob_id, double* ret, int osize) { + this->get_layer_blob_data(this->test_net,name,blob_id,ret,osize); + } + + int get_train_net_layer_blob_data (char* name, int blob_id, double* ret, int osize) { + if ( ! this->_check(this->solver, "solver") ) return -1 ; + boost::shared_ptr> net = this->solver->net(); + this->get_layer_blob_data(net,name,blob_id,ret,osize); + } + + int get_input_blob_data(int id, double* ret, int osize){ + if ( ! this->_check(this->solver, "solver") ) return -1 ; + if ( id >= this->solver->net()->input_blobs().size() ){ + if (this->output_log) + std::cout << "too large id for input layer " + << id << " > " << this->solver->net()->input_blobs().size() + << std::endl; + return 1; + } + return this->get_blob_data( boost::shared_ptr >(this->solver->net()->input_blobs()[id]), ret ,osize); + } + + int create_solver (char* solver_path, char* solverstate){ + struct stat buf; + if (solver_path && stat(solver_path, &buf)==0){ + caffe::ReadProtoFromTextFileOrDie(solver_path, &this->solver_param); + if ( this->solver ) this->solver.reset(); + this->solver = boost::shared_ptr>(caffe::GetSolver(this->solver_param)); + if (solverstate && stat(solverstate, &buf)==0) { + if (this->output_log) std::cout << "Restoring previous solver status from " << solverstate << std::endl; + this->solver->Restore(solverstate); + } + // + int FLAGS_gpu = -1; + if (this->solver_param.solver_mode() == caffe::SolverParameter_SolverMode_GPU) { + FLAGS_gpu = solver_param.device_id(); + } + if (FLAGS_gpu >= 0) { + LOG(INFO) << "Use GPU with device ID " << FLAGS_gpu; + caffe::Caffe::SetDevice(FLAGS_gpu); + caffe::Caffe::set_mode(caffe::Caffe::GPU); + } else { + LOG(INFO) << "Use CPU."; + caffe::Caffe::set_mode(caffe::Caffe::CPU); + } + } + return 0; + } + + int reset_memory_layer(char* name, int size, double* data, double* label){ + if ( ! this->_check(this->solver, "solver") ) return -1 ; + // + boost::shared_ptr> net = this->solver->net(); + const boost::shared_ptr> layer_org = net->layer_by_name(name); + if ( ! this->_check(layer_org, name) ) return 1; + if ( std::string(layer_org->type()) == "MemoryData" ) { + boost::shared_ptr> layer = + boost::dynamic_pointer_cast>(layer_org); + layer->Reset(data, label, size); + } else { + if (this->output_log) std::cout << " reset_memory failed, type = " << layer_org->type() << std::endl; + } + // + return 0; + } + + // deprecated + int initialize_solver (int isize, int dsize, double* idata, double* ddata, double* idummy, double* ddummy){ + return this->reset_memory_layer((char*)"input", isize, idata, idummy) + this->reset_memory_layer((char*)"target", dsize, ddata, ddummy); + } + + double caffe_learn () { + if ( ! this->_check(this->solver, "solver") ) return -1 ; + // + // caffe::set_phase(caffe::TRAIN); + this->solver->Solve(); + // + double buf[1]; + boost::shared_ptr> net = this->solver->net(); + this->get_blob_data(net, (char*)"loss", buf, 1); + return buf[0]; + } + + int memory_calc_forward (int inputsize, int outputsize, double* input, double* output, double* idummy){ + if ( ! this->_check(this->solver, "solver") ) return 1 ; + boost::shared_ptr> net = this->solver->net(); + const boost::shared_ptr> layer_org = net->layer_by_name("input"); + if ( ! this->_check(layer_org, "input_layer") ) return 1; + if ( ! (std::string(layer_org->type()) == "MemoryData") ) return 1; + boost::shared_ptr> input_layer = + boost::dynamic_pointer_cast>(layer_org); + // + input_layer->Reset(input, idummy, inputsize); + net->ForwardPrefilled(nullptr); + // + this->get_blob_data(net, (char*)"output", output, outputsize); + return 0; + } + + int calc_forward (int num, int channels, int width, int height, + int inputsize, char* input, + int outputsize, double* output){ + return _calc_forward(num,channels,width,height,inputsize,input,0,NULL,outputsize,output); + } + + int calc_forward_double (int num, int channels, int width, int height, + int inputsize, double* input, + int outputsize, double* output){ + return _calc_forward(num,channels,width,height,0,NULL,inputsize,input,outputsize,output); + } + + int _calc_forward (int num, int channels, int width, int height, + int inputsize, char* input, + int finputsize, double* finput, + int outputsize, double* output){ + if ( ! this->_check(this->test_net, "test_net") ) return -1 ; + // + // std::cout << "calc_forward" << std::endl; + // boost::shared_ptr> net = this->solver->net(); + // caffe::Blob* blob = new caffe::Blob(); + caffe::Blob blob; + std::vector*> bottom; + caffe::BlobProto blob_proto; + blob_proto.set_num(num); + blob_proto.set_channels(channels); + blob_proto.set_height(height); + blob_proto.set_width(width); + if ( inputsize > 0 && input ){ // set data, char input precede + for ( int i=0 ; i 0 && finput ){ + for ( int i=0 ; i_get_blob_data(boost::shared_ptr>(blob), ret, 10); + // std::cout << " -- initialize done" << std::endl; + this->test_net->Forward(bottom, nullptr); + // net->Forward(bottom, nullptr); + // std::cout << " -- forwarding done" << std::endl; + // + this->get_blob_data(this->test_net, (char*)"output", output, outputsize); + return 0; + } + + int gen_test_net (char* net_path_, char* train_file){ + struct stat buf; + const char* net_path ; + if ( net_path_ && stat(net_path_, &buf)==0) { + net_path = net_path_; + } else if ( this->solver && this->solver_param.has_net() && stat(this->solver_param.net().c_str(), &buf)==0) { + net_path = this->solver_param.net().c_str(); + } else { + if (this->output_log) std::cout << " network missing" << std::endl; + return 1; + } + if ( this->test_net ) this->test_net.reset(); + this->test_net = boost::shared_ptr>(new caffe::Net(net_path, caffe::TEST)); + // + if (train_file && stat(train_file, &buf)==0){ + this->test_net->CopyTrainedLayersFrom(train_file); + } else if ( this->solver ) { + this->test_net->ShareTrainedLayersWith(this->solver->net().get()); + } else { + if (this->output_log) std::cout << " no layer params" << std::endl; + return 1; + } + return 0; + } +}; + +boost::shared_ptr ec(new eus_caffe); + +extern "C" { + int eus_caffe_output_log (int val){ return (int)ec->set_output_log((bool)val); } + int eus_caffe_get_blob_count (char* name){ return ec->get_blob_count(name); } + int eus_caffe_get_train_net_blob_count (char* name){ return ec->get_train_net_blob_count(name); } + int eus_caffe_get_blob_data (char* name, double* ret, int osize){ return ec->get_blob_data(name,ret,osize); } + int eus_caffe_get_train_net_blob_data (char* name, double* ret, int osize){ return ec->get_train_net_blob_data(name,ret,osize); } + int eus_caffe_get_layer_blob_data (char* name, int blob_id, double* ret, int osize) { return ec->get_layer_blob_data(name,blob_id,ret,osize); } + int eus_caffe_get_train_net_layer_blob_data (char* name, int blob_id, double* ret, int osize) { return ec->get_train_net_layer_blob_data(name,blob_id,ret,osize); } + int eus_caffe_get_input_blob_data (int id, double* ret, int osize){ return ec->get_input_blob_data(id,ret,osize); } + // + int eus_caffe_create_solver (char* solver_path, char* solverstate){ return ec->create_solver(solver_path,solverstate); } + int eus_caffe_reset_memory_layer (char* name, int size, double* data, double* label){ return ec->reset_memory_layer(name,size,data,label); } + int eus_caffe_initialize_solver (int isize, int dsize, double* idata, double* ddata, double* idummy, double* ddummy){ return ec->initialize_solver(isize,dsize,idata,ddata,idummy,ddummy); } + double eus_caffe_learn () { return ec->caffe_learn(); } + int eus_caffe_calc_forward (int num, int channels, int width, int height, int inputsize, char* input, int outputsize, double* output){ return ec->calc_forward(num,channels,width,height,inputsize,input,outputsize,output);} + int eus_caffe_calc_forward_double (int num, int channels, int width, int height, int inputsize, double* input, int outputsize, double* output){ return ec->calc_forward_double(num,channels,width,height,inputsize,input,outputsize,output);} + int eus_caffe_memory_calc_forward (int inputsize, int outputsize, double* input, double* output, double* idummy){ return ec->memory_calc_forward(inputsize,outputsize,input,output,idummy);} + int eus_caffe_gen_test_net (char* net_path, char* train_file){ return ec->gen_test_net(net_path, train_file); } +} diff --git a/eus_caffe/src/eus_log_lib.cpp b/eus_caffe/src/eus_log_lib.cpp new file mode 100644 index 000000000..93da6c793 --- /dev/null +++ b/eus_caffe/src/eus_log_lib.cpp @@ -0,0 +1,74 @@ +#include +#include +#include +#include + +std::shared_ptr eus_log_stdcout(std::cout.rdbuf()); +std::shared_ptr eus_log_stdcerr(std::cerr.rdbuf()); +std::shared_ptr eus_log_ofs; + +extern "C" { + int log_change_output_stream(char* path, int size){ + if ( path && size > 0 ){ + if ( eus_log_ofs ) { + eus_log_ofs->close(); + eus_log_ofs.reset(new std::ofstream(path)); + } else { + eus_log_ofs = std::shared_ptr(new std::ofstream(path)); + } + std::cout.rdbuf(eus_log_ofs->rdbuf()); + std::cerr.rdbuf(eus_log_ofs->rdbuf()); + } else { + if ( eus_log_ofs ) { + eus_log_ofs->close(); + eus_log_ofs = NULL; + } + std::cout.rdbuf(eus_log_stdcout.get()); + std::cerr.rdbuf(eus_log_stdcerr.get()); + } + return 0; + } + + int log_test_echo(char* str){ + std::cout << str << std::endl; + std::cerr << str << std::endl; + return 0; + } + + int size_vector(char* path){ + std::ifstream ifs(path, std::ios::binary); + std::streamsize s = ifs.seekg(0,std::ios::end).tellg(); + ifs.close(); + return (int)(s/sizeof(double)); + } + + int write_vector(char* path, double* val, int size){ + std::ofstream fout(path, std::ios::out|std::ios::binary|std::ios::trunc); + if ( ! fout ) { + std::cout << "file not found " << path << std::endl; + return 255; + } + fout.write((char*)val, size * sizeof(double)); + fout.close(); + return 0; + } + + int read_vector(char* path, double* val, int size){ + std::ifstream fin(path, std::ios::in|std::ios::binary); + if ( ! fin ) { + std::cout << "file not found " << path << std::endl; + return 0; + } + double d; + for (int i=0; i" << size << std::endl; + return i; + } + fin.read( (char*)&d, sizeof(double) ); + val[i] = d; + } + fin.close(); + return size; + } +}