From 5cc52385266cc541800d704f011f2aa90f0de177 Mon Sep 17 00:00:00 2001 From: Paul Janin Date: Wed, 6 May 2015 16:03:29 +0200 Subject: [PATCH] filtreRGB works --- CMakeLists.txt | 3 +++ src/filtreRGB.cpp | 41 ++++++++++++++++++++++++----------------- 2 files changed, 27 insertions(+), 17 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c8c9ac3..a5f9ae7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -50,6 +50,9 @@ add_library(display src/display.cpp) add_executable(keyboard_cmd src/keyboard_cmd.cpp) target_link_libraries(keyboard_cmd display ${catkin_LIBRARIES} ${ncursesw_LIBRARIES}) +add_executable(filtreRGB src/filtreRGB.cpp) +target_link_libraries(filtreRGB ${catkin_LIBRARIES}) + add_executable(normal_estimator src/normal_estimator.cpp) target_link_libraries(normal_estimator ${catkin_LIBRARIES}) add_dependencies(normal_estimator hand_control_generate_messages_cpp) diff --git a/src/filtreRGB.cpp b/src/filtreRGB.cpp index 2094c5a..ee1420a 100644 --- a/src/filtreRGB.cpp +++ b/src/filtreRGB.cpp @@ -59,46 +59,53 @@ main(int argc, char** argv) uint8_t delta(0); - if (node.getParam("red", red)) + int redInt; + int greenInt; + int blueInt; + + int deltaInt; + + if (node.getParam("red", redInt)) { - ROS_INFO("red : %f" , red); + ROS_INFO("red : %d" , redInt); } else { node.setParam("red", 0); - node.getParam("red", red); - ROS_INFO("red : %f (default value)", red); + node.getParam("red", redInt); + ROS_INFO("red : %d (default value)", redInt); } - if (node.getParam("blue", blue)) + if (node.getParam("blue", blueInt)) { - ROS_INFO("blue : %f" , blue); + ROS_INFO("blue : %d" , blueInt); } else { node.setParam("blue", 0); - node.getParam("blue", blue); - ROS_INFO("blue : %f (default value)", blue); + node.getParam("blue", blueInt); + ROS_INFO("blue : %d (default value)", blueInt); } - if (node.getParam("green", green)) + if (node.getParam("green", greenInt)) { - ROS_INFO("green : %f" , green); + ROS_INFO("green : %d" , greenInt); } else { node.setParam("green", 0); - node.getParam("green", green); - ROS_INFO("green : %f (default value)", green); + node.getParam("green", greenInt); + ROS_INFO("green : %d (default value)", greenInt); } - if (node.getParam("delta", delta)) + if (node.getParam("delta", deltaInt)) { - ROS_INFO("delta : %f" , delta); + ROS_INFO("delta : %d" , deltaInt); } else { node.setParam("delta", 0); - node.getParam("delta", delta); - ROS_INFO("delta : %f (default value)", delta); + node.getParam("delta", deltaInt); + ROS_INFO("delta : %d (default value)", deltaInt); } + // initialisatio ros::Publisher publisher = node.advertise("output", 1); - Callback callback(publisher, (uint8_t) red, (uint8_t) green, (uint8_t) blue, (uint8_t) delta); + Callback callback(publisher, (uint8_t) redInt, (uint8_t) greenInt, (uint8_t) blueInt, (uint8_t) deltaInt); ros::Subscriber subscriber = node.subscribe("input", 1, callback); // démarrage