Merge branch 'dev' of gitlab.rezometz.org:guillaume/miniprojet into dev
This commit is contained in:
commit
a5cac585c0
7 changed files with 102 additions and 74 deletions
|
@ -3,15 +3,15 @@
|
|||
#include <geometry_msgs/Twist.h>
|
||||
|
||||
void callback(const std_msgs::String& msg, geometry_msgs::Twist& cmd) {
|
||||
if (msg.data == "forward") {
|
||||
if (msg.data == "avance") {
|
||||
cmd.linear.x = 1.0;
|
||||
cmd.angular.z = 0.0;
|
||||
} else if (msg.data == "stop") {
|
||||
} else if (msg.data == "arret") {
|
||||
cmd = geometry_msgs::Twist();
|
||||
} else if (msg.data == "left") {
|
||||
} else if (msg.data == "gauche") {
|
||||
cmd.angular.z = 1.0;
|
||||
cmd.linear.x = 0.0;
|
||||
} else if (msg.data == "right") {
|
||||
} else if (msg.data == "droite") {
|
||||
cmd.angular.z = -1.0;
|
||||
cmd.linear.x = 0.0;
|
||||
}
|
||||
|
|
|
@ -7,13 +7,14 @@
|
|||
|
||||
#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) {
|
||||
cmax = config.cmax;
|
||||
threshold = config.threshold;
|
||||
}
|
||||
|
||||
void callback(const sensor_msgs::ImageConstPtr& msg, int& threshold, int& cmax, ros::Publisher& order_pub, image_transport::Publisher& image_pub) {
|
||||
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;
|
||||
|
||||
|
@ -35,26 +36,7 @@ void callback(const sensor_msgs::ImageConstPtr& msg, int& threshold, int& cmax,
|
|||
if (contours.size() != 0) {
|
||||
int index = math::max_cont(contours);
|
||||
math::csignal desc = math::descriptors(contours[index], cmax);
|
||||
//TODO: implémenter algo ml
|
||||
//TODO: publier résultat
|
||||
int r = 0;
|
||||
switch (r) {
|
||||
case 0:
|
||||
s.data = "left";
|
||||
break;
|
||||
case 1:
|
||||
s.data = "right";
|
||||
break;
|
||||
case 2:
|
||||
s.data = "stop";
|
||||
break;
|
||||
case 3:
|
||||
s.data = "forward";
|
||||
break;
|
||||
default:
|
||||
s.data = "None";
|
||||
break;
|
||||
}
|
||||
s.data = predict(desc, dataset, 5, 2);
|
||||
order_pub.publish(s);
|
||||
|
||||
cv::drawContours(input, contours, index, 255);
|
||||
|
@ -68,12 +50,14 @@ int main(int argc, char** argv) {
|
|||
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)));
|
||||
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;
|
||||
|
|
33
tests/examples/test-knn.cpp
Normal file
33
tests/examples/test-knn.cpp
Normal file
|
@ -0,0 +1,33 @@
|
|||
#include <iostream>
|
||||
#include <math.hpp>
|
||||
#include <file.hpp>
|
||||
#include <knn.hpp>
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
int k = 20;
|
||||
std::string filename;
|
||||
std::string sample_name;
|
||||
int cmax = 10;
|
||||
int threshold = 20;
|
||||
int n = 2;
|
||||
|
||||
if (argc > 3) {
|
||||
filename = argv[1];
|
||||
k = atoi(argv[2]);
|
||||
sample_name = argv[3];
|
||||
} else {
|
||||
std::cout << "Invalid number of arguments" << std::endl;
|
||||
return 0;
|
||||
}
|
||||
|
||||
math::dataset references = load_csv(filename, 2*cmax+1);
|
||||
|
||||
if (references.size() == 0) {
|
||||
std::cout << "Invalid file" << std::endl;
|
||||
return 0;
|
||||
}
|
||||
|
||||
sample_name = random_image(sample_name);
|
||||
math::csignal sample = math::img2desc(sample_name, cmax, threshold);
|
||||
std::cout << predict(sample, references, k, n) << std::endl;
|
||||
};
|
|
@ -1,8 +1,8 @@
|
|||
add_executable(traitement traitement.cpp)
|
||||
target_link_libraries(traitement ${OpenCV_LIBS})
|
||||
|
||||
add_executable(knn knn.cpp)
|
||||
target_link_libraries(knn ${OpenCV_LIBS} ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY})
|
||||
add_executable(save-dataset save-dataset.cpp)
|
||||
target_link_libraries(save-dataset ${OpenCV_LIBS} ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY})
|
||||
|
||||
add_executable(neural_network neural_network.cpp)
|
||||
target_link_libraries(neural_network ${OpenCV_LIBS} ${Boost_FILESYSTEM_LIBRARY} ${Boost_SYSTEM_LIBRARY})
|
||||
|
|
|
@ -1,4 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <boost/filesystem.hpp>
|
||||
#include <random>
|
||||
#include <iostream>
|
||||
#include <string>
|
||||
#include "math.hpp"
|
||||
|
@ -18,15 +21,9 @@ void read_directory(const std::string& name, std::vector<std::string>& v) {
|
|||
}
|
||||
|
||||
void save_as_csv(const math::dataset& dataset, std::string filename) {
|
||||
// file pointer
|
||||
std::fstream fout;
|
||||
|
||||
// opens an existing csv file or creates a new file.
|
||||
fout.open(filename, std::ios::out);
|
||||
|
||||
std::string name;
|
||||
|
||||
// Insert the data to file
|
||||
for (auto p: dataset) {
|
||||
for (auto x: p.first) {
|
||||
fout << x.real() << ','
|
||||
|
@ -37,6 +34,24 @@ void save_as_csv(const math::dataset& dataset, std::string filename) {
|
|||
}
|
||||
}
|
||||
|
||||
std::string random_image(const std::string& path) {
|
||||
std::random_device rd;
|
||||
std::mt19937 gen(rd());
|
||||
std::uniform_int_distribution<> uniform(0, 4);
|
||||
|
||||
|
||||
std::vector<std::string> dirs;
|
||||
read_directory(path, dirs);
|
||||
int rd_dir = uniform(gen);
|
||||
std::vector<std::string> images;
|
||||
read_directory(path+"/"+dirs[rd_dir], images);
|
||||
|
||||
std::uniform_int_distribution<> uniform2(0, images.size());
|
||||
int rd_image = uniform2(gen);
|
||||
std::cout << images[rd_image] << std::endl;
|
||||
return path+"/"+dirs[rd_dir]+"/"+images[rd_image];
|
||||
}
|
||||
|
||||
math::dataset& load_csv(std::string filename, int size) {
|
||||
math::dataset* d = new math::dataset();
|
||||
std::fstream fin;
|
||||
|
|
|
@ -1,17 +1,19 @@
|
|||
#include <map>
|
||||
#include "file.hpp"
|
||||
#include "math.hpp"
|
||||
#pragma once
|
||||
|
||||
#include <stdexcept>
|
||||
#include <queue>
|
||||
#include <opencv2/opencv.hpp>
|
||||
#include <iostream>
|
||||
#include <map>
|
||||
|
||||
double distance(math::csignal& v1, math::csignal& v2, int n){
|
||||
#include "file.hpp"
|
||||
#include "math.hpp"
|
||||
|
||||
double distance(const math::csignal& v1, const math::csignal& v2, int n){
|
||||
if (v1.size() != v2.size()) {
|
||||
throw std::runtime_error("les deux vecteurs doivent être de même longueur");
|
||||
}
|
||||
double d = 0;
|
||||
|
||||
auto v1_it = v1.begin();
|
||||
auto v2_it = v2.begin();
|
||||
|
||||
|
@ -19,19 +21,7 @@ double distance(math::csignal& v1, math::csignal& v2, int n){
|
|||
double dist = std::abs(*(v1_it++) - *(v2_it++));
|
||||
d += std::pow(dist, n);
|
||||
}
|
||||
return std::pow(d, 1/n);
|
||||
};
|
||||
|
||||
int argmax(std::vector<int>& v){
|
||||
int arg = 0;
|
||||
int max = v[0];
|
||||
for(int i = 1; i < v.size() ; ++i){
|
||||
if (v[i]>max){
|
||||
arg = i;
|
||||
max = v[i];
|
||||
};
|
||||
};
|
||||
return arg;
|
||||
return std::pow(d, 1/float(n));
|
||||
};
|
||||
|
||||
struct pair_comp {
|
||||
|
@ -46,29 +36,12 @@ struct pair_comp {
|
|||
};
|
||||
};
|
||||
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
int k = 20;
|
||||
int size = 100;
|
||||
std::string path;
|
||||
int cmax = 10;
|
||||
int threshold = 20;
|
||||
|
||||
if (argc > 2) {
|
||||
path = argv[1];
|
||||
threshold = atoi(argv[2]);
|
||||
} else {
|
||||
std::cout << "Invalid number of arguments" << std::endl;
|
||||
return 0;
|
||||
}
|
||||
|
||||
math::dataset references = get_data(path, size, cmax, threshold);
|
||||
math::csignal sample = math::img2desc(path+"/arret/arret0199.jpg", cmax, threshold);
|
||||
std::string predict(const math::csignal& sample, const math::dataset& references, int k, int n) {
|
||||
std::priority_queue<std::pair<double, std::string>, std::vector<std::pair<double, std::string>>, pair_comp> neighbors;
|
||||
std::map<std::string, int> labels;
|
||||
|
||||
for (auto desc: references) {
|
||||
double d = distance(desc.first, sample, 1);
|
||||
double d = distance(desc.first, sample, n);
|
||||
neighbors.push({d, desc.second});
|
||||
}
|
||||
|
||||
|
@ -88,5 +61,5 @@ int main(int argc, char** argv) {
|
|||
}
|
||||
}
|
||||
|
||||
std::cout << label << std::endl;
|
||||
};
|
||||
return label;
|
||||
}
|
23
tests/src/save-dataset.cpp
Normal file
23
tests/src/save-dataset.cpp
Normal file
|
@ -0,0 +1,23 @@
|
|||
#include "file.hpp"
|
||||
#include "math.hpp"
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
std::string path;
|
||||
int cmax;
|
||||
int threshold;
|
||||
int size;
|
||||
|
||||
if (argc > 4) {
|
||||
path = argv[1];
|
||||
cmax = atoi(argv[2]);
|
||||
threshold = atoi(argv[3]);
|
||||
size = atoi(argv[4]);
|
||||
} else {
|
||||
std::cout << "Invalid number of arguments" << std::endl;
|
||||
return 0;
|
||||
}
|
||||
|
||||
math::dataset dataset = get_data(path, size, cmax, threshold);
|
||||
save_as_csv(dataset, path+"/../descripteurs/dataset"+std::to_string(size)+".csv");
|
||||
return 0;
|
||||
}
|
Loading…
Reference in a new issue