Revision f0dcf4ca client/cpp/include/MiddlewareROS.h

View differences:

client/cpp/include/MiddlewareROS.h
35 35
    #include <hlrc_server/phoneme.h>
36 36
    #include <hlrc_server/soundchunk.h>
37 37
    #include <hlrc_server/gazetargetAction.h>
38
    #include <hlrc_server/lookattargetAction.h>
38 39
    #include <hlrc_server/animationAction.h>
39 40
    #include <hlrc_server/mouthtargetAction.h>
40 41
    #include <hlrc_server/utteranceAction.h>
......
50 51
class MiddlewareROS : public Middleware{
51 52
#ifndef ROS_SUPPORT
52 53
public:
53
    MiddlewareRSB(std::string scope) : Middleware(scope){
54
    MiddlewareROS(std::string scope) : Middleware(scope){
54 55
        printf("> ERROR: hlrc was compiled without ROS middleware support. Please use MiddlewareRSB() instead!\n\n");
55 56
        exit(EXIT_FAILURE);
56 57
    }
......
59 60
    void publish_default_emotion(RobotEmotion e, bool blocking){};
60 61
    void publish_current_emotion(RobotEmotion e, bool blocking){};
61 62
    void publish_gaze_target(RobotGaze g, bool blocking){};
63
    void publish_lookat_target(float x, float y, float z, const std::string frame_id,
64
                               bool blocking, float roll){};
62 65
    void publish_mouth_target(RobotMouth m, bool blocking){};
63 66
    void publish_head_animation(RobotHeadAnimation a, bool blocking) {};
64 67
    void publish_speech(std::string text, bool blocking) {};
65 68

  
66

  
67

  
68 69
#else
69 70
public:
70 71
    MiddlewareROS(std::string scope);
......
74 75
    void publish_current_emotion(RobotEmotion e, bool blocking);
75 76
    void publish_default_emotion(RobotEmotion e, bool blocking);
76 77
    void publish_gaze_target(RobotGaze target, bool blocking);
78
    void publish_lookat_target(float x, float y, float z, const std::string frame_id,
79
                               bool blocking, float roll);
77 80
    void publish_mouth_target(RobotMouth target, bool blocking);
78 81
    void publish_head_animation(RobotHeadAnimation a, bool blocking);
79 82
    void publish_speech(std::string text, bool blocking);
......
87 90
    actionlib::SimpleActionClient<hlrc_server::emotionstateAction>  *default_emotionstate_ac;
88 91
    actionlib::SimpleActionClient<hlrc_server::emotionstateAction>  *current_emotionstate_ac;
89 92
    actionlib::SimpleActionClient<hlrc_server::gazetargetAction>    *gazetarget_ac;
90
    actionlib::SimpleActionClient<hlrc_server::mouthtargetAction>    *mouthtarget_ac;
91
    actionlib::SimpleActionClient<hlrc_server::speechAction>     *speech_ac;
93
    actionlib::SimpleActionClient<hlrc_server::lookattargetAction>  *lookattarget_ac;
94
    actionlib::SimpleActionClient<hlrc_server::mouthtargetAction>   *mouthtarget_ac;
95
    actionlib::SimpleActionClient<hlrc_server::speechAction>        *speech_ac;
92 96
#endif
93 97
};

Also available in: Unified diff