Main.cpp
Go to the documentation of this file.
00001 #include <FaceFind.h>
00002 #include <Qtcv.h>
00003 
00004 // callback queue
00005 #include <ros/callback_queue.h>
00006 
00007 // Qt
00008 #include <QApplication>
00009 
00010 // image transport
00011 #include <image_transport/image_transport.h>
00012 #include <compressed_image_transport/compressed_subscriber.h>
00013 
00014 // laser scanner
00015 #include <pr2_msgs/SetPeriodicCmd.h>
00016 
00023 int main(int argc, char** argv)
00024 {
00025         //** Qt application (must be first line!) */
00026         QApplication application(argc, argv);
00027         
00028         //** own face finder class */
00029         FaceFind faceFind;
00030         
00031         //** start ros */
00032         ros::init(argc, argv, "facefinder");
00033         ros::NodeHandle n;
00034         ros::CallbackQueue cq;
00035         n.setCallbackQueue(&cq);
00036         
00037         //** image transport helper */
00038         image_transport::ImageTransport it(n);
00039         
00040         //** subscribe to stereo camera */
00041         image_transport::Subscriber image = it.subscribe("/wide_stereo/left/image_rect_color", 20,
00042                         &FaceFind::ImageCBAll, &faceFind, image_transport::TransportHints("compressed"));
00043         
00044         //** subscribe to prosilica camera */
00045         image_transport::Subscriber prosilica  = it.subscribe("/prosilica/image_color", 5,
00046                         &FaceFind::ProsilicaCBAll, &faceFind, image_transport::TransportHints("compressed"));
00047         
00048         //** subscribe to face detector */
00049         ros::Subscriber face_positions = n.subscribe("face_detector/people_tracker_measurements", 20,
00050                         &FaceFind::FacePosCBAll, &faceFind);
00051         
00052         //** subscribe to camera info, for coordinate conversion */
00053         ros::Subscriber camera_model = n.subscribe("/wide_stereo/left/camera_info", 5, &FaceFind::CameraModelCBAll, &faceFind);
00054         ros::Subscriber prosilica_camera_model = n.subscribe("/prosilica/camera_info", 5,
00055                         &FaceFind::ProsilicaCameraModelCBAll, &faceFind);
00056         
00057         //** laser clients */
00058         faceFind.laserscanner_client = n.serviceClient<laser_assembler::AssembleScans>("assemble_scans");
00059         faceFind.lasertilt_client    = n.serviceClient<pr2_msgs::SetPeriodicCmd>("/laser_tilt_controller/set_periodic_cmd");
00060 
00061         //** server for project status messages */
00062         ros::ServiceServer statusService = n.advertiseService("/alubsc/status_msg", &FaceFind::StatusMessageCBAll, &faceFind);
00063         
00064         //** server for edge image from contour_detector */
00065         ros::ServiceServer edgeImageService = n.advertiseService("/alubsc/edge_image", &FaceFind::EdgeImageCBAll, &faceFind);
00066         
00067         //** clients for commands */
00068         faceFind.pen_gripper_client = n.serviceClient<portrait_robot_msgs::alubsc_node_instr>("/alubsc/node_instr/pen_gripper");
00069         faceFind.contour_detector_client = n.serviceClient<portrait_robot_msgs::alubsc_node_instr>("/contour_detector/contour_detector");
00070         faceFind.painter_client = n.serviceClient<portrait_robot_msgs::alubsc_node_instr>("/alubsc/node_instr/painter");
00071         faceFind.corner_client = n.serviceClient<portrait_robot_msgs::alubsc_node_instr>("/alubsc/node_instr/manual_canvas_setting");
00072         
00073         //** gui related connects */
00074         UserInterface window;
00075         
00076         QObject::connect(&faceFind, SIGNAL(newCameraImage(QImage)), &window, SLOT(SetLeftImage(QImage)));
00077         QObject::connect(&faceFind, SIGNAL(newPhoto(QImage)), &window, SLOT(SetCenterImage(QImage)));
00078         QObject::connect(&faceFind, SIGNAL(newMask(QImage)), &window, SLOT(SetRightImage(QImage)));
00079         QObject::connect(&faceFind, SIGNAL(setGUIInfo(QString)), &window, SLOT(SetInfo(QString)));
00080         QObject::connect(&faceFind, SIGNAL(setGUIStatus(QString)), &window, SLOT(SetStatus(QString)));
00081         QObject::connect(&faceFind, SIGNAL(newStatusMessage(int, QString)), &window, SLOT(UpdateStatusMessage(int, QString)));
00082         QObject::connect(&faceFind, SIGNAL(activateButton(int)), &window, SLOT(ActivateButton(int)));
00083         
00084         QObject::connect(&window, SIGNAL(sendMouseEvent(int, int, int)),
00085                         &faceFind, SLOT(ReceiveMouseEvent(int, int, int)));
00086         QObject::connect(&window, SIGNAL(mirror()), &faceFind, SLOT(Mirror()));
00087         QObject::connect(&window, SIGNAL(penButtonClick()), &faceFind, SLOT(PenButton()));
00088         QObject::connect(&window, SIGNAL(edgeButtonClick()), &faceFind, SLOT(EdgeButton()));
00089         QObject::connect(&window, SIGNAL(paintButtonClick()), &faceFind, SLOT(PaintButton()));
00090         QObject::connect(&window, SIGNAL(cornerButtonClick()), &faceFind, SLOT(CornerButton()));
00091         QObject::connect(&window, SIGNAL(loadEdgeImage(const char*)), &faceFind, SLOT(EdgeImageFromFile(const char*)));
00092         QObject::connect(&window, SIGNAL(loadPhoto(const char*, const char*)), &faceFind, SLOT(PhotoFromFile(const char*, const char*)));
00093         QObject::connect(&window, SIGNAL(headButtonClick()), &faceFind, SLOT(HeadButton()));
00094         QObject::connect(&window, SIGNAL(abortButtonClick()), &faceFind, SLOT(AbortButton()));
00095         
00096         window.show();
00097         
00098         //** ros spinner with callback queue */
00099         ros::AsyncSpinner spinner(0, &cq);
00100         spinner.start();
00101         application.exec();
00102         spinner.stop();
00103         
00104         return 0;
00105 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


face_finder
Author(s): Nikolaus Mayer, Christian Schilling
autogenerated on Wed Dec 26 2012 16:22:45