Revision f0dcf4ca

View differences:

client/CMakeLists.txt
5 5

  
6 6
add_subdirectory(cpp)
7 7
add_subdirectory(python)
8

  
9

  
client/cpp/include/Middleware.h
46 46
    void set_default_emotion(RobotEmotion e, bool blocking);
47 47
    void set_current_emotion(RobotEmotion e, bool blocking);
48 48
    void set_gaze_target(RobotGaze target, bool blocking);
49
    void set_lookat_target(float x, float y, float z, const std::string frame_id,
50
                           bool blocking, float roll);
49 51
    void set_mouth_target(RobotMouth target, bool blocking);
50 52
    void set_head_animation(RobotHeadAnimation a, bool blocking);
51 53
    void set_speak(std::string text, bool blocking);
......
59 61
    virtual void publish_default_emotion(RobotEmotion e, bool blocking) = 0;
60 62
    virtual void publish_current_emotion(RobotEmotion e, bool blocking) = 0;
61 63
    virtual void publish_gaze_target(RobotGaze g, bool blocking) = 0;
64
    virtual void publish_lookat_target(float x, float y, float z, const std::string frame_id,
65
                                       bool blocking, float roll) = 0;
62 66
    virtual void publish_mouth_target(RobotMouth m, bool blocking) = 0;
63 67
    virtual void publish_head_animation(RobotHeadAnimation a, bool blocking) = 0;
64 68
    virtual void publish_speech(std::string text, bool blocking) = 0;
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
};
client/cpp/include/MiddlewareRSB.h
51 51
    void publish_default_emotion(RobotEmotion e, bool blocking){};
52 52
    void publish_current_emotion(RobotEmotion e, bool blocking){};
53 53
    void publish_gaze_target(RobotGaze g, bool blocking){};
54
    void publish_lookat_target(float x, float y, float z, const std::string frame_id,
55
                               bool blocking, float roll){};
54 56
    void publish_mouth_target(RobotMouth m, bool blocking){};
55 57
    void publish_head_animation(RobotHeadAnimation a, bool blocking) {};
56 58
    void publish_speech(std::string text, bool blocking) {};
......
66 68
    void publish_current_emotion(RobotEmotion e, bool blocking);
67 69
    void publish_default_emotion(RobotEmotion e, bool blocking);
68 70
    void publish_gaze_target(RobotGaze target, bool blocking);
71
    void publish_lookat_target(float x, float y, float z, const std::string frame_id,
72
                               bool blocking, float roll);
69 73
    void publish_mouth_target(RobotMouth target, bool blocking);
70 74
    void publish_head_animation(RobotHeadAnimation a, bool blocking);
71 75
    void publish_speech(std::string text, bool blocking);
client/cpp/include/RobotController.h
44 44

  
45 45
    void set_gaze_target(RobotGaze target, bool blocking=false);
46 46
    RobotGaze get_gaze_target();
47
    void set_lookat_target(float x, float y, float z, const std::string frame_id="",
48
                           bool blocking=false, float roll=0.0);
47 49

  
48 50
    void set_mouth_target(RobotMouth target, bool blocking=false);
49 51

  
client/cpp/src/Middleware.cpp
58 58
    publish_gaze_target(gazeTarget, blocking);
59 59
}
60 60

  
61
void Middleware::set_lookat_target(float x, float y, float z, const string frame_id, bool blocking, float roll)
62
{
63
    publish_lookat_target(x,y,z, frame_id, blocking, roll);
64
}
65

  
61 66
void Middleware::set_mouth_target(RobotMouth target, bool blocking){
62 67
    mouthTarget = target;
63 68
    publish_mouth_target(mouthTarget, blocking);
client/cpp/src/MiddlewareROS.cpp
78 78
    current_emotionstate_ac = create_action_client<hlrc_server::emotionstateAction>(scope + "/currentEmotion");
79 79
    default_emotionstate_ac = create_action_client<hlrc_server::emotionstateAction>(scope + "/defaultEmotion");
80 80
    gazetarget_ac = create_action_client<hlrc_server::gazetargetAction>(scope + "/gaze");
81
    lookattarget_ac = create_action_client<hlrc_server::lookattargetAction>(scope + "/lookat");
81 82
    mouthtarget_ac = create_action_client<hlrc_server::mouthtargetAction>(scope + "/mouth");
82 83
    speech_ac = create_action_client<hlrc_server::speechAction>(scope + "/speech");
83 84

  
......
173 174
    }
174 175
}
175 176

  
177
void MiddlewareROS::publish_lookat_target(float x, float y, float z, const string frame_id, bool blocking, float roll)
178
{
179
    hlrc_server::lookattargetGoal goal;
180
    goal.point.header.frame_id = frame_id;
181
    goal.point.header.stamp = ros::Time::now();
182

  
183
    geometry_msgs::Point &p = goal.point.point;
184
    p.x = x;
185
    p.y = y;
186
    p.z = z;
187
    goal.roll = roll;
188

  
189
    //send
190
    lookattarget_ac->sendGoal(goal);
191

  
192
    if (blocking){
193
        bool finished_before_timeout = gazetarget_ac->waitForResult(ros::Duration(ROS_ACTION_CALL_TIMEOUT));
194
        if (!finished_before_timeout){
195
            printf("> ERROR: blocking call timed out!\n");
196
        }
197
    }
198
}
199

  
176 200

  
177 201
void MiddlewareROS::publish_mouth_target(RobotMouth target, bool blocking){
178 202
    hlrc_server::mouthtargetGoal goal;
client/cpp/src/MiddlewareRSB.cpp
156 156
    }
157 157
}
158 158

  
159
void MiddlewareRSB::publish_lookat_target(float x, float y, float z, const std::string frame_id,
160
                                          bool blocking, float roll){
161
    std::cerr << "not yet implemented" << std::endl;
162
}
163

  
159 164
void MiddlewareRSB::publish_mouth_target(RobotMouth target, bool blocking){
160 165
/*
161 166
    boost::shared_ptr<rst::robot::MouthTarget> request(new rst::robot::MouthTarget());
client/cpp/src/RobotController.cpp
64 64
    return middleware->get_gaze_target();
65 65
}
66 66

  
67
void RobotController::set_lookat_target(float x, float y, float z, const std::string frame_id,
68
                                        bool blocking, float roll){
69
    middleware->set_lookat_target(x, y, z, frame_id, blocking, roll);
70
}
71

  
67 72
void RobotController::set_mouth_target(RobotMouth target, bool blocking){
68 73
    middleware->set_mouth_target(target, blocking);
69 74
}
server/CMakeLists.txt
96 96

  
97 97
    catkin_package(
98 98
        INCLUDE_DIRS include
99
        LIBRARIES hlrc_server
99
        LIBRARIES
100 100
        CATKIN_DEPENDS actionlib_msgs
101 101
        #CATKIN_DEPENDS message_runtime
102 102
        #DEPENDS system_lib

Also available in: Unified diff