diff --git a/ROS/gesture_based_control/CMakeLists.txt b/ROS/gesture_based_control/CMakeLists.txt
index 7b4e5ce..c77ce27 100644
--- a/ROS/gesture_based_control/CMakeLists.txt
+++ b/ROS/gesture_based_control/CMakeLists.txt
@@ -7,6 +7,8 @@ find_package(catkin REQUIRED COMPONENTS
geometry_msgs
roscpp
std_msgs
+ cv_bridge
+ image_transport
)
catkin_package()
@@ -17,3 +19,6 @@ include_directories(
add_executable(controller src/controller.cpp)
target_link_libraries(controller ${catkin_LIBRARIES})
+
+add_executable(descripteur src/descripteur.cpp)
+target_link_libraries(descripteur ${catkin_LIBRARIES})
diff --git a/ROS/gesture_based_control/launch/gesture_control.launch b/ROS/gesture_based_control/launch/gesture_control.launch
index 316aa9a..53a1e39 100644
--- a/ROS/gesture_based_control/launch/gesture_control.launch
+++ b/ROS/gesture_based_control/launch/gesture_control.launch
@@ -7,4 +7,7 @@
+
+
+
diff --git a/ROS/gesture_based_control/src/descripteur.cpp b/ROS/gesture_based_control/src/descripteur.cpp
new file mode 100644
index 0000000..b50f715
--- /dev/null
+++ b/ROS/gesture_based_control/src/descripteur.cpp
@@ -0,0 +1,30 @@
+#include
+#include
+#include
+#include
+//#include
+
+void callback(const sensor_msgs::ImageConstPtr& msg) {
+ cv_bridge::CvImagePtr cv_ptr;
+
+ 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;
+ }
+
+ const cv::Mat& input = cv_ptr->image;
+
+}
+
+int main(int argc, char** argv) {
+ ros::init(argc, argv, "descripteur");
+
+ ros::NodeHandle n;
+ image_transport::ImageTransport it(n);
+
+ image_transport::Subscriber sub = it.subscribe("/image_raw", 1, callback);
+
+ ros::spin();
+}