diff --git a/CMakeLists.txt b/CMakeLists.txt
index 9ed17ae..33f993b 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -6,16 +6,25 @@ find_package(catkin REQUIRED COMPONENTS
std_msgs
image_transport
cv_bridge
+ message_generation
)
find_package(OpenCV)
+add_message_files(
+ FILES
+ BoundingBox.msg
+)
+
+generate_messages()
catkin_package(CATKIN_DEPENDS
roscpp
std_msgs
image_transport
cv_bridge
+ message_runtime
)
+
include_directories (${catkin_INCLUDE_DIRS})
add_executable (papillon src/papillon.cpp)
diff --git a/msg/BoundingBox.msg b/msg/BoundingBox.msg
new file mode 100644
index 0000000..27213ee
--- /dev/null
+++ b/msg/BoundingBox.msg
@@ -0,0 +1,4 @@
+float64 x
+float64 y
+float64 width
+float64 height
diff --git a/package.xml b/package.xml
index 7ecb2ec..7e113fa 100644
--- a/package.xml
+++ b/package.xml
@@ -45,10 +45,12 @@
std_msgs
image_transport
cv_bridge
+ message_generation
roscpp
std_msgs
image_transport
cv_bridge
+ message_runtime
diff --git a/src/papillon.cpp b/src/papillon.cpp
index 653558f..acc8fb9 100644
--- a/src/papillon.cpp
+++ b/src/papillon.cpp
@@ -2,7 +2,7 @@
#include
#include
#include
-#include
+#include
#include
@@ -19,7 +19,7 @@ class Traite_image {
cv::Mat prev;
cv::Mat last_T;
bool first = true;
- int resize_f = 2;
+ int resize_f = 1;
int theObject[2] = {0,0};
cv::Rect objectBoundingRectangle = cv::Rect(0,0,0,0);
@@ -34,7 +34,7 @@ class Traite_image {
Traite_image() : n("~"),it(n) {
pub_img = it.advertise("/image_out", 1);
- pub_cmd = n.advertise("/vrep/drone/cmd_vel", 1);
+ pub_cmd = n.advertise("/bbox", 1);
sub = it.subscribe("/usb_cam/image_raw", 1, [this](const sensor_msgs::ImageConstPtr& img) -> void { this->on_image(img);},ros::VoidPtr(),image_transport::TransportHints("compressed"));
}