Statistics
| Branch: | Tag: | Revision:

humotion / examples / meka / src / mekajointinterface.cpp @ 10cae485

History | View | Annotate | Download (7.225 KB)

1 2be6243f Sebastian Meyer zu Borgsen
#include "mekajointinterface.h"
2
using namespace std;
3
4
//WARNING: DO NOT CHANGE THIS; VELOCITYMODE IS NOT YET IMPLEMENTED
5
#define POSITION_CONTROL 1
6
7 473a6a6c Simon Schulz
void MekaJointInterface::incoming_jointstates(const sensor_msgs::JointState & msg){
8 a4795834 Simon Schulz
    //fetch current timestamp
9 6353defa Simon Schulz
    double timestamp = msg.header.stamp.toSec();
10 a4795834 Simon Schulz
11
    //iterate through incoming joints and filter out joints we need:
12
    for(int i=0; i<msg.name.size(); i++){
13 6353defa Simon Schulz
14 a4795834 Simon Schulz
        string name = msg.name[i];
15 0b76d42b Simon Schulz
        //printf("incoming data for joint '%s'\n", name.c_str());
16 a4795834 Simon Schulz
17
        int id = -1;
18 e8e20dfe Sebastian Meyer zu Borgsen
        if (name == "head_j1"){
19 a4795834 Simon Schulz
            id = ID_NECK_PAN;
20 e8e20dfe Sebastian Meyer zu Borgsen
        }else if(name == "head_j0"){
21 a4795834 Simon Schulz
            id = ID_NECK_TILT;
22
        }
23
24
        //store data:
25
        if (id != -1){
26
            //printf("> storing joint data for joint id %d\n", id);
27 7115c3a4 Simon Schulz
            if (i >= msg.position.size()){
28 2c4bbc89 Simon Schulz
                printf("> joint state msg is missing position data for joint '%s'...\n", name.c_str());
29
                return;
30 7115c3a4 Simon Schulz
            }
31
            if (i >= msg.velocity.size()){
32 2c4bbc89 Simon Schulz
                //printf("> joint state msg is missing velocity data for joint '%s'...\n", name.c_str());
33 3f8fb5a1 Simon Schulz
                //exit(EXIT_FAILURE);
34 2c4bbc89 Simon Schulz
                return;
35 7115c3a4 Simon Schulz
            }
36
            //ok, safe to access data
37 a4795834 Simon Schulz
            JointInterface::store_incoming_position(id, msg.position[i], timestamp);
38
            JointInterface::store_incoming_speed(   id, msg.velocity[i], timestamp);
39
        }
40
    }
41
42 6353defa Simon Schulz
    //dummy data uses current time
43
    timestamp = get_timestamp_s();
44
45 a4795834 Simon Schulz
    //store dummy positions for joints we do not know about:
46
    store_dummy_data(ID_LIP_LEFT_UPPER, timestamp);
47
    store_dummy_data(ID_LIP_LEFT_LOWER, timestamp);
48
    store_dummy_data(ID_LIP_CENTER_UPPER, timestamp);
49
    store_dummy_data(ID_LIP_CENTER_LOWER, timestamp);
50
    store_dummy_data(ID_LIP_RIGHT_UPPER, timestamp);
51
    store_dummy_data(ID_LIP_RIGHT_LOWER, timestamp);
52
53
    store_dummy_data(ID_NECK_ROLL, timestamp);
54
    store_dummy_data(ID_EYES_BOTH_UD, timestamp);
55
    store_dummy_data(ID_EYES_LEFT_LR, timestamp);
56
    store_dummy_data(ID_EYES_RIGHT_LR, timestamp);
57
    store_dummy_data(ID_EYES_LEFT_LID_LOWER, timestamp);
58
    store_dummy_data(ID_EYES_LEFT_LID_UPPER, timestamp);
59
    store_dummy_data(ID_EYES_LEFT_BROW, timestamp);
60
    store_dummy_data(ID_EYES_RIGHT_LID_LOWER, timestamp);
61
    store_dummy_data(ID_EYES_RIGHT_LID_UPPER, timestamp);
62
    store_dummy_data(ID_EYES_RIGHT_BROW, timestamp);
63
64
}
65
66
void MekaJointInterface::store_dummy_data(int id, double timestamp){
67
    JointInterface::store_incoming_position(id, 0.0, timestamp);
68
    JointInterface::store_incoming_speed(id, 0.0, timestamp);
69 473a6a6c Simon Schulz
}
70
71 2be6243f Sebastian Meyer zu Borgsen
//! constructor
72 e4bb9fd4 Simon Schulz
MekaJointInterface::MekaJointInterface(string _input_scope, string _output_scope) : humotion::server::JointInterface(){
73
    input_scope = _input_scope;
74
    output_scope = _output_scope;
75 2be6243f Sebastian Meyer zu Borgsen
76 473a6a6c Simon Schulz
    //subscribe to meka joint states
77 99ebae32 Simon Schulz
    int argc = 0;
78
    ros::init(argc, (char**)NULL, "meka_humotion");
79 473a6a6c Simon Schulz
    ros::NodeHandle n;
80 2be6243f Sebastian Meyer zu Borgsen
81 e4bb9fd4 Simon Schulz
    printf("> listening on jointstates on '%s'\n",input_scope.c_str());
82
    joint_state_subscriber = n.subscribe(input_scope, 150, &MekaJointInterface::incoming_jointstates , this);
83 2be6243f Sebastian Meyer zu Borgsen
84 e4bb9fd4 Simon Schulz
    printf("> sending targets on '%s'\n", output_scope.c_str());
85
    target_publisher = n.advertise<trajectory_msgs::JointTrajectory>(output_scope, 100);
86 2be6243f Sebastian Meyer zu Borgsen
87 a4795834 Simon Schulz
    //tell humotion about min/max joint values:
88
    init_joints();
89 2be6243f Sebastian Meyer zu Borgsen
}
90
91
//! destructor
92
MekaJointInterface::~MekaJointInterface(){
93
}
94
95 473a6a6c Simon Schulz
96
97
void MekaJointInterface::run(){
98
   //iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
99
   //data_receiver->start();
100 a4795834 Simon Schulz
   ros::spin();
101 473a6a6c Simon Schulz
}
102
103
104 6353defa Simon Schulz
double MekaJointInterface::get_timestamp_s(){
105 a4795834 Simon Schulz
    struct timespec spec;
106
    clock_gettime(CLOCK_REALTIME, &spec);
107 6353defa Simon Schulz
    return spec.tv_sec + spec.tv_nsec / 1.0e9;
108 a4795834 Simon Schulz
}
109
110 473a6a6c Simon Schulz
//! set the target position of a joint
111
//! \param enum id of joint
112
//! \param float value
113
void MekaJointInterface::publish_target_position(int e){
114 6353defa Simon Schulz
   //we do this in execute motion for all joints at once...
115 473a6a6c Simon Schulz
}
116
117
118
//! actually execute the scheduled motion commands
119
void MekaJointInterface::execute_motion(){
120 a4795834 Simon Schulz
    //build msg
121
    trajectory_msgs::JointTrajectory msg;
122
    msg.joint_names.push_back("head_j0");
123
    msg.joint_names.push_back("head_j1");
124
125 e8e20dfe Sebastian Meyer zu Borgsen
    trajectory_msgs::JointTrajectoryPoint p;
126
    p.positions.push_back(joint_target[ID_NECK_TILT] * M_PI / 180.0);
127 10cae485 Sebastian Meyer zu Borgsen
    p.positions.push_back(joint_target[ID_NECK_PAN] * M_PI / 180.0 +0.314);
128
    printf("targets pan=%4.1f tilt=%4.1f (eye p %4.1f t %4.2f)\n",joint_target[ID_NECK_TILT],joint_target[ID_NECK_PAN],joint_target[ID_EYES_LEFT_LR],joint_target[ID_EYES_BOTH_UD]);
129 a4795834 Simon Schulz
130 e8e20dfe Sebastian Meyer zu Borgsen
    p.time_from_start = ros::Duration(1.2 * 1.0 / humotion::server::Server::MOTION_UPDATERATE);
131 a4795834 Simon Schulz
132 e8e20dfe Sebastian Meyer zu Borgsen
    msg.points.push_back(p);
133 a4795834 Simon Schulz
134
    target_publisher.publish(msg);
135
136
    /*
137
     void MekaJointInterface::store_min_max(int id, float min, float max){
138
header:
139
  seq: 636
140
  stamp:
141
    secs: 0
142
    nsecs: 0
143
  frame_id: ''
144
joint_names: ['head_j0', 'head_j1']
145
points:
146
  -
147
    positions: [-0.31, 0.01954768762234005]
148
    velocities: []
149
    accelerations: []
150
    effort: []
151
    time_from_start:
152
      secs: 1
153
      nsecs: 0
154

155
     */
156
157 473a6a6c Simon Schulz
    #if 0
158
    // set up neck and eye motion commands:
159
    if (POSITION_CONTROL){
160
        //position control
161
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
162
            set_target_in_positionmode(i, target_angle[i]);
163
        }
164
    }else{
165
        //velocity control
166
        for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
167
            set_target_in_velocitymode(i, target_angle[i]);
168
        }
169
    }
170
    //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
171

172

173
    //eyelids: unfortuantely the icub has only 1dof for eyelids, so we use only one dof here:
174
    set_eyelid_angle(target_angle[ICUB_ID_EYES_RIGHT_LID_UPPER]);
175

176
    //eyebrows are set using a special command as well:
177
    set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
178
    set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
179

180
    //mouth
181
    set_mouth();
182

183
    #endif
184
}
185

186

187
//! prepare and enable a joint
188
//! NOTE: this should also prefill the min/max positions for this joint
189
//! \param the enum id of a joint
190
void MekaJointInterface::enable_joint(int e){
191 ddccf279 Simon Schulz
    //meka does not support this, joints are always enabled
192 473a6a6c Simon Schulz
}
193

194
//! shutdown and disable a joint
195
//! \param the enum id of a joint
196
void MekaJointInterface::disable_joint(int e){
197 ddccf279 Simon Schulz
    //meka does not support this, joints are always enabled
198 473a6a6c Simon Schulz
}
199

200 a4795834 Simon Schulz
void MekaJointInterface::store_min_max(int id, float min, float max){
201
    joint_min[id] = min;
202
    joint_max[id] = max;
203
}
204

205
void MekaJointInterface::init_joints(){
206 10cae485 Sebastian Meyer zu Borgsen
    store_min_max(ID_NECK_TILT, -18, 1);
207
    store_min_max(ID_NECK_PAN, -56, 56);
208 a4795834 Simon Schulz

209
    store_min_max(ID_NECK_ROLL, -1, 1);
210
    store_min_max(ID_EYES_BOTH_UD, -1, 1);
211
    store_min_max(ID_EYES_LEFT_LR, -1, 1);
212
    store_min_max(ID_EYES_RIGHT_LR, -1, 1);
213
    store_min_max(ID_EYES_LEFT_LID_UPPER, -1, 1);
214
    store_min_max(ID_EYES_LEFT_LID_LOWER, -1, 1);
215
    store_min_max(ID_EYES_RIGHT_LID_UPPER, -1, 1);
216
    store_min_max(ID_EYES_RIGHT_LID_LOWER, -1, 1);
217
    store_min_max(ID_EYES_LEFT_BROW, -1, 1);
218
    store_min_max(ID_EYES_RIGHT_BROW, -1, 1);
219
    store_min_max(ID_LIP_CENTER_UPPER, -1, 1);
220
    store_min_max(ID_LIP_CENTER_LOWER, -1, 1);
221
    store_min_max(ID_LIP_LEFT_UPPER, -1, 1);
222
    store_min_max(ID_LIP_LEFT_LOWER, -1, 1);
223
    store_min_max(ID_LIP_RIGHT_UPPER, -1, 1);
224
    store_min_max(ID_LIP_RIGHT_LOWER, -1, 1);
225
}
226