humotion / examples / meka / src / mekajointinterface.cpp @ 8db9ba4f
History | View | Annotate | Download (7.617 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 | b0d48d96 | Sebastian Meyer zu Borgsen | if (id == ID_NECK_PAN){
|
| 38 | //joint is inverted
|
||
| 39 | JointInterface::store_incoming_position(id, -180.0 / M_PI * msg.position[i], timestamp); |
||
| 40 | JointInterface::store_incoming_speed( id, -180.0 / M_PI * msg.velocity[i], timestamp); |
||
| 41 | }else if (id == ID_NECK_TILT){ |
||
| 42 | JointInterface::store_incoming_position(id, 180.0 / M_PI * msg.position[i], timestamp); |
||
| 43 | JointInterface::store_incoming_speed( id, 180.0 / M_PI * msg.velocity[i], timestamp); |
||
| 44 | } |
||
| 45 | a4795834 | Simon Schulz | } |
| 46 | } |
||
| 47 | |||
| 48 | 6353defa | Simon Schulz | //dummy data uses current time
|
| 49 | timestamp = get_timestamp_s(); |
||
| 50 | |||
| 51 | a4795834 | Simon Schulz | //store dummy positions for joints we do not know about:
|
| 52 | store_dummy_data(ID_LIP_LEFT_UPPER, timestamp); |
||
| 53 | store_dummy_data(ID_LIP_LEFT_LOWER, timestamp); |
||
| 54 | store_dummy_data(ID_LIP_CENTER_UPPER, timestamp); |
||
| 55 | store_dummy_data(ID_LIP_CENTER_LOWER, timestamp); |
||
| 56 | store_dummy_data(ID_LIP_RIGHT_UPPER, timestamp); |
||
| 57 | store_dummy_data(ID_LIP_RIGHT_LOWER, timestamp); |
||
| 58 | |||
| 59 | store_dummy_data(ID_NECK_ROLL, timestamp); |
||
| 60 | store_dummy_data(ID_EYES_BOTH_UD, timestamp); |
||
| 61 | store_dummy_data(ID_EYES_LEFT_LR, timestamp); |
||
| 62 | store_dummy_data(ID_EYES_RIGHT_LR, timestamp); |
||
| 63 | store_dummy_data(ID_EYES_LEFT_LID_LOWER, timestamp); |
||
| 64 | store_dummy_data(ID_EYES_LEFT_LID_UPPER, timestamp); |
||
| 65 | store_dummy_data(ID_EYES_LEFT_BROW, timestamp); |
||
| 66 | store_dummy_data(ID_EYES_RIGHT_LID_LOWER, timestamp); |
||
| 67 | store_dummy_data(ID_EYES_RIGHT_LID_UPPER, timestamp); |
||
| 68 | store_dummy_data(ID_EYES_RIGHT_BROW, timestamp); |
||
| 69 | |||
| 70 | } |
||
| 71 | |||
| 72 | void MekaJointInterface::store_dummy_data(int id, double timestamp){ |
||
| 73 | fcc5e139 | Sebastian Meyer zu Borgsen | JointInterface::store_incoming_position(id, 0.0, timestamp); |
| 74 | a4795834 | Simon Schulz | JointInterface::store_incoming_speed(id, 0.0, timestamp); |
| 75 | 473a6a6c | Simon Schulz | } |
| 76 | |||
| 77 | 2be6243f | Sebastian Meyer zu Borgsen | //! constructor
|
| 78 | e4bb9fd4 | Simon Schulz | MekaJointInterface::MekaJointInterface(string _input_scope, string _output_scope) : humotion::server::JointInterface(){ |
| 79 | input_scope = _input_scope; |
||
| 80 | output_scope = _output_scope; |
||
| 81 | 2be6243f | Sebastian Meyer zu Borgsen | |
| 82 | 473a6a6c | Simon Schulz | //subscribe to meka joint states
|
| 83 | 99ebae32 | Simon Schulz | int argc = 0; |
| 84 | ros::init(argc, (char**)NULL, "meka_humotion"); |
||
| 85 | 473a6a6c | Simon Schulz | ros::NodeHandle n; |
| 86 | 2be6243f | Sebastian Meyer zu Borgsen | |
| 87 | e4bb9fd4 | Simon Schulz | printf("> listening on jointstates on '%s'\n",input_scope.c_str());
|
| 88 | joint_state_subscriber = n.subscribe(input_scope, 150, &MekaJointInterface::incoming_jointstates , this); |
||
| 89 | 2be6243f | Sebastian Meyer zu Borgsen | |
| 90 | e4bb9fd4 | Simon Schulz | printf("> sending targets on '%s'\n", output_scope.c_str());
|
| 91 | target_publisher = n.advertise<trajectory_msgs::JointTrajectory>(output_scope, 100);
|
||
| 92 | 2be6243f | Sebastian Meyer zu Borgsen | |
| 93 | a4795834 | Simon Schulz | //tell humotion about min/max joint values:
|
| 94 | init_joints(); |
||
| 95 | 2be6243f | Sebastian Meyer zu Borgsen | } |
| 96 | |||
| 97 | //! destructor
|
||
| 98 | MekaJointInterface::~MekaJointInterface(){
|
||
| 99 | } |
||
| 100 | |||
| 101 | 473a6a6c | Simon Schulz | |
| 102 | |||
| 103 | void MekaJointInterface::run(){
|
||
| 104 | //iCubDataReceiver *data_receiver = new iCubDataReceiver(10/*1000.0 / MAIN_LOOP_FREQUENCY*/, iencs, this);
|
||
| 105 | //data_receiver->start();
|
||
| 106 | a4795834 | Simon Schulz | ros::spin(); |
| 107 | 473a6a6c | Simon Schulz | } |
| 108 | |||
| 109 | |||
| 110 | 6353defa | Simon Schulz | double MekaJointInterface::get_timestamp_s(){
|
| 111 | a4795834 | Simon Schulz | struct timespec spec;
|
| 112 | clock_gettime(CLOCK_REALTIME, &spec); |
||
| 113 | 6353defa | Simon Schulz | return spec.tv_sec + spec.tv_nsec / 1.0e9; |
| 114 | a4795834 | Simon Schulz | } |
| 115 | |||
| 116 | 473a6a6c | Simon Schulz | //! set the target position of a joint
|
| 117 | //! \param enum id of joint
|
||
| 118 | //! \param float value
|
||
| 119 | void MekaJointInterface::publish_target_position(int e){ |
||
| 120 | 6353defa | Simon Schulz | //we do this in execute motion for all joints at once...
|
| 121 | 473a6a6c | Simon Schulz | } |
| 122 | |||
| 123 | |||
| 124 | //! actually execute the scheduled motion commands
|
||
| 125 | void MekaJointInterface::execute_motion(){
|
||
| 126 | a4795834 | Simon Schulz | //build msg
|
| 127 | trajectory_msgs::JointTrajectory msg; |
||
| 128 | msg.joint_names.push_back("head_j0");
|
||
| 129 | msg.joint_names.push_back("head_j1");
|
||
| 130 | |||
| 131 | e8e20dfe | Sebastian Meyer zu Borgsen | trajectory_msgs::JointTrajectoryPoint p; |
| 132 | p.positions.push_back(joint_target[ID_NECK_TILT] * M_PI / 180.0); |
||
| 133 | f10ec142 | Sebastian Meyer zu Borgsen | //pan joint is inverted!
|
| 134 | p.positions.push_back(-joint_target[ID_NECK_PAN] * M_PI / 180.0); |
||
| 135 | fcc5e139 | Sebastian Meyer zu Borgsen | //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]);
|
| 136 | a4795834 | Simon Schulz | |
| 137 | e8e20dfe | Sebastian Meyer zu Borgsen | p.time_from_start = ros::Duration(1.2 * 1.0 / humotion::server::Server::MOTION_UPDATERATE); |
| 138 | a4795834 | Simon Schulz | |
| 139 | e8e20dfe | Sebastian Meyer zu Borgsen | msg.points.push_back(p); |
| 140 | a4795834 | Simon Schulz | |
| 141 | target_publisher.publish(msg); |
||
| 142 | |||
| 143 | /*
|
||
| 144 | void MekaJointInterface::store_min_max(int id, float min, float max){
|
||
| 145 | header:
|
||
| 146 | seq: 636
|
||
| 147 | stamp:
|
||
| 148 | secs: 0
|
||
| 149 | nsecs: 0
|
||
| 150 | frame_id: ''
|
||
| 151 | joint_names: ['head_j0', 'head_j1']
|
||
| 152 | points:
|
||
| 153 | -
|
||
| 154 | positions: [-0.31, 0.01954768762234005]
|
||
| 155 | velocities: []
|
||
| 156 | accelerations: []
|
||
| 157 | effort: []
|
||
| 158 | time_from_start:
|
||
| 159 | secs: 1
|
||
| 160 | nsecs: 0
|
||
| 161 | |||
| 162 | */
|
||
| 163 | |||
| 164 | 473a6a6c | Simon Schulz | #if 0
|
| 165 | // set up neck and eye motion commands:
|
||
| 166 | if (POSITION_CONTROL){
|
||
| 167 | //position control
|
||
| 168 | for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
|
||
| 169 | set_target_in_positionmode(i, target_angle[i]);
|
||
| 170 | }
|
||
| 171 | }else{
|
||
| 172 | //velocity control
|
||
| 173 | for(int i=ICUB_ID_NECK_TILT; i<=ICUB_ID_EYES_VERGENCE; i++){
|
||
| 174 | set_target_in_velocitymode(i, target_angle[i]);
|
||
| 175 | }
|
||
| 176 | }
|
||
| 177 | //printf("> TARGET PAN = %3.2f\n",target_angle[ICUB_ID_NECK_PAN]);
|
||
| 178 | |||
| 179 | |||
| 180 | //eyelids: unfortuantely the icub has only 1dof for eyelids, so we use only one dof here:
|
||
| 181 | set_eyelid_angle(target_angle[ICUB_ID_EYES_RIGHT_LID_UPPER]);
|
||
| 182 | |||
| 183 | //eyebrows are set using a special command as well:
|
||
| 184 | set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW);
|
||
| 185 | set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW);
|
||
| 186 | |||
| 187 | //mouth
|
||
| 188 | set_mouth();
|
||
| 189 | |||
| 190 | #endif
|
||
| 191 | }
|
||
| 192 | |||
| 193 | |||
| 194 | //! prepare and enable a joint
|
||
| 195 | //! NOTE: this should also prefill the min/max positions for this joint
|
||
| 196 | //! \param the enum id of a joint
|
||
| 197 | void MekaJointInterface::enable_joint(int e){
|
||
| 198 | ddccf279 | Simon Schulz | //meka does not support this, joints are always enabled
|
| 199 | 473a6a6c | Simon Schulz | }
|
| 200 | |||
| 201 | //! shutdown and disable a joint
|
||
| 202 | //! \param the enum id of a joint
|
||
| 203 | void MekaJointInterface::disable_joint(int e){
|
||
| 204 | ddccf279 | Simon Schulz | //meka does not support this, joints are always enabled
|
| 205 | 473a6a6c | Simon Schulz | }
|
| 206 | |||
| 207 | a4795834 | Simon Schulz | void MekaJointInterface::store_min_max(int id, float min, float max){
|
| 208 | joint_min[id] = min;
|
||
| 209 | joint_max[id] = max;
|
||
| 210 | }
|
||
| 211 | |||
| 212 | void MekaJointInterface::init_joints(){
|
||
| 213 | f10ec142 | Sebastian Meyer zu Borgsen | store_min_max(ID_NECK_TILT, -37, 1);
|
| 214 | store_min_max(ID_NECK_PAN, -70, 70);
|
||
| 215 | a4795834 | Simon Schulz | |
| 216 | store_min_max(ID_NECK_ROLL, -1, 1);
|
||
| 217 | store_min_max(ID_EYES_BOTH_UD, -1, 1);
|
||
| 218 | store_min_max(ID_EYES_LEFT_LR, -1, 1);
|
||
| 219 | store_min_max(ID_EYES_RIGHT_LR, -1, 1);
|
||
| 220 | store_min_max(ID_EYES_LEFT_LID_UPPER, -1, 1);
|
||
| 221 | store_min_max(ID_EYES_LEFT_LID_LOWER, -1, 1);
|
||
| 222 | store_min_max(ID_EYES_RIGHT_LID_UPPER, -1, 1);
|
||
| 223 | store_min_max(ID_EYES_RIGHT_LID_LOWER, -1, 1);
|
||
| 224 | store_min_max(ID_EYES_LEFT_BROW, -1, 1);
|
||
| 225 | store_min_max(ID_EYES_RIGHT_BROW, -1, 1);
|
||
| 226 | store_min_max(ID_LIP_CENTER_UPPER, -1, 1);
|
||
| 227 | store_min_max(ID_LIP_CENTER_LOWER, -1, 1);
|
||
| 228 | store_min_max(ID_LIP_LEFT_UPPER, -1, 1);
|
||
| 229 | store_min_max(ID_LIP_LEFT_LOWER, -1, 1);
|
||
| 230 | store_min_max(ID_LIP_RIGHT_UPPER, -1, 1);
|
||
| 231 | store_min_max(ID_LIP_RIGHT_LOWER, -1, 1);
|
||
| 232 | }
|
||
| 233 |