ajout du noeud qui calculera les descripteurs de Fourrier
This commit is contained in:
parent
1d8ada838d
commit
14320925be
3 changed files with 38 additions and 0 deletions
|
@ -7,6 +7,8 @@ find_package(catkin REQUIRED COMPONENTS
|
||||||
geometry_msgs
|
geometry_msgs
|
||||||
roscpp
|
roscpp
|
||||||
std_msgs
|
std_msgs
|
||||||
|
cv_bridge
|
||||||
|
image_transport
|
||||||
)
|
)
|
||||||
|
|
||||||
catkin_package()
|
catkin_package()
|
||||||
|
@ -17,3 +19,6 @@ include_directories(
|
||||||
|
|
||||||
add_executable(controller src/controller.cpp)
|
add_executable(controller src/controller.cpp)
|
||||||
target_link_libraries(controller ${catkin_LIBRARIES})
|
target_link_libraries(controller ${catkin_LIBRARIES})
|
||||||
|
|
||||||
|
add_executable(descripteur src/descripteur.cpp)
|
||||||
|
target_link_libraries(descripteur ${catkin_LIBRARIES})
|
||||||
|
|
|
@ -7,4 +7,7 @@
|
||||||
<remap from="/cmd_vel" to="/turtle1/cmd_vel"/>
|
<remap from="/cmd_vel" to="/turtle1/cmd_vel"/>
|
||||||
</node>
|
</node>
|
||||||
<node name="turtle" pkg="turtlesim" type="turtlesim_node"/>
|
<node name="turtle" pkg="turtlesim" type="turtlesim_node"/>
|
||||||
|
<node name="descripteur" pkg="gesture_based_control" type="descripteur" output="screen">
|
||||||
|
<remap from="/image_raw" to="/usb_cam/image_raw"/>
|
||||||
|
</node>
|
||||||
</launch>
|
</launch>
|
||||||
|
|
30
ROS/gesture_based_control/src/descripteur.cpp
Normal file
30
ROS/gesture_based_control/src/descripteur.cpp
Normal file
|
@ -0,0 +1,30 @@
|
||||||
|
#include <ros/ros.h>
|
||||||
|
#include <opencv2/opencv.hpp>
|
||||||
|
#include <image_transport/image_transport.h>
|
||||||
|
#include <cv_bridge/cv_bridge.h>
|
||||||
|
//#include <math.hpp>
|
||||||
|
|
||||||
|
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();
|
||||||
|
}
|
Loading…
Reference in a new issue