Statistics
| Branch: | Tag: | Revision:

humotion / include / humotion / server / motion_generator.h @ ea068cf1

History | View | Annotate | Download (2.191 KB)

1
/*
2
* This file is part of humotion
3
*
4
* Copyright(c) sschulz <AT> techfak.uni-bielefeld.de
5
* http://opensource.cit-ec.de/projects/humotion
6
*
7
* This file may be licensed under the terms of the
8
* GNU Lesser General Public License Version 3 (the ``LGPL''),
9
* or (at your option) any later version.
10
*
11
* Software distributed under the License is distributed
12
* on an ``AS IS'' basis, WITHOUT WARRANTY OF ANY KIND, either
13
* express or implied. See the LGPL for the specific language
14
* governing rights and limitations.
15
*
16
* You should have received a copy of the LGPL along with this
17
* program. If not, go to http://www.gnu.org/licenses/lgpl.html
18
* or write to the Free Software Foundation, Inc.,
19
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
20
*
21
* The development of this software was supported by the
22
* Excellence Cluster EXC 277 Cognitive Interaction Technology.
23
* The Excellence Cluster EXC 277 is a grant of the Deutsche
24
* Forschungsgemeinschaft (DFG) in the context of the German
25
* Excellence Initiative.
26
*/
27

    
28
#ifndef INCLUDE_HUMOTION_SERVER_MOTION_GENERATOR_H_
29
#define INCLUDE_HUMOTION_SERVER_MOTION_GENERATOR_H_
30

    
31
#include <boost/date_time/posix_time/posix_time.hpp>
32

    
33
#include <string>
34

    
35
#include "humotion/server/joint_interface.h"
36

    
37
namespace humotion {
38
namespace server {
39

    
40
class MotionGenerator {
41
 public:
42
    explicit MotionGenerator(JointInterface *j);
43
    ~MotionGenerator();
44

    
45
    virtual void calculate_targets() = 0;
46
    virtual void publish_targets() = 0;
47

    
48
    virtual void set_gaze_target(GazeState s);
49
    virtual void set_mouth_target(MouthState s);
50

    
51
 protected:
52
    float get_current_position(int joint_id);
53
    float get_current_speed(int joint_id);
54
    humotion::Timestamp get_timestamped_state(int joint_id, float *position, float *velocity);
55
    float limit_target(int joint_id, float val);
56
    bool mouth_target_input_active();
57
    bool gaze_target_input_active();
58

    
59
    JointInterface *joint_interface_;
60

    
61
    // gaze
62
    GazeState  requested_gaze_state_;
63
    boost::system_time last_gaze_target_update_;
64

    
65
    // mouth
66
    MouthState requested_mouth_target_;
67
    boost::system_time last_mouth_target_update_;
68
};
69

    
70
}  // namespace server
71
}  // namespace humotion
72

    
73
#endif  // INCLUDE_HUMOTION_SERVER_MOTION_GENERATOR_H_