Compare commits
40 Commits
@ -0,0 +1,9 @@ |
|||
# Miniprojet: Extraction des Ordres à Partir de Gestes |
|||
|
|||
## TODO |
|||
|
|||
- [ ] sauvegarder et lire des fichiers qui contiennent des descripteurs; |
|||
- [ ] sauvegarder les poids du réseau depuis matlab et les lire en c++; |
|||
- [ ] sauvegarder les prototypes de kmeans et les lire en c++; |
|||
- [ ] implémenter les k-means; |
|||
- [ ] implémenter l'algo de réseau de néuronnes; |
|||
@ -1,206 +1,30 @@ |
|||
cmake_minimum_required(VERSION 2.8.3) |
|||
project(gesture_based_control) |
|||
|
|||
## Compile as C++11, supported in ROS Kinetic and newer |
|||
# add_compile_options(-std=c++11) |
|||
add_compile_options(-std=c++11) |
|||
|
|||
## Find catkin macros and libraries |
|||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) |
|||
## is used, also find other catkin packages |
|||
find_package(catkin REQUIRED COMPONENTS |
|||
geometry_msgs |
|||
roscpp |
|||
std_msgs |
|||
cv_bridge |
|||
image_transport |
|||
dynamic_reconfigure |
|||
) |
|||
|
|||
## System dependencies are found with CMake's conventions |
|||
# find_package(Boost REQUIRED COMPONENTS system) |
|||
|
|||
|
|||
## Uncomment this if the package has a setup.py. This macro ensures |
|||
## modules and global scripts declared therein get installed |
|||
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html |
|||
# catkin_python_setup() |
|||
|
|||
################################################ |
|||
## Declare ROS messages, services and actions ## |
|||
################################################ |
|||
|
|||
## To declare and build messages, services or actions from within this |
|||
## package, follow these steps: |
|||
## * Let MSG_DEP_SET be the set of packages whose message types you use in |
|||
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). |
|||
## * In the file package.xml: |
|||
## * add a build_depend tag for "message_generation" |
|||
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET |
|||
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in |
|||
## but can be declared for certainty nonetheless: |
|||
## * add a exec_depend tag for "message_runtime" |
|||
## * In this file (CMakeLists.txt): |
|||
## * add "message_generation" and every package in MSG_DEP_SET to |
|||
## find_package(catkin REQUIRED COMPONENTS ...) |
|||
## * add "message_runtime" and every package in MSG_DEP_SET to |
|||
## catkin_package(CATKIN_DEPENDS ...) |
|||
## * uncomment the add_*_files sections below as needed |
|||
## and list every .msg/.srv/.action file to be processed |
|||
## * uncomment the generate_messages entry below |
|||
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) |
|||
|
|||
## Generate messages in the 'msg' folder |
|||
# add_message_files( |
|||
# FILES |
|||
# Message1.msg |
|||
# Message2.msg |
|||
# ) |
|||
|
|||
## Generate services in the 'srv' folder |
|||
# add_service_files( |
|||
# FILES |
|||
# Service1.srv |
|||
# Service2.srv |
|||
# ) |
|||
|
|||
## Generate actions in the 'action' folder |
|||
# add_action_files( |
|||
# FILES |
|||
# Action1.action |
|||
# Action2.action |
|||
# ) |
|||
|
|||
## Generate added messages and services with any dependencies listed here |
|||
# generate_messages( |
|||
# DEPENDENCIES |
|||
# geometry_msgs# std_msgs |
|||
# ) |
|||
|
|||
################################################ |
|||
## Declare ROS dynamic reconfigure parameters ## |
|||
################################################ |
|||
|
|||
## To declare and build dynamic reconfigure parameters within this |
|||
## package, follow these steps: |
|||
## * In the file package.xml: |
|||
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" |
|||
## * In this file (CMakeLists.txt): |
|||
## * add "dynamic_reconfigure" to |
|||
## find_package(catkin REQUIRED COMPONENTS ...) |
|||
## * uncomment the "generate_dynamic_reconfigure_options" section below |
|||
## and list every .cfg file to be processed |
|||
|
|||
## Generate dynamic reconfigure parameters in the 'cfg' folder |
|||
# generate_dynamic_reconfigure_options( |
|||
# cfg/DynReconf1.cfg |
|||
# cfg/DynReconf2.cfg |
|||
# ) |
|||
|
|||
################################### |
|||
## catkin specific configuration ## |
|||
################################### |
|||
## The catkin_package macro generates cmake config files for your package |
|||
## Declare things to be passed to dependent projects |
|||
## INCLUDE_DIRS: uncomment this if your package contains header files |
|||
## LIBRARIES: libraries you create in this project that dependent projects also need |
|||
## CATKIN_DEPENDS: catkin_packages dependent projects also need |
|||
## DEPENDS: system dependencies of this project that dependent projects also need |
|||
catkin_package( |
|||
# INCLUDE_DIRS include |
|||
# LIBRARIES gesture_based_control |
|||
# CATKIN_DEPENDS geometry_msgs roscpp std_msgs |
|||
# DEPENDS system_lib |
|||
generate_dynamic_reconfigure_options( |
|||
cfg/Descriptor.cfg |
|||
) |
|||
|
|||
########### |
|||
## Build ## |
|||
########### |
|||
catkin_package() |
|||
|
|||
## Specify additional locations of header files |
|||
## Your package locations should be listed before other locations |
|||
include_directories( |
|||
# include |
|||
${catkin_INCLUDE_DIRS} |
|||
) |
|||
|
|||
## Declare a C++ library |
|||
# add_library(${PROJECT_NAME} |
|||
# src/${PROJECT_NAME}/gesture_based_control.cpp |
|||
# ) |
|||
|
|||
## Add cmake target dependencies of the library |
|||
## as an example, code may need to be generated before libraries |
|||
## either from message generation or dynamic reconfigure |
|||
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) |
|||
|
|||
## Declare a C++ executable |
|||
## With catkin_make all packages are built within a single CMake context |
|||
## The recommended prefix ensures that target names across packages don't collide |
|||
# add_executable(${PROJECT_NAME}_node src/gesture_based_control_node.cpp) |
|||
|
|||
## Rename C++ executable without prefix |
|||
## The above recommended prefix causes long target names, the following renames the |
|||
## target back to the shorter version for ease of user use |
|||
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" |
|||
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") |
|||
|
|||
## Add cmake target dependencies of the executable |
|||
## same as for the library above |
|||
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) |
|||
|
|||
## Specify libraries to link a library or executable target against |
|||
# target_link_libraries(${PROJECT_NAME}_node |
|||
# ${catkin_LIBRARIES} |
|||
# ) |
|||
|
|||
############# |
|||
## Install ## |
|||
############# |
|||
|
|||
# all install targets should use catkin DESTINATION variables |
|||
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html |
|||
|
|||
## Mark executable scripts (Python etc.) for installation |
|||
## in contrast to setup.py, you can choose the destination |
|||
# install(PROGRAMS |
|||
# scripts/my_python_script |
|||
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} |
|||
# ) |
|||
|
|||
## Mark executables for installation |
|||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html |
|||
# install(TARGETS ${PROJECT_NAME}_node |
|||
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} |
|||
# ) |
|||
|
|||
## Mark libraries for installation |
|||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html |
|||
# install(TARGETS ${PROJECT_NAME} |
|||
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} |
|||
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} |
|||
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} |
|||
# ) |
|||
|
|||
## Mark cpp header files for installation |
|||
# install(DIRECTORY include/${PROJECT_NAME}/ |
|||
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} |
|||
# FILES_MATCHING PATTERN "*.h" |
|||
# PATTERN ".svn" EXCLUDE |
|||
# ) |
|||
|
|||
## Mark other files for installation (e.g. launch and bag files, etc.) |
|||
# install(FILES |
|||
# # myfile1 |
|||
# # myfile2 |
|||
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} |
|||
# ) |
|||
|
|||
############# |
|||
## Testing ## |
|||
############# |
|||
|
|||
## Add gtest based cpp test target and link libraries |
|||
# catkin_add_gtest(${PROJECT_NAME}-test test/test_gesture_based_control.cpp) |
|||
# if(TARGET ${PROJECT_NAME}-test) |
|||
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) |
|||
# endif() |
|||
add_executable(controller src/controller.cpp) |
|||
target_link_libraries(controller ${catkin_LIBRARIES}) |
|||
|
|||
## Add folders to be run by python nosetests |
|||
# catkin_add_nosetests(test) |
|||
add_executable(descripteur src/descripteur.cpp) |
|||
target_link_libraries(descripteur ${catkin_LIBRARIES}) |
|||
#add_dependencies(descripteur ${PROJECT_NAME}_gencfg) |
|||
|
|||
@ -0,0 +1,11 @@ |
|||
#!/usr/bin/env python |
|||
PACKAGE = "gesture_based_control" |
|||
|
|||
from dynamic_reconfigure.parameter_generator_catkin import * |
|||
|
|||
gen = ParameterGenerator() |
|||
|
|||
gen.add("cmax", int_t, 0, "cmax", 50, 0, 100) |
|||
gen.add("threshold", int_t, 0, "threshold", 50, 0, 255) |
|||
|
|||
exit(gen.generate(PACKAGE, "gesture_based_control", "Descriptors")) |
|||
@ -0,0 +1,14 @@ |
|||
<launch> |
|||
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node"> |
|||
<param name="pixel_format" value="yuyv"/> |
|||
</node> |
|||
<node name="rqt_image_view" pkg="rqt_image_view" type="rqt_image_view"/> |
|||
<node name="controller" pkg="gesture_based_control" type="controller" output="screen"> |
|||
<remap from="/cmd_vel" to="/turtle1/cmd_vel"/> |
|||
</node> |
|||
<node name="turtle" pkg="turtlesim" type="turtlesim_node"/> |
|||
<node name="descripteur" pkg="gesture_based_control" type="descripteur" output="screen"> |
|||
<remap from="/image_raw" to="/usb_cam/image_raw"/> |
|||
</node> |
|||
<node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure"/> |
|||
</launch> |
|||
@ -0,0 +1,38 @@ |
|||
#include <ros/ros.h> |
|||
#include <std_msgs/String.h> |
|||
#include <geometry_msgs/Twist.h> |
|||
|
|||
void callback(const std_msgs::String& msg, geometry_msgs::Twist& cmd) { |
|||
if (msg.data == "avance") { |
|||
cmd.linear.x = 1.0; |
|||
cmd.angular.z = 0.0; |
|||
} else if (msg.data == "arret") { |
|||
cmd = geometry_msgs::Twist(); |
|||
} else if (msg.data == "gauche") { |
|||
cmd.angular.z = 1.0; |
|||
cmd.linear.x = 0.0; |
|||
} else if (msg.data == "droite") { |
|||
cmd.angular.z = -1.0; |
|||
cmd.linear.x = 0.0; |
|||
} |
|||
} |
|||
|
|||
int main(int argc, char** argv) { |
|||
ros::init(argc, argv, "controller"); |
|||
|
|||
ros::NodeHandle n; |
|||
ros::Publisher pub = n.advertise<geometry_msgs::Twist>("/cmd_vel", 0); |
|||
|
|||
geometry_msgs::Twist cmd; |
|||
ros::Rate rate(10); |
|||
|
|||
boost::function<void(const std_msgs::String&)> cb = boost::bind(callback, _1, boost::ref(cmd)); |
|||
ros::Subscriber sub = n.subscribe<std_msgs::String&>("/order", 0, cb); |
|||
|
|||
while(ros::ok()) { |
|||
pub.publish(cmd); |
|||
ros::spinOnce(); |
|||
rate.sleep(); |
|||
} |
|||
return 0; |
|||
} |
|||
@ -0,0 +1,69 @@ |
|||
#include <ros/ros.h> |
|||
#include <opencv2/opencv.hpp> |
|||
#include <image_transport/image_transport.h> |
|||
#include <cv_bridge/cv_bridge.h> |
|||
#include <std_msgs/String.h> |
|||
#include <dynamic_reconfigure/server.h> |
|||
|
|||
#include <gesture_based_control/DescriptorsConfig.h> |
|||
#include "math.hpp" |
|||
#include "file.hpp" |
|||
#include "knn.hpp" |
|||
|
|||
void callback(gesture_based_control::DescriptorsConfig &config, uint32_t level, int& cmax, int& threshold) { |
|||
threshold = config.threshold; |
|||
} |
|||
|
|||
void callback(const sensor_msgs::ImageConstPtr& msg, int& threshold, int& cmax, ros::Publisher& order_pub, image_transport::Publisher& image_pub, math::dataset& dataset) { |
|||
cv_bridge::CvImagePtr cv_ptr; |
|||
std_msgs::String s; |
|||
|
|||
try { |
|||
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::RGB8); |
|||
}catch(cv_bridge::Exception& e) { |
|||
ROS_ERROR("cv_bridge exception: %s", e.what()); |
|||
return; |
|||
} |
|||
|
|||
cv::Mat& input = cv_ptr->image; |
|||
cv::Mat binaire(input.rows, input.cols, CV_8UC1); |
|||
math::filter(input, binaire, threshold); |
|||
cv::GaussianBlur(input, input, cv::Size(7,7), 1.5, 1.5); |
|||
|
|||
std::vector<math::contour> contours; |
|||
std::vector<cv::Vec4i> hierarchy; |
|||
cv::findContours(binaire, contours, hierarchy, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE); |
|||
if (contours.size() != 0) { |
|||
int index = math::max_cont(contours); |
|||
math::csignal desc = math::descriptors(contours[index], cmax); |
|||
s.data = predict(desc, dataset, 5, 2); |
|||
order_pub.publish(s); |
|||
|
|||
cv::drawContours(input, contours, index, 255); |
|||
} |
|||
image_pub.publish(cv_bridge::CvImage(msg->header, "rgb8", input).toImageMsg()); |
|||
} |
|||
|
|||
int main(int argc, char** argv) { |
|||
ros::init(argc, argv, "descripteur"); |
|||
|
|||
int threshold = 25; |
|||
int cmax = 10; |
|||
|
|||
math::dataset dataset = load_csv("/home/guillaume/Documents/3A_supelec/miniprojet/learning/descripteurs/dataset50.csv", 21); |
|||
|
|||
ros::NodeHandle n; |
|||
image_transport::ImageTransport it(n); |
|||
|
|||
ros::Publisher order_pub = n.advertise<std_msgs::String>("/order", 100); |
|||
image_transport::Publisher image_pub = it.advertise("/image_out", 1); |
|||
image_transport::Subscriber sub = it.subscribe("/image_raw", 1, boost::bind(callback, _1, boost::ref(threshold), boost::ref(cmax), boost::ref(order_pub), boost::ref(image_pub), boost::ref(dataset))); |
|||
|
|||
dynamic_reconfigure::Server<gesture_based_control::DescriptorsConfig> server; |
|||
dynamic_reconfigure::Server<gesture_based_control::DescriptorsConfig>::CallbackType f; |
|||
|
|||
f = boost::bind(&callback, _1, _2, boost::ref(cmax), boost::ref(threshold)); |
|||
server.setCallback(f); |
|||
|
|||
ros::spin(); |
|||
} |
|||
@ -0,0 +1 @@ |
|||
/home/guillaume/Documents/3A_supelec/miniprojet/tests/src/math.hpp |
|||
@ -0,0 +1,29 @@ |
|||
function [net, rt] = PMC_training(entree, sortie, n_cache, nb_apprentissage) |
|||
|
|||
[n_entree, nb_echantillons] = size(entree); |
|||
[n_sortie, ~] = size(sortie); |
|||
|
|||
% net = newff(entree, sortie, n_cache, {'tansig' 'tansig'}, 'trainscg'); |
|||
net = feedforwardnet(n_cache, 'trainscg'); |
|||
|
|||
net.trainParam.epochs = 1000; % Le nombre de cycle d’apprentissage est fixé à 1000 |
|||
|
|||
net.trainParam.lr = 0.02; % Le pas d’apprentissage est égal à 0.02 |
|||
|
|||
net.trainParam.show = 100; % Des informations sur les performances du réseau sont affichées tous les 100 cycles d’apprentissage |
|||
|
|||
net.trainParam.goal = 1e-10; % L’algorithme d’apprentissage s’arrête lorsque l’erreur quadratique moyenne est inférieure à 1e-10 |
|||
|
|||
net.trainParam.min_grad = 1e-10; % L’algorithme d’apprentissage s’arrête lorsque le module du gradient est inférieur à 1e-10 |
|||
|
|||
net.divideParam.trainRatio = nb_apprentissage / nb_echantillons; |
|||
net.divideParam.valRatio = 0; % On n'utilise pas d'ensemble de validation. |
|||
net.divideParam.testRatio = (nb_echantillons - nb_apprentissage) / nb_echantillons; |
|||
|
|||
net = train(net, entree, sortie); |
|||
|
|||
entree_test = entree(:,(nb_apprentissage + 1): nb_echantillons); |
|||
sortie_test = sortie(:,(nb_apprentissage + 1): nb_echantillons); |
|||
rt = sim(net, entree_test, [], [], sortie_test); |
|||
end |
|||
|
|||
@ -0,0 +1,176 @@ |
|||
#define _CRT_SECURE_NO_DEPRECATE |
|||
|
|||
#include <stdio.h> |
|||
#include <stdlib.h> |
|||
#include <string.h> |
|||
#include <malloc.h> |
|||
#include <math.h> |
|||
#include "constant.h" |
|||
#include "global.h" |
|||
#include "algo.h" |
|||
|
|||
void Erreur(char * chaine,int numero) |
|||
{ |
|||
fprintf(stderr,chaine); |
|||
fprintf(stderr,"\nerreur %d\n",numero); |
|||
exit(numero); |
|||
} |
|||
|
|||
int LireVecteurs (void) |
|||
{ |
|||
int k; |
|||
if((ent=fopen(noment,"rb"))==NULL) |
|||
return 1; |
|||
fread(&M,sizeof(int),1,ent); |
|||
fread(&dimvec,sizeof(int),1,ent); |
|||
fread(&dico,sizeof(int),1,ent); |
|||
fread(&numiter,sizeof(int),1,ent); |
|||
if((vecteurs=(float**)calloc(M,sizeof(float *)))==NULL) |
|||
return 3; |
|||
for(k=0;k<M;k++) |
|||
{ |
|||
if((vecteurs[k]=(float*)calloc(dimvec,sizeof(float)))==NULL) |
|||
return 4; |
|||
} |
|||
for(k=0;k<M;k++) |
|||
fread(vecteurs[k],sizeof(float),dimvec,ent); |
|||
fclose(ent); |
|||
return 0; |
|||
} |
|||
|
|||
int InitDictionnaire(void) |
|||
{ |
|||
int k; |
|||
if((vecteurs_classes=(float**)calloc(dico,sizeof(float *)))==NULL) |
|||
return 1; |
|||
for(k=0;k<dico;k++) |
|||
{ |
|||
if((vecteurs_classes[k]=(float*)calloc(dimvec,sizeof(float)))==NULL) |
|||
return 2; |
|||
} |
|||
if((vecteurs_final=(float**)calloc(dico,sizeof(float *)))==NULL) |
|||
return 3; |
|||
for(k=0;k<dico;k++) |
|||
{ |
|||
if((vecteurs_final[k]=(float*)calloc(dimvec,sizeof(float)))==NULL) |
|||
return 4; |
|||
} |
|||
if((index_final=(int*)calloc(M,sizeof(int)))==NULL) |
|||
return 5; |
|||
if((popul_final=(int*)calloc(dico,sizeof(int)))==NULL) |
|||
return 6; |
|||
if((index_classes=(int*)calloc(M,sizeof(int)))==NULL) |
|||
return 7; |
|||
if((popul_classes=(int*)calloc(dico,sizeof(int)))==NULL) |
|||
return 8; |
|||
return 0; |
|||
} |
|||
|
|||
int CalculDictionnaire(void) |
|||
{ |
|||
int n,k,p,index; |
|||
double energie_prec,distance,distancemin; |
|||
char fini; |
|||
for(k=0;k<dico;k++) |
|||
{ |
|||
index=(int)floor(((double)(M-1)*(double)(rand()))/(double)RAND_MAX); |
|||
for(n=0;n<dimvec;n++) |
|||
vecteurs_classes[k][n]=vecteurs[index][n]; |
|||
} |
|||
energie=0.0; |
|||
etape=0; |
|||
fini=0; |
|||
while(!fini) |
|||
{ |
|||
memset(popul_classes,0,dico*sizeof(int)); |
|||
energie_prec=energie; |
|||
energie=0.0; |
|||
for(k=0;k<M;k++) |
|||
{ |
|||
index=0; |
|||
distancemin=0.0; |
|||
for(n=0;n<dimvec;n++) |
|||
{ |
|||
distancemin+= |
|||
(vecteurs[k][n]-vecteurs_classes[0][n])* |
|||
(vecteurs[k][n]-vecteurs_classes[0][n]); |
|||
} |
|||
for(p=1;p<dico;p++) |
|||
{ |
|||
distance=0.0; |
|||
for(n=0;n<dimvec;n++) |
|||
{ |
|||
distance+= |
|||
(vecteurs[k][n]-vecteurs_classes[p][n])* |
|||
(vecteurs[k][n]-vecteurs_classes[p][n]); |
|||
} |
|||
if(distance<distancemin) |
|||
{ |
|||
distancemin=distance; |
|||
index=p; |
|||
} |
|||
} |
|||
index_classes[k]=index; |
|||
popul_classes[index]+=1; |
|||
energie+=distancemin; |
|||
} |
|||
for(p=0;p<dico;p++) |
|||
{ |
|||
if(popul_classes[p]) |
|||
{ |
|||
memset(vecteurs_classes[p],0,dimvec*sizeof(float)); |
|||
} |
|||
} |
|||
for(k=0;k<M;k++) |
|||
{ |
|||
index=index_classes[k]; |
|||
if(popul_classes[index]) |
|||
{ |
|||
for(n=0;n<dimvec;n++) |
|||
{ |
|||
vecteurs_classes[index][n]+=vecteurs[k][n]; |
|||
} |
|||
} |
|||
} |
|||
for(p=0;p<dico;p++) |
|||
{ |
|||
if(popul_classes[p]) |
|||
{ |
|||
for(n=0;n<dimvec;n++) |
|||
{ |
|||
vecteurs_classes[p][n]/=popul_classes[p]; |
|||
} |
|||
} |
|||
} |
|||
if(etape!=0) |
|||
{ |
|||
if(((energie_prec-energie)/energie)<SEUIL) |
|||
fini=1; |
|||
} |
|||
etape++; |
|||
} |
|||
return 0; |
|||
} |
|||
|
|||
int SauveClasses(void) |
|||
{ |
|||
int k; |
|||
if((sor=fopen(nomsor,"wb"))==NULL) |
|||
return 1; |
|||
fwrite(&dimvec,sizeof(int),1,sor); |
|||
fwrite(&dico,sizeof(int),1,sor); |
|||
for(k=0;k<dico;k++) |
|||
fwrite(vecteurs_final[k],sizeof(float),dimvec,sor); |
|||
fwrite(popul_final,sizeof(int),dico,sor); |
|||
fclose(sor); |
|||
return 0; |
|||
} |
|||
|
|||
int SauveCode(void) |
|||
{ |
|||
if((cod=fopen(nomcod,"wb"))==NULL) |
|||
return 1; |
|||
fwrite(index_final,sizeof(int),M,sor); |
|||
fclose(sor); |
|||
return 0; |
|||
} |
|||
@ -0,0 +1,6 @@ |
|||
void Erreur(char *,int); |
|||
int LireVecteurs(void); |
|||
int InitDictionnaire(void); |
|||
int CalculDictionnaire(void); |
|||
int SauveClasses(void); |
|||
int SauveCode(void); |
|||
@ -0,0 +1,10 @@ |
|||
#define NOM 50 |
|||
#define SEUIL 1e-5 |
|||
|
|||
typedef struct |
|||
{ |
|||
int index; |
|||
int popul; |
|||
float * vecteur; |
|||
} |
|||
TRI; |
|||
@ -0,0 +1,4 @@ |
|||
function [image]=data_set(i, n) |
|||
|
|||
|
|||
end |
|||
@ -0,0 +1,28 @@ |
|||
function [coeff,num]=descripteurfouriernorm(z,cmax) |
|||
cmin=-cmax; |
|||
z_moy=mean(z); |
|||
longc=length(z); |
|||
% on calcule les coefficients de Fourier |
|||
TC=fft(z-z_moy)/longc; |
|||
num=cmin:cmax; |
|||
% on sélectionne les coefficients entre cmin et cmax |
|||
coeff=zeros(cmax-cmin+1,1); |
|||
coeff(end-cmax:end)=TC(1:cmax+1); |
|||
coeff(1:-cmin)=TC(end+cmin+1:end); |
|||
|
|||
% on retourne la séquence si le parcours est dans le |
|||
% sens inverse du sens trigonométrique |
|||
if abs(coeff(num==-1))>abs(coeff(num==1)) |
|||
coeff=coeff(end:-1:1); |
|||
end |
|||
|
|||
% corrections de phase pour normaliser |
|||
% par rapport à la rotation et l'origine |
|||
% du signal z |
|||
Phi=angle(coeff(num==-1).*coeff(num==1))/2; |
|||
coeff=coeff*exp(-1i*Phi); |
|||
theta=angle(coeff(num==1)); |
|||
coeff=coeff.*exp(-1i*num'*theta); |
|||
|
|||
% correction pour normaliser la taille |
|||
coeff=coeff/abs(coeff(num==1)); |
|||
@ -0,0 +1,25 @@ |
|||
#define _CRT_SECURE_NO_DEPRECATE |
|||
|
|||
#include <stdio.h> |
|||
#include "constant.h" |
|||
|
|||
char noment[NOM]; |
|||
char nomsor[NOM]; |
|||
char nomcod[NOM]; |
|||
int dimvec,M,dico,numiter; |
|||
|
|||
FILE * ent,* sor,* cod; |
|||
|
|||
float ** vecteurs; |
|||
float ** vecteurs_classes; |
|||
int * index_classes; |
|||
int * popul_classes; |
|||
float ** vecteurs_final; |
|||
int * index_final; |
|||
int * popul_final; |
|||
int etape; |
|||
double energie; |
|||
double energieminimale; |
|||
|
|||
TRI * buftri; |
|||
|
|||
@ -0,0 +1,25 @@ |
|||
|
|||
|
|||
|
|||
|
|||
|
|||
extern char noment[NOM]; |
|||
extern char nomsor[NOM]; |
|||
extern char nomcod[NOM]; |
|||
extern int dimvec,M,dico,numiter; |
|||
|
|||
extern FILE * ent,* sor,* cod; |
|||
|
|||
extern float ** vecteurs; |
|||
extern float ** vecteurs_classes; |
|||
extern int * index_classes; |
|||
extern int * popul_classes; |
|||
extern float ** vecteurs_final; |
|||
extern int * index_final; |
|||
extern int * popul_final; |
|||
extern int etape; |
|||
extern double energie; |
|||
extern double energieminimale; |
|||
|
|||
extern TRI * buftri; |
|||
|
|||
@ -0,0 +1,41 @@ |
|||
% kmoyennes.m |
|||
% [vecteursliste,code,occur]=kmoyennes(vecteurs,dico,numiter) |
|||
% vecteurs : vecteurs de la base (rangés en colonnes) |
|||
% dico : nombre de classes |
|||
% numiter : nombre d'essais pour trouver le dictionnaire |
|||
% vecteursliste : contient les vecteurs prototypes |
|||
% code : contient les index des classes |
|||
% occur : nombre d'éléments dans chaque classe |
|||
|
|||
function [vecteursliste,code,occur]=kmoyennes(vecteurs,dico,numiter) |
|||
|
|||
% nombre de lignes du tableau vecteurs : dimension des vecteurs |
|||
dimvec=size(vecteurs,1); |
|||
% nombre de colonnes du tableau vecteurs : nombre de vecteurs |
|||
M=size(vecteurs,2); |
|||
|
|||
% ecriture des fichiers nécessaires au fonctionnment du programme quantvec |
|||
fid=fopen('vecteurs','w'); |
|||
fwrite(fid,M,'int'); |
|||
fwrite(fid,dimvec,'int'); |
|||
fwrite(fid,dico,'int'); |
|||
fwrite(fid,numiter,'int'); |
|||
fwrite(fid,vecteurs,'float'); |
|||
fclose(fid); |
|||
|
|||
% lancement du programme quantvec |
|||
unix('./quantvec vecteurs dict code'); |
|||
|
|||
% lecture des fichiers résultat |
|||
fid=fopen('dict','r'); |
|||
dimvec=fread(fid,1,'int'); |
|||
dico=fread(fid,1,'int'); |
|||
vecteursliste=fread(fid,[dimvec dico],'float'); |
|||
occur=fread(fid,dico,'int'); |
|||
fclose(fid); |
|||
disp('vecteurs dans la liste') |
|||
disp([dimvec dico]) |
|||
|
|||
fid=fopen('code','r'); |
|||
code=fread(fid,M,'int'); |
|||
fclose(fid); |
|||
@ -0,0 +1,92 @@ |
|||
close all |
|||
|
|||
%acceptable threshold values: 15-30 |
|||
threshold = 20; |
|||
cmax = 10; |
|||
cmin = -cmax; |
|||
n_classes = 16; |
|||
iterations = 50; |
|||
N = 200; |
|||
|
|||
dataset = dir('../images/*/*.jpg'); |
|||
dataset_size = length(dataset); |
|||
|
|||
vecteurs=zeros(2*(cmax-cmin+1),dataset_size); %TODO: renommer en vectors |
|||
|
|||
classes = []; %colonne [avance; arret; gauche; droite; rejet] |
|||
|
|||
% c'est lent |
|||
% s'assurer que l'on choisit toutes les images |
|||
% |
|||
n=1; |
|||
while n<dataset_size+1 |
|||
% choix d'une image aleatoire |
|||
choix = 1 + floor(dataset_size*rand(dataset_size, 1)); |
|||
% extraction de l'image du dataset |
|||
image = dataset(choix(1)); |
|||
% lecture de l'image |
|||
img = imread([image.folder '/' image.name]); |
|||
% filtrage de la couleur de la peau |
|||
binary = rgb_filter(img, threshold); |
|||
% determination du contour |
|||
c = contourc(binary); |
|||
if size(c,2)~=0 |
|||
|
|||
% Determination du contour de taille max |
|||
cont = max_contour(c); |
|||
% transformation en signal complexe |
|||
z = cont(:,1) + 1i*cont(:,2); |
|||
if length(z)>11 |
|||
|
|||
% calcul des descripteurs de Fourier |
|||
[coeff,ncoeff]=descripteurfouriernorm(z,cmax); |
|||
% Extraction des composantes |
|||
vecteurs(:,n)=[real(coeff);imag(coeff)]; |
|||
% Ajout de la classe correspondante |
|||
deb = dataset(choix(1)).name(1:2); |
|||
if deb == 'av' |
|||
classes = [classes , [1;0;0;0;0]]; |
|||
elseif deb == 'ar' |
|||
classes = [classes , [0;1;0;0;0]]; |
|||
elseif deb == 'ga' |
|||
classes = [classes , [0;0;1;0;0]]; |
|||
elseif deb == 'dr' |
|||
classes = [classes , [0;0;0;1;0]]; |
|||
else |
|||
classes = [classes , [0;0;0;0;1]]; |
|||
end |
|||
|
|||
|
|||
% affichage de l'avancement |
|||
disp(n/dataset_size); |
|||
n = n+1; |
|||
end |
|||
end |
|||
|
|||
end |
|||
|
|||
% utilisation de l'algorithme des kmeans |
|||
kmeans = kmoyennes(vecteurs, n_classes, iterations); |
|||
|
|||
% affichage des prototypes |
|||
figure |
|||
for n=1:n_classes |
|||
contfil=resconstrdesfour(kmeans(1:end/2,n)+1i*kmeans(end/2+1:end,n),N,cmax); |
|||
subplot(4,4,n) |
|||
h=plot(real(contfil),imag(contfil),'-',real(contfil(1)),imag(contfil(1)),'o'); |
|||
title(['prototype ' int2str(n)]) |
|||
set(h(1),'LineWidth',2) |
|||
set(h(2),'LineWidth',3) |
|||
grid on |
|||
axis equal |
|||
axis ij |
|||
drawnow |
|||
end |
|||
|
|||
% utilisation de l'algorithme du perceptron multicouches |
|||
|
|||
[net, resultats_test] = PMC_training(vecteurs, classes, 10, 1100); |
|||
|
|||
%faire une prediction : y = net(x) |
|||
|
|||
|
|||
@ -0,0 +1,8 @@ |
|||
all : quantvec |
|||
|
|||
quantvec : *.c *.h |
|||
g++ -O3 -Wall *.c -o quantvec |
|||
|
|||
clean : |
|||
rm quantvec |
|||
|
|||
@ -0,0 +1,18 @@ |
|||
function [cont]=max_contour(contours) |
|||
i=1; |
|||
id=1; |
|||
max = 0; |
|||
while i+contours(2, id) < size(contours, 2) |
|||
contours(2,i); |
|||
if contours(2,i) > max |
|||
max = contours(2,i); |
|||
id = i; |
|||
end |
|||
i=i+1+contours(2,i); |
|||
end |
|||
|
|||
cont = zeros(max, 2); |
|||
cont(1:end,1) = contours(1, id+1:id+max); |
|||
cont(1:end,2) = contours(2, id+1:id+max); |
|||
|
|||
end |
|||
@ -0,0 +1,63 @@ |
|||
#define _CRT_SECURE_NO_DEPRECATE |
|||
|
|||
#include <stdio.h> |
|||
#include <stdlib.h> |
|||
#include <time.h> |
|||
#include <string.h> |
|||
#include <malloc.h> |
|||
#include <math.h> |
|||
#include "constant.h" |
|||
#include "global.h" |
|||
#include "algo.h" |
|||
|
|||
int main(int ac,char ** av) |
|||
{ |
|||
int erreur,iter,p; |
|||
if(ac != 4) |
|||
Erreur((char*)"Il faut 3 parametres",1); |
|||
strncpy(noment,av[1],NOM-1); |
|||
strncpy(nomsor,av[2],NOM-1); |
|||
strncpy(nomcod,av[3],NOM-1); |
|||
|
|||
srand( (unsigned)time( NULL ) ); |
|||
|
|||
if((erreur=LireVecteurs())!=0) |
|||
Erreur((char*)"Erreur de lecture des vecteurs",erreur); |
|||
fprintf(stderr,"nombre de vecteurs : %d\n",M); |
|||
fprintf(stderr,"dimension des vecteurs : %d\n",dimvec); |
|||
fprintf(stderr,"taille du dictionnaire : %d\n",dico); |
|||
fprintf(stderr,"nombre d'iterations : %d\n",numiter); |
|||
if((erreur=InitDictionnaire())!=0) |
|||
Erreur((char*)"Erreur d'initialisation du dictionnaire",erreur); |
|||
|
|||
iter=0; |
|||
if((erreur=CalculDictionnaire())!=0) |
|||
Erreur((char*)"Erreur de calcul itératif du dictionnaire",erreur); |
|||
energieminimale=energie; |
|||
memcpy(index_final,index_classes,M*sizeof(int)); |
|||
memcpy(popul_final,popul_classes,dico*sizeof(int)); |
|||
for(p=0;p<dico;p++) |
|||
memcpy(vecteurs_final[p],vecteurs_classes[p],dimvec*sizeof(float)); |
|||
fprintf(stderr,"iteration %d, distorsion %lf en %d etapes\n",iter,energie/((double)M*(double)dimvec),etape); |
|||
|
|||
for(iter=1;iter<numiter;iter++) |
|||
{ |
|||
if((erreur=CalculDictionnaire())!=0) |
|||
Erreur((char*)"Erreur de calcul itératif du dictionnaire",erreur); |
|||
if(energie<energieminimale) |
|||
{ |
|||
energieminimale=energie; |
|||
memcpy(index_final,index_classes,M*sizeof(int)); |
|||
memcpy(popul_final,popul_classes,dico*sizeof(int)); |
|||
for(p=0;p<dico;p++) |
|||
memcpy(vecteurs_final[p],vecteurs_classes[p],dimvec*sizeof(float)); |
|||
} |
|||
fprintf(stderr,"iteration %d, distorsion %lf en %d etapes\n",iter,energie/((double)M*(double)dimvec),etape); |
|||
} |
|||
|
|||
fprintf(stderr,"distorsion finale %lf\n",energieminimale/((double)M*(double)dimvec)); |
|||
if((erreur=SauveClasses())!=0) |
|||
Erreur((char*)"Erreur de sauvegarde des classes",erreur); |
|||
if((erreur=SauveCode())!=0) |
|||
Erreur((char*)"Erreur de sauvegarde du code",erreur); |
|||
} |
|||
@ -0,0 +1,11 @@ |
|||
function z_fil=resconstrdesfour(coeff,N,cmax) |
|||
|
|||
cmin=-cmax; |
|||
TC=zeros(N,1); |
|||
|
|||
TC(1:cmax+1)=coeff(end-cmax:end); |
|||
TC(end+cmin+1:end)=coeff(1:-cmin); |
|||
|
|||
z_fil=ifft(TC)*N; |
|||
|
|||
z_fil=[z_fil;z_fil(1)]; |
|||
@ -0,0 +1,23 @@ |
|||
function [filtered_img]=rgb_filter(img, threshold) |
|||
height = size(img, 1); |
|||
width = size(img, 2); |
|||
depth = size(img, 3); |
|||
|
|||
filtered_img = zeros(height, width, 1); |
|||
|
|||
for i=1:height |
|||
for j=1:width |
|||
r = img(i, j, 1); |
|||
g = img(i, j, 2); |
|||
b = img(i, j, 3); |
|||
if (r > g && r > b) |
|||
if (r-b > threshold || r-g > threshold) |
|||
filtered_img(i, j, 1) = 1; |
|||
else |
|||
filtered_img(i, j, 1) = 0; |
|||
end |
|||
end |
|||
end |
|||
end |
|||
|
|||
end |
|||
@ -0,0 +1,3 @@ |
|||
int InitInfo(void); |
|||
void TraiteErreur(int,char*); |
|||
DWORD WINAPI Traitement(LPVOID); |
|||
|
After Width: | Height: | Size: 11 KiB |
|
After Width: | Height: | Size: 15 KiB |
|
After Width: | Height: | Size: 15 KiB |
|
After Width: | Height: | Size: 14 KiB |
|
After Width: | Height: | Size: 9.9 KiB |
|
After Width: | Height: | Size: 6.7 KiB |
|
After Width: | Height: | Size: 6.1 KiB |
|
After Width: | Height: | Size: 5.5 KiB |
|
After Width: | Height: | Size: 5.2 KiB |
|
After Width: | Height: | Size: 5.1 KiB |
|
After Width: | Height: | Size: 4.9 KiB |
|
After Width: | Height: | Size: 4.9 KiB |
|
After Width: | Height: | Size: 4.9 KiB |
|
After Width: | Height: | Size: 4.9 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.9 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.9 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.6 KiB |
|
After Width: | Height: | Size: 4.6 KiB |
|
After Width: | Height: | Size: 4.6 KiB |
|
After Width: | Height: | Size: 4.6 KiB |
|
After Width: | Height: | Size: 4.6 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.6 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.6 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.7 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.9 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.8 KiB |
|
After Width: | Height: | Size: 4.9 KiB |
|
After Width: | Height: | Size: 4.9 KiB |
|
After Width: | Height: | Size: 4.9 KiB |