humotion / examples / humotion_yarp_icub / src / icub_jointinterface.cpp @ 07e68eb7
History | View | Annotate | Download (19.569 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 |
#include "humotion_yarp_icub/icub_faceinterface.h" |
| 29 |
#include "humotion_yarp_icub/icub_jointinterface.h" |
| 30 |
|
| 31 |
#include <yarp/os/Property.h> |
| 32 |
#include <string> |
| 33 |
|
| 34 |
using std::cout;
|
| 35 |
using std::cerr;
|
| 36 |
using std::string; |
| 37 |
|
| 38 |
//! constructor
|
| 39 |
iCubJointInterface::iCubJointInterface(string _scope) : humotion::server::JointInterface() {
|
| 40 |
scope = _scope; |
| 41 |
|
| 42 |
// add mappings from icub ids to humotion ids
|
| 43 |
init_id_map(); |
| 44 |
|
| 45 |
// initialise the pd controller for the velocity and position mixer
|
| 46 |
init_pv_mix_pid(); |
| 47 |
|
| 48 |
// intantiate the face interface
|
| 49 |
face_interface_ = new iCubFaceInterface(scope);
|
| 50 |
|
| 51 |
// intantiate the polydriver
|
| 52 |
yarp::os::Property options; |
| 53 |
options.put("device", "remote_controlboard"); |
| 54 |
options.put("local", "/local/head"); |
| 55 |
options.put("remote", scope + "/head"); |
| 56 |
yarp_polydriver_.open(options); |
| 57 |
|
| 58 |
// fetch yarp views:
|
| 59 |
bool success = true; |
| 60 |
// success &= yarp_polydriver_.view(yarp_iencs_);
|
| 61 |
// success &= yarp_polydriver_.view(yarp_ipos_);
|
| 62 |
success &= yarp_polydriver_.view(yarp_ivel_); |
| 63 |
success &= yarp_polydriver_.view(yarp_ilimits_); |
| 64 |
success &= yarp_polydriver_.view(yarp_pid_); |
| 65 |
success &= yarp_polydriver_.view(yarp_amp_); |
| 66 |
|
| 67 |
if (!success) {
|
| 68 |
cout << "ERROR: failed to fetch one or more yarp views... exiting\n";
|
| 69 |
exit(EXIT_FAILURE); |
| 70 |
} |
| 71 |
|
| 72 |
|
| 73 |
// tell humotion about min/max joint values:
|
| 74 |
init_joints(); |
| 75 |
|
| 76 |
// initialise joint controller
|
| 77 |
init_controller(); |
| 78 |
} |
| 79 |
|
| 80 |
//! destructor
|
| 81 |
iCubJointInterface::~iCubJointInterface() {
|
| 82 |
// stop velocity controller on exit
|
| 83 |
yarp_ivel_->stop(); |
| 84 |
} |
| 85 |
|
| 86 |
//! init the controller that allows to write target angles or velocities
|
| 87 |
void iCubJointInterface::init_controller() {
|
| 88 |
int number_of_joints;
|
| 89 |
|
| 90 |
// use position controller, first fetch no of axes:
|
| 91 |
yarp_ivel_->getAxes(&number_of_joints); |
| 92 |
|
| 93 |
// set ref acceleration to a value for all axes:
|
| 94 |
yarp_commands_.resize(number_of_joints); |
| 95 |
yarp_commands_ = 1e6;
|
| 96 |
yarp_ivel_->setRefAccelerations(yarp_commands_.data()); |
| 97 |
yarp_ivel_->setVelocityMode(); |
| 98 |
} |
| 99 |
|
| 100 |
//! initialise icub joint id to humotion joint id mappings
|
| 101 |
void iCubJointInterface::init_id_map() {
|
| 102 |
insert_icupid_to_humotionid_mapping(ICUB_ID_LIP_LEFT_UPPER, ID_LIP_LEFT_UPPER); |
| 103 |
insert_icupid_to_humotionid_mapping(ICUB_ID_LIP_LEFT_LOWER, ID_LIP_LEFT_LOWER); |
| 104 |
insert_icupid_to_humotionid_mapping(ICUB_ID_LIP_CENTER_UPPER, ID_LIP_CENTER_UPPER); |
| 105 |
insert_icupid_to_humotionid_mapping(ICUB_ID_LIP_CENTER_LOWER, ID_LIP_CENTER_LOWER); |
| 106 |
insert_icupid_to_humotionid_mapping(ICUB_ID_LIP_RIGHT_UPPER, ID_LIP_RIGHT_UPPER); |
| 107 |
insert_icupid_to_humotionid_mapping(ICUB_ID_LIP_RIGHT_LOWER, ID_LIP_RIGHT_LOWER); |
| 108 |
insert_icupid_to_humotionid_mapping(ICUB_ID_NECK_PAN, ID_NECK_PAN); |
| 109 |
insert_icupid_to_humotionid_mapping(ICUB_ID_NECK_TILT, ID_NECK_TILT); |
| 110 |
insert_icupid_to_humotionid_mapping(ICUB_ID_NECK_ROLL, ID_NECK_ROLL); |
| 111 |
// FIXME: remove this hack tha repurposes LEFT/RIGHT eye pan from humotion as vergence/pan
|
| 112 |
insert_icupid_to_humotionid_mapping(ICUB_ID_EYES_PAN, ID_EYES_LEFT_LR); |
| 113 |
insert_icupid_to_humotionid_mapping(ICUB_ID_EYES_VERGENCE, ID_EYES_RIGHT_LR); |
| 114 |
insert_icupid_to_humotionid_mapping(ICUB_ID_EYES_BOTH_UD, ID_EYES_BOTH_UD); |
| 115 |
insert_icupid_to_humotionid_mapping(ICUB_ID_EYES_LEFT_LID_LOWER, ID_EYES_LEFT_LID_LOWER); |
| 116 |
insert_icupid_to_humotionid_mapping(ICUB_ID_EYES_LEFT_LID_UPPER, ID_EYES_LEFT_LID_UPPER); |
| 117 |
insert_icupid_to_humotionid_mapping(ICUB_ID_EYES_LEFT_BROW, ID_EYES_LEFT_BROW); |
| 118 |
insert_icupid_to_humotionid_mapping(ICUB_ID_EYES_RIGHT_LID_LOWER, ID_EYES_RIGHT_LID_LOWER); |
| 119 |
insert_icupid_to_humotionid_mapping(ICUB_ID_EYES_RIGHT_LID_UPPER, ID_EYES_RIGHT_LID_UPPER); |
| 120 |
insert_icupid_to_humotionid_mapping(ICUB_ID_EYES_RIGHT_BROW, ID_EYES_RIGHT_BROW); |
| 121 |
} |
| 122 |
|
| 123 |
//! initialize the position and velocity mixer PD controller
|
| 124 |
void iCubJointInterface::init_pv_mix_pid() {
|
| 125 |
// init control variables and last error variable for the internal
|
| 126 |
// position and velocity mixer PD controller:
|
| 127 |
pv_mix_pid_p_.resize(ICUB_JOINT_ID_ENUM_SIZE); |
| 128 |
pv_mix_pid_d_.resize(ICUB_JOINT_ID_ENUM_SIZE); |
| 129 |
pv_mix_last_error_.resize(ICUB_JOINT_ID_ENUM_SIZE); |
| 130 |
|
| 131 |
enum_id_bimap_t::const_iterator it; |
| 132 |
for (it = enum_id_bimap.begin(); it != enum_id_bimap.end(); ++it) {
|
| 133 |
int id = it->left;
|
| 134 |
pv_mix_pid_p_[id] = 5.5; |
| 135 |
pv_mix_pid_d_[id] = 0.3; |
| 136 |
pv_mix_last_error_[id] = 0.0; |
| 137 |
} |
| 138 |
} |
| 139 |
|
| 140 |
//! add mapping from icub joint ids to humotion ids
|
| 141 |
//! this might look strange at the first sight but we need to have a generic
|
| 142 |
//! way to acces joints from libhumotion. therefore the lib uses its enum with ID_* enum ids
|
| 143 |
//! to access the joints. now we need to define a mapping to map those to the icub motor ids.
|
| 144 |
void iCubJointInterface::insert_icupid_to_humotionid_mapping(int icubid, int humotionid) { |
| 145 |
enum_id_bimap.insert(enum_id_bimap_entry_t(icubid, humotionid)); |
| 146 |
} |
| 147 |
|
| 148 |
|
| 149 |
|
| 150 |
|
| 151 |
void iCubJointInterface::run() {
|
| 152 |
float loop_duration_ms = 1000.0 / MAIN_LOOP_FREQUENCY; |
| 153 |
iCubDataReceiver *data_receiver = new iCubDataReceiver(loop_duration_ms, this); |
| 154 |
data_receiver->start(); |
| 155 |
} |
| 156 |
|
| 157 |
//! stores the target position & velocity of a given joint
|
| 158 |
//! \param enum id of joint
|
| 159 |
//! \param float value
|
| 160 |
void iCubJointInterface::publish_target(int humotion_id, float position, float velocity) { |
| 161 |
// special handler for eye joints
|
| 162 |
if ((humotion_id == JointInterface::ID_EYES_LEFT_LR) ||
|
| 163 |
(humotion_id == JointInterface::ID_EYES_RIGHT_LR)) {
|
| 164 |
// the icub has a combined pan angle for both eyes, so seperate this:
|
| 165 |
float target_position_left = get_target_position(JointInterface::ID_EYES_LEFT_LR);
|
| 166 |
float target_position_right = get_target_position(JointInterface::ID_EYES_RIGHT_LR);
|
| 167 |
float target_velocity_left = get_target_velocity(JointInterface::ID_EYES_LEFT_LR);
|
| 168 |
float target_velocity_right = get_target_velocity(JointInterface::ID_EYES_RIGHT_LR);
|
| 169 |
|
| 170 |
|
| 171 |
// calculate target angles
|
| 172 |
float target_position_pan = (target_position_right + target_position_left) / 2; |
| 173 |
float target_position_vergence = (target_position_right - target_position_left);
|
| 174 |
|
| 175 |
/*cout << "LR " << target_position_left << " " << target_position_right <<
|
| 176 |
" PAN " << target_position_pan << " VERGENCE " << target_position_vergence << "\n";*/
|
| 177 |
|
| 178 |
// calculate target velocities
|
| 179 |
// for now just use the same velocity for pan and vergence
|
| 180 |
float target_velocity_pan = (target_velocity_left + target_velocity_right) / 2.0; |
| 181 |
float target_velocity_vergence = target_velocity_left - target_velocity_right;
|
| 182 |
|
| 183 |
store_icub_joint_target(ICUB_ID_EYES_PAN, |
| 184 |
target_position_pan, target_velocity_pan); |
| 185 |
store_icub_joint_target(ICUB_ID_EYES_VERGENCE, |
| 186 |
target_position_vergence, target_velocity_vergence); |
| 187 |
} else {
|
| 188 |
// convert to icub joint id
|
| 189 |
int icub_id = convert_humotion_jointid_to_icub(humotion_id);
|
| 190 |
// store target data
|
| 191 |
store_icub_joint_target(icub_id, position, velocity); |
| 192 |
} |
| 193 |
} |
| 194 |
|
| 195 |
|
| 196 |
//! set the target data for a given icub joint
|
| 197 |
//! \param id of joint
|
| 198 |
//! \param float value of position
|
| 199 |
void iCubJointInterface::store_icub_joint_target(int icub_id, float position, float velocity) { |
| 200 |
//cout << "store_icub_joint_target(" << icub_id << ", " << position << ", ..)\n";
|
| 201 |
|
| 202 |
if ((icub_id == ICUB_ID_NECK_PAN) || (icub_id == ICUB_ID_EYES_VERGENCE)) {
|
| 203 |
// icub uses an inverted neck pan specification
|
| 204 |
position = -position; |
| 205 |
velocity = -velocity; |
| 206 |
} |
| 207 |
|
| 208 |
// store values
|
| 209 |
target_angle_[icub_id] = position; |
| 210 |
target_velocity_[icub_id] = velocity; |
| 211 |
} |
| 212 |
|
| 213 |
//! execute a move in velocity mode
|
| 214 |
//! \param id of joint
|
| 215 |
//! \param angle
|
| 216 |
void iCubJointInterface::set_target_in_velocitymode(int icub_id) { |
| 217 |
// fetch humotion id from icub joint id
|
| 218 |
int humotion_id = convert_icub_jointid_to_humotion(icub_id);
|
| 219 |
|
| 220 |
// fetch the target velocity
|
| 221 |
float target_velocity = target_velocity_[icub_id];
|
| 222 |
|
| 223 |
float vmax = 350.0; |
| 224 |
if (target_velocity > vmax) target_velocity = vmax;
|
| 225 |
if (target_velocity < -vmax) target_velocity = -vmax;
|
| 226 |
|
| 227 |
// execute:
|
| 228 |
if ((icub_id != ICUB_ID_NECK_PAN)
|
| 229 |
&& (icub_id != ICUB_ID_EYES_BOTH_UD) |
| 230 |
&& (icub_id != ICUB_ID_NECK_TILT) |
| 231 |
&& (icub_id != ICUB_ID_EYES_PAN) |
| 232 |
&& (icub_id != ICUB_ID_EYES_VERGENCE) |
| 233 |
// && (icub_id != ICUB_ID_NECK_TILT)
|
| 234 |
) {
|
| 235 |
// limit to some joints for debugging...
|
| 236 |
return;
|
| 237 |
} |
| 238 |
|
| 239 |
// we now add a pd control loop for velocity moves in order to handle position errors
|
| 240 |
// FIXME: add position interpolation into future. this requires to enable the velocity
|
| 241 |
// broadcast in the torso and head ini file and fetch that velocity in the
|
| 242 |
// icub_data_receiver as well. TODO: check if the can bus has enough bandwidth for that
|
| 243 |
|
| 244 |
// first: fetch the timstamp of the last known position
|
| 245 |
humotion::Timestamp data_ts = get_ts_position(humotion_id).get_last_timestamp(); |
| 246 |
|
| 247 |
// fetch current position & velocity
|
| 248 |
float current_position = get_ts_position(humotion_id).get_interpolated_value(data_ts);
|
| 249 |
float current_velocity = get_ts_speed(humotion_id).get_interpolated_value(data_ts);
|
| 250 |
|
| 251 |
// the icub has a combined eye pan actuator, therefore
|
| 252 |
// we have to calculate pan angle and vergence based on the left and right target angles:
|
| 253 |
if (icub_id == ICUB_ID_EYES_PAN) {
|
| 254 |
// fetch timestamp
|
| 255 |
data_ts = get_ts_position(ID_EYES_LEFT_LR).get_last_timestamp(); |
| 256 |
|
| 257 |
// get the left and right positions
|
| 258 |
float pos_left = get_ts_position(ID_EYES_LEFT_LR).get_interpolated_value(data_ts);
|
| 259 |
float pos_right = get_ts_position(ID_EYES_RIGHT_LR).get_interpolated_value(data_ts);
|
| 260 |
current_position = (pos_left + pos_right) / 2.0; |
| 261 |
|
| 262 |
// same for velocities:
|
| 263 |
float vel_left = get_ts_speed(ID_EYES_LEFT_LR).get_interpolated_value(data_ts);
|
| 264 |
float vel_right = get_ts_speed(ID_EYES_RIGHT_LR).get_interpolated_value(data_ts);
|
| 265 |
current_velocity = (vel_left + vel_right) / 2.0; |
| 266 |
|
| 267 |
} else if (icub_id == ICUB_ID_EYES_VERGENCE) { |
| 268 |
// fetch timestamp
|
| 269 |
data_ts = get_ts_position(ID_EYES_LEFT_LR).get_last_timestamp(); |
| 270 |
|
| 271 |
// get the left and right positions
|
| 272 |
float pos_left = get_ts_position(ID_EYES_LEFT_LR).get_interpolated_value(data_ts);
|
| 273 |
float pos_right = get_ts_position(ID_EYES_RIGHT_LR).get_interpolated_value(data_ts);
|
| 274 |
|
| 275 |
current_position = pos_left - pos_right; |
| 276 |
|
| 277 |
// same for velocities:
|
| 278 |
float vel_left = get_ts_speed(ID_EYES_LEFT_LR).get_interpolated_value(data_ts);
|
| 279 |
float vel_right = get_ts_speed(ID_EYES_RIGHT_LR).get_interpolated_value(data_ts);
|
| 280 |
current_velocity = (vel_left - vel_right); |
| 281 |
} |
| 282 |
|
| 283 |
// calculate position error:
|
| 284 |
float position_error = target_angle_[icub_id] - current_position;
|
| 285 |
|
| 286 |
// calculate d term
|
| 287 |
float error_d = (position_error - pv_mix_last_error_[icub_id]) / (framerate*1000.0); |
| 288 |
pv_mix_last_error_[icub_id] = position_error; |
| 289 |
|
| 290 |
// finally do a PD loop to get the target velocity
|
| 291 |
float pv_mix_velocity = pv_mix_pid_p_[icub_id] * position_error
|
| 292 |
+ pv_mix_pid_p_[icub_id]*error_d |
| 293 |
+ target_velocity; |
| 294 |
|
| 295 |
|
| 296 |
/*cout << "\n"
|
| 297 |
<< current_position << " "
|
| 298 |
<< target_angle_[icub_id] << " "
|
| 299 |
<< current_velocity << " "
|
| 300 |
<< pv_mix_velocity << " "
|
| 301 |
<< target_velocity << " "
|
| 302 |
<< position_error << " "
|
| 303 |
<< " PID" << icub_id << "\n";*/
|
| 304 |
|
| 305 |
// execute velocity move
|
| 306 |
bool success;
|
| 307 |
int count = 0; |
| 308 |
do {
|
| 309 |
success = yarp_ivel_->velocityMove(icub_id, pv_mix_velocity); |
| 310 |
if (count++ >= 10) { |
| 311 |
cerr << "ERROR: failed to send velocity move command! gave up after 10 trials\n";
|
| 312 |
yarp_ivel_->stop(); |
| 313 |
exit(EXIT_FAILURE); |
| 314 |
} |
| 315 |
} while (!success);
|
| 316 |
} |
| 317 |
|
| 318 |
//! actually execute the scheduled motion commands
|
| 319 |
void iCubJointInterface::execute_motion() {
|
| 320 |
// set up neck and eye motion commands in velocitymode
|
| 321 |
for (int i = ICUB_ID_NECK_TILT; i <= ICUB_ID_EYES_VERGENCE; i++) { |
| 322 |
set_target_in_velocitymode(i); |
| 323 |
} |
| 324 |
/*
|
| 325 |
// eyelids: unfortuantely the icub has only 1dof for eyelids
|
| 326 |
// therefore we can only use an opening value
|
| 327 |
float opening_left = target_angle_[ICUB_ID_EYES_LEFT_LID_UPPER]
|
| 328 |
- target_angle_[ICUB_ID_EYES_LEFT_LID_LOWER];
|
| 329 |
float opening_right = target_angle_[ICUB_ID_EYES_RIGHT_LID_UPPER]
|
| 330 |
- target_angle_[ICUB_ID_EYES_RIGHT_LID_LOWER];
|
| 331 |
float opening = (opening_left + opening_right) / 2.0;
|
| 332 |
// send it to icub face if
|
| 333 |
face_interface_->set_eyelid_angle(opening);
|
| 334 |
|
| 335 |
//eyebrows are set using a special command as well:
|
| 336 |
face_interface_->set_eyebrow_angle(ICUB_ID_EYES_LEFT_BROW, target_angle_);
|
| 337 |
face_interface_->set_eyebrow_angle(ICUB_ID_EYES_RIGHT_BROW, target_angle_);
|
| 338 |
|
| 339 |
//mouth
|
| 340 |
face_interface_->set_mouth(target_angle_);
|
| 341 |
*/
|
| 342 |
|
| 343 |
// store joint values which we do not handle on icub here:
|
| 344 |
double timestamp = humotion::Timestamp::now().to_seconds();
|
| 345 |
JointInterface::store_incoming_position(ID_LIP_LEFT_UPPER, |
| 346 |
target_angle_[ICUB_ID_LIP_LEFT_UPPER], timestamp); |
| 347 |
JointInterface::store_incoming_position(ID_LIP_LEFT_LOWER, |
| 348 |
target_angle_[ICUB_ID_LIP_LEFT_LOWER], timestamp); |
| 349 |
JointInterface::store_incoming_position(ID_LIP_CENTER_UPPER, |
| 350 |
target_angle_[ICUB_ID_LIP_CENTER_UPPER], timestamp); |
| 351 |
JointInterface::store_incoming_position(ID_LIP_CENTER_LOWER, |
| 352 |
target_angle_[ICUB_ID_LIP_CENTER_LOWER], timestamp); |
| 353 |
JointInterface::store_incoming_position(ID_LIP_RIGHT_UPPER, |
| 354 |
target_angle_[ICUB_ID_LIP_RIGHT_UPPER], timestamp); |
| 355 |
JointInterface::store_incoming_position(ID_LIP_RIGHT_LOWER, |
| 356 |
target_angle_[ICUB_ID_LIP_RIGHT_LOWER], timestamp); |
| 357 |
} |
| 358 |
|
| 359 |
|
| 360 |
void iCubJointInterface::set_joint_enable_state(int humotion_id, bool enable) { |
| 361 |
int icub_jointid = convert_humotion_jointid_to_icub(humotion_id);
|
| 362 |
/*
|
| 363 |
switch(e){
|
| 364 |
default:
|
| 365 |
break;
|
| 366 |
|
| 367 |
case(ID_NECK_PAN):
|
| 368 |
icub_jointid = ICUB_ID_NECK_PAN;
|
| 369 |
break;
|
| 370 |
|
| 371 |
case(ID_NECK_TILT):
|
| 372 |
icub_jointid = ICUB_ID_NECK_TILT;
|
| 373 |
break;
|
| 374 |
|
| 375 |
case(ID_NECK_ROLL):
|
| 376 |
icub_jointid = ICUB_ID_NECK_ROLL;
|
| 377 |
break;
|
| 378 |
|
| 379 |
case(ID_EYES_BOTH_UD):
|
| 380 |
icub_jointid = ICUB_ID_EYES_BOTH_UD;
|
| 381 |
break;
|
| 382 |
|
| 383 |
// icub handles eyes as pan angle + vergence...
|
| 384 |
// -> hack: left eye enables pan and right eye enables vergence
|
| 385 |
case(ID_EYES_LEFT_LR):
|
| 386 |
icub_jointid = ICUB_ID_EYES_PAN;
|
| 387 |
break;
|
| 388 |
|
| 389 |
case(ID_EYES_RIGHT_LR):
|
| 390 |
icub_jointid = ICUB_ID_EYES_VERGENCE;
|
| 391 |
break;
|
| 392 |
}
|
| 393 |
*/
|
| 394 |
|
| 395 |
if ((icub_jointid != -1) && (icub_jointid <= ICUB_ID_EYES_VERGENCE)) { |
| 396 |
if (enable) {
|
| 397 |
yarp_amp_->enableAmp(icub_jointid); |
| 398 |
yarp_pid_->enablePid(icub_jointid); |
| 399 |
} else {
|
| 400 |
yarp_pid_->disablePid(icub_jointid); |
| 401 |
yarp_amp_->disableAmp(icub_jointid); |
| 402 |
} |
| 403 |
} |
| 404 |
} |
| 405 |
|
| 406 |
//! prepare and enable a joint
|
| 407 |
//! NOTE: this should also prefill the min/max positions for this joint
|
| 408 |
//! \param the enum id of a joint
|
| 409 |
void iCubJointInterface::enable_joint(int e) { |
| 410 |
set_joint_enable_state(e, true);
|
| 411 |
} |
| 412 |
|
| 413 |
//! shutdown and disable a joint
|
| 414 |
//! \param the enum id of a joint
|
| 415 |
void iCubJointInterface::disable_joint(int e) { |
| 416 |
set_joint_enable_state(e, false);
|
| 417 |
} |
| 418 |
|
| 419 |
void iCubJointInterface::store_min_max(yarp::dev::IControlLimits *ilimits, int icub_id) { |
| 420 |
double min, max;
|
| 421 |
int humotion_id = convert_icub_jointid_to_humotion(icub_id);
|
| 422 |
|
| 423 |
ilimits->getLimits(icub_id, &min, &max); |
| 424 |
joint_min[humotion_id] = min; |
| 425 |
joint_max[humotion_id] = max; |
| 426 |
} |
| 427 |
|
| 428 |
//! initialise a joint (set up controller mode etc)
|
| 429 |
void iCubJointInterface::init_joints() {
|
| 430 |
store_min_max(yarp_ilimits_, ICUB_ID_NECK_TILT); |
| 431 |
store_min_max(yarp_ilimits_, ICUB_ID_NECK_ROLL); |
| 432 |
store_min_max(yarp_ilimits_, ICUB_ID_NECK_PAN); |
| 433 |
store_min_max(yarp_ilimits_, ICUB_ID_EYES_BOTH_UD); |
| 434 |
|
| 435 |
// icub handles eyes differently, we have to set pan angle + vergence
|
| 436 |
double pan_min, pan_max, vergence_min, vergence_max;
|
| 437 |
yarp_ilimits_->getLimits(ICUB_ID_EYES_PAN, &pan_min, &pan_max); |
| 438 |
yarp_ilimits_->getLimits(ICUB_ID_EYES_VERGENCE, &vergence_min, &vergence_max); |
| 439 |
|
| 440 |
// this is not 100% correct, should be fixed
|
| 441 |
joint_min[ID_EYES_LEFT_LR] = pan_min; // - vergence_max/2;
|
| 442 |
joint_max[ID_EYES_LEFT_LR] = pan_max; // - vergence_max/2;
|
| 443 |
joint_min[ID_EYES_RIGHT_LR] = joint_min[ID_EYES_LEFT_LR]; |
| 444 |
joint_max[ID_EYES_RIGHT_LR] = joint_max[ID_EYES_LEFT_LR]; |
| 445 |
|
| 446 |
// eyelids
|
| 447 |
joint_min[ID_EYES_RIGHT_LID_UPPER] = -50; // 24-30; |
| 448 |
joint_max[ID_EYES_RIGHT_LID_UPPER] = 50; // 48-30; |
| 449 |
// lid_angle = joint_max[ID_EYES_RIGHT_LID_UPPER];
|
| 450 |
|
| 451 |
// eyebrows
|
| 452 |
joint_min[ID_EYES_LEFT_BROW] = -50;
|
| 453 |
joint_max[ID_EYES_LEFT_BROW] = 50;
|
| 454 |
joint_min[ID_EYES_RIGHT_BROW] = joint_min[ID_EYES_LEFT_BROW]; |
| 455 |
joint_max[ID_EYES_RIGHT_BROW] = joint_max[ID_EYES_LEFT_BROW]; |
| 456 |
|
| 457 |
// mouth
|
| 458 |
joint_min[ID_LIP_CENTER_UPPER] = 5;
|
| 459 |
joint_max[ID_LIP_CENTER_UPPER] = 50;
|
| 460 |
joint_min[ID_LIP_CENTER_LOWER] = 5;
|
| 461 |
joint_max[ID_LIP_CENTER_LOWER] = 50;
|
| 462 |
joint_min[ID_LIP_LEFT_UPPER] = 5;
|
| 463 |
joint_max[ID_LIP_LEFT_UPPER] = 50;
|
| 464 |
joint_min[ID_LIP_LEFT_LOWER] = 5;
|
| 465 |
joint_max[ID_LIP_LEFT_LOWER] = 50;
|
| 466 |
joint_min[ID_LIP_RIGHT_UPPER] = 5;
|
| 467 |
joint_max[ID_LIP_RIGHT_UPPER] = 50;
|
| 468 |
joint_min[ID_LIP_RIGHT_LOWER] = 5;
|
| 469 |
joint_max[ID_LIP_RIGHT_LOWER] = 50;
|
| 470 |
} |
| 471 |
|
| 472 |
//! conversion table for humotion joint id to icub joint id
|
| 473 |
//! \param int value for humotion joint id from JointInterface::JOINT_ID_ENUM
|
| 474 |
//! \return int value of icub joint id
|
| 475 |
int iCubJointInterface::convert_humotion_jointid_to_icub(int humotion_id) { |
| 476 |
enum_id_bimap_t::right_const_iterator it = enum_id_bimap.right.find(humotion_id); |
| 477 |
if (it == enum_id_bimap.right.end()) {
|
| 478 |
// key does not exist
|
| 479 |
cerr << "ERROR: invalid humotion joint id (" << humotion_id <<
|
| 480 |
") given. can not convert this. exiting\n";
|
| 481 |
exit(EXIT_FAILURE); |
| 482 |
} |
| 483 |
return it->second;
|
| 484 |
} |
| 485 |
|
| 486 |
|
| 487 |
//! conversion table for icub joint id to humotion joint id
|
| 488 |
//! \param int value of icub joint id
|
| 489 |
//! \return int value of humotion joint id from JointInterface::JOINT_ID_ENUM
|
| 490 |
int iCubJointInterface::convert_icub_jointid_to_humotion(int icub_id) { |
| 491 |
enum_id_bimap_t::left_const_iterator it = enum_id_bimap.left.find(icub_id); |
| 492 |
if (it == enum_id_bimap.left.end()) {
|
| 493 |
// key does not exist
|
| 494 |
cout << "ERROR: invalid icub joint id given. can not convert this. exiting\n";
|
| 495 |
exit(EXIT_FAILURE); |
| 496 |
} |
| 497 |
return it->second;
|
| 498 |
} |
| 499 |
|