add new message type BoundingBox

This commit is contained in:
samilyjcc 2016-06-14 12:53:22 +02:00
parent 0e85119c64
commit bdaba2e13c
4 changed files with 18 additions and 3 deletions

View file

@ -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)

4
msg/BoundingBox.msg Normal file
View file

@ -0,0 +1,4 @@
float64 x
float64 y
float64 width
float64 height

View file

@ -45,10 +45,12 @@
<build_depend>std_msgs</build_depend>
<build_depend>image_transport</build_depend>
<build_depend>cv_bridge</build_depend>
<build_depend>message_generation</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>image_transport</run_depend>
<run_depend>cv_bridge</run_depend>
<run_depend>message_runtime</run_depend>

View file

@ -2,7 +2,7 @@
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <geometry_msgs/Twist.h>
#include <papillon/BoundingBox.h>
#include <opencv/cv.h>
@ -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<geometry_msgs::Twist>("/vrep/drone/cmd_vel", 1);
pub_cmd = n.advertise<papillon::BoundingBox>("/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"));
}