merged with lukas

This commit is contained in:
Pavel Lutskov
2019-01-28 15:04:29 +01:00
9 changed files with 2080 additions and 25 deletions

View File

@@ -11,7 +11,6 @@
#include <opencv2/video/tracking.hpp>
#include <aruco/aruco.h>
// static const std::string OPENCV_WINDOW = "Original image";
static const std::string ARUCO_WINDOW = "Aruco window";
class ImageConverter {
@@ -31,13 +30,11 @@ class ImageConverter {
&ImageConverter::imageCb, this);
// Create output windows
// cv::namedWindow(OPENCV_WINDOW);
cv::namedWindow(ARUCO_WINDOW);
}
~ImageConverter() {
// Clean Up
// cv::destroyWindow(OPENCV_WINDOW);
cv::destroyWindow(ARUCO_WINDOW);
}
@@ -55,9 +52,6 @@ class ImageConverter {
return;
}
// Output Original Image (bcs y not)
// cv::imshow(OPENCV_WINDOW, cv_ptr->image);
// Do Aruco
cv::Mat cam_mat = (cv::Mat_<double>(3, 3) <<
690., 0.0, 320,

View File

@@ -182,8 +182,9 @@ public:
void commandRecognition()
{
//recognition has to be started and ended once a valid command was found
initializeVocabulary();
this->initializeVocabulary();
ros::Rate loop_rate(1);
loop_rate.sleep();
std_srvs::Empty srv;
if (recog_start_srv.call(srv)) {
@@ -199,7 +200,8 @@ int main(int argc, char** argv) {
ros::init(argc, argv, "speech");
Nao_control TermiNAOtor;
ros::Rate loop_rate(0.5);
//TermiNAOtor.initializeVocabulary();
ros::Rate loop_rate(1);
loop_rate.sleep();
TermiNAOtor.commandRecognition();
ROS_INFO("SPIN");