00001
00010 #include "SoftErrorLimiter.h"
00011 #include "hrpsys/util/VectorConvert.h"
00012 #include "hrpsys/idl/RobotHardwareService.hh"
00013 #include <rtm/CorbaNaming.h>
00014 #include <hrpModel/ModelLoaderUtil.h>
00015
00016 #include <math.h>
00017 #include <vector>
00018 #include <limits>
00019 #include <iomanip>
00020 #define deg2rad(x)((x)*M_PI/180)
00021
00022
00023
00024 static const char* softerrorlimiter_spec[] =
00025 {
00026 "implementation_id", "SoftErrorLimiter",
00027 "type_name", "SoftErrorLimiter",
00028 "description", "soft error limiter",
00029 "version", HRPSYS_PACKAGE_VERSION,
00030 "vendor", "AIST",
00031 "category", "example",
00032 "activity_type", "DataFlowComponent",
00033 "max_instance", "10",
00034 "language", "C++",
00035 "lang_type", "compile",
00036
00037 "conf.default.debugLevel", "0",
00038 ""
00039 };
00040
00041
00042 static std::ostream& operator<<(std::ostream& os, const struct RTC::Time &tm)
00043 {
00044 int pre = os.precision();
00045 os.setf(std::ios::fixed);
00046 os << std::setprecision(6)
00047 << (tm.sec + tm.nsec/1e9)
00048 << std::setprecision(pre);
00049 os.unsetf(std::ios::fixed);
00050 return os;
00051 }
00052
00053 SoftErrorLimiter::SoftErrorLimiter(RTC::Manager* manager)
00054 : RTC::DataFlowComponentBase(manager),
00055
00056 m_qRefIn("qRef", m_qRef),
00057 m_qCurrentIn("qCurrent", m_qCurrent),
00058 m_servoStateIn("servoStateIn", m_servoState),
00059 m_qOut("q", m_qRef),
00060 m_servoStateOut("servoStateOut", m_servoState),
00061 m_beepCommandOut("beepCommand", m_beepCommand),
00062 m_SoftErrorLimiterServicePort("SoftErrorLimiterService"),
00063
00064 m_debugLevel(0),
00065 dummy(0),
00066 is_beep_port_connected(false)
00067 {
00068 init_beep();
00069 start_beep(3136);
00070 }
00071
00072 SoftErrorLimiter::~SoftErrorLimiter()
00073 {
00074 quit_beep();
00075 }
00076
00077
00078
00079 RTC::ReturnCode_t SoftErrorLimiter::onInitialize()
00080 {
00081 std::cerr << "[" << m_profile.instance_name << "] onInitialize()" << std::endl;
00082
00083
00084 bindParameter("debugLevel", m_debugLevel, "0");
00085
00086
00087
00088
00089
00090
00091 addInPort("qRef", m_qRefIn);
00092 addInPort("qCurrent", m_qCurrentIn);
00093 addInPort("servoState", m_servoStateIn);
00094
00095
00096 addOutPort("q", m_qOut);
00097 addOutPort("servoState", m_servoStateOut);
00098 addOutPort("beepCommand", m_beepCommandOut);
00099
00100
00101 m_SoftErrorLimiterServicePort.registerProvider("service0", "SoftErrorLimiterService", m_service0);
00102
00103
00104
00105
00106 addPort(m_SoftErrorLimiterServicePort);
00107
00108
00109
00110 m_robot = boost::shared_ptr<robot>(new robot());
00111 RTC::Properties& prop = getProperties();
00112
00113 RTC::Manager& rtcManager = RTC::Manager::instance();
00114 std::string nameServer = rtcManager.getConfig()["corba.nameservers"];
00115 int comPos = nameServer.find(",");
00116 if (comPos < 0){
00117 comPos = nameServer.length();
00118 }
00119 nameServer = nameServer.substr(0, comPos);
00120 RTC::CorbaNaming naming(rtcManager.getORB(), nameServer.c_str());
00121 if (!loadBodyFromModelLoader(m_robot, prop["model"].c_str(),
00122 CosNaming::NamingContext::_duplicate(naming.getRootContext())
00123 )){
00124 std::cerr << "[" << m_profile.instance_name << "] failed to load model[" << prop["model"] << "] in "
00125 << m_profile.instance_name << std::endl;
00126 return RTC::RTC_ERROR;
00127 }
00128
00129 std::cout << "[" << m_profile.instance_name << "] dof = " << m_robot->numJoints() << std::endl;
00130 if (!m_robot->init()) return RTC::RTC_ERROR;
00131 m_service0.setRobot(m_robot);
00132 m_servoState.data.length(m_robot->numJoints());
00133 for(unsigned int i = 0; i < m_robot->numJoints(); i++) {
00134 m_servoState.data[i].length(1);
00135 int status = 0;
00136 status |= 1<< OpenHRP::RobotHardwareService::CALIB_STATE_SHIFT;
00137 status |= 1<< OpenHRP::RobotHardwareService::POWER_STATE_SHIFT;
00138 status |= 1<< OpenHRP::RobotHardwareService::SERVO_STATE_SHIFT;
00139 status |= 0<< OpenHRP::RobotHardwareService::SERVO_ALARM_SHIFT;
00140 status |= 0<< OpenHRP::RobotHardwareService::DRIVER_TEMP_SHIFT;
00141 m_servoState.data[i][0] = status;
00142 }
00143
00144
00145 coil::stringTo(dt, prop["dt"].c_str());
00146 soft_limit_error_beep_freq = static_cast<int>(1.0/(4.0*dt));
00147 position_limit_error_beep_freq = static_cast<int>(1.0/(2.0*dt));
00148 debug_print_freq = static_cast<int>(0.2/dt);
00149
00150
00151 m_beepCommand.data.length(bc.get_num_beep_info());
00152
00153
00154 hrp::readJointLimitTableFromProperties (joint_limit_tables, m_robot, prop["joint_limit_table"], std::string(m_profile.instance_name));
00155
00156 return RTC::RTC_OK;
00157 }
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180 RTC::ReturnCode_t SoftErrorLimiter::onActivated(RTC::UniqueId ec_id)
00181 {
00182 std::cerr << "[" << m_profile.instance_name<< "] onActivated(" << ec_id << ")" << std::endl;
00183 return RTC::RTC_OK;
00184 }
00185
00186 RTC::ReturnCode_t SoftErrorLimiter::onDeactivated(RTC::UniqueId ec_id)
00187 {
00188 std::cerr << "[" << m_profile.instance_name<< "] onDeactivated(" << ec_id << ")" << std::endl;
00189 return RTC::RTC_OK;
00190 }
00191
00192 RTC::ReturnCode_t SoftErrorLimiter::onExecute(RTC::UniqueId ec_id)
00193 {
00194
00195 static int loop = 0;
00196 static bool debug_print_velocity_first = false;
00197 static bool debug_print_position_first = false;
00198 static bool debug_print_error_first = false;
00199 loop ++;
00200
00201
00202
00203
00204 if (!is_beep_port_connected && (loop % 500 == 0) ) {
00205 if ( m_beepCommandOut.connectors().size() > 0 ) {
00206 is_beep_port_connected = true;
00207 quit_beep();
00208 std::cerr << "[" << m_profile.instance_name<< "] beepCommand data port connection found! Use BeeperRTC." << std::endl;
00209 }
00210 }
00211
00212 if (m_qRefIn.isNew()) {
00213 m_qRefIn.read();
00214 }
00215 if (m_qCurrentIn.isNew()) {
00216 m_qCurrentIn.read();
00217 }
00218 if (m_servoStateIn.isNew()) {
00219 m_servoStateIn.read();
00220 }
00221
00222
00223
00224
00225
00226
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236 bool soft_limit_error = false;
00237 bool velocity_limit_error = false;
00238 bool position_limit_error = false;
00239 if ( m_qRef.data.length() == m_qCurrent.data.length() &&
00240 m_qRef.data.length() == m_servoState.data.length() ) {
00241
00242 static std::vector<double> prev_angle;
00243 if ( prev_angle.size() != m_qRef.data.length() ) {
00244 prev_angle.resize(m_qRef.data.length(), 0);
00245 for ( unsigned int i = 0; i < m_qRef.data.length(); i++ ){
00246 prev_angle[i] = m_qCurrent.data[i];
00247 }
00248 }
00249 std::vector<int> servo_state;
00250 servo_state.resize(m_qRef.data.length(), 0);
00251 for ( unsigned int i = 0; i < m_qRef.data.length(); i++ ){
00252 servo_state[i] = (m_servoState.data[i][0] & OpenHRP::RobotHardwareService::SERVO_STATE_MASK) >> OpenHRP::RobotHardwareService::SERVO_STATE_SHIFT;
00253 }
00254
00255
00256
00257
00258
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272 for ( unsigned int i = 0; i < m_qRef.data.length(); i++ ){
00273
00274
00275
00276
00277 double total_upper_limit = std::numeric_limits<double>::max(), total_lower_limit = -std::numeric_limits<double>::max();
00278 {
00279 double qvel = (m_qRef.data[i] - prev_angle[i]) / dt;
00280 double lvlimit = m_robot->joint(i)->lvlimit + 0.000175;
00281 double uvlimit = m_robot->joint(i)->uvlimit - 0.000175;
00282
00283 if ( servo_state[i] == 1 && (lvlimit < uvlimit) && ((lvlimit > qvel) || (uvlimit < qvel)) ) {
00284 if (loop % debug_print_freq == 0 || debug_print_velocity_first ) {
00285 std::cerr << "[" << m_profile.instance_name<< "] [" << m_qRef.tm
00286 << "] velocity limit over " << m_robot->joint(i)->name << "(" << i << "), qvel=" << qvel
00287 << ", lvlimit =" << lvlimit
00288 << ", uvlimit =" << uvlimit
00289 << ", servo_state = " << ( servo_state[i] ? "ON" : "OFF") << std::endl;
00290 }
00291
00292 if ( lvlimit > qvel ) {
00293 total_lower_limit = std::max(prev_angle[i] + lvlimit * dt, total_lower_limit);
00294 }
00295 if ( uvlimit < qvel ) {
00296 total_upper_limit = std::min(prev_angle[i] + uvlimit * dt, total_upper_limit);
00297 }
00298 velocity_limit_error = true;
00299 }
00300 }
00301
00302
00303 {
00304 double llimit = m_robot->joint(i)->llimit;
00305 double ulimit = m_robot->joint(i)->ulimit;
00306 if (joint_limit_tables.find(m_robot->joint(i)->name) != joint_limit_tables.end()) {
00307 std::map<std::string, hrp::JointLimitTable>::iterator it = joint_limit_tables.find(m_robot->joint(i)->name);
00308 llimit = it->second.getLlimit(m_qRef.data[it->second.getTargetJointId()]);
00309 ulimit = it->second.getUlimit(m_qRef.data[it->second.getTargetJointId()]);
00310 }
00311
00312 bool servo_limit_state = (llimit < ulimit) && ((llimit > m_qRef.data[i]) || (ulimit < m_qRef.data[i]));
00313 if ( servo_state[i] == 1 && servo_limit_state ) {
00314 if (loop % debug_print_freq == 0 || debug_print_position_first) {
00315 std::cerr << "[" << m_profile.instance_name<< "] [" << m_qRef.tm
00316 << "] position limit over " << m_robot->joint(i)->name << "(" << i << "), qRef=" << m_qRef.data[i]
00317 << ", llimit =" << llimit
00318 << ", ulimit =" << ulimit
00319 << ", servo_state = " << ( servo_state[i] ? "ON" : "OFF")
00320 << ", prev_angle = " << prev_angle[i] << std::endl;
00321 }
00322
00323 if ( llimit > m_qRef.data[i] && prev_angle[i] > m_qRef.data[i] ) {
00324 total_lower_limit = std::max(llimit, total_lower_limit);
00325 }
00326 if ( ulimit < m_qRef.data[i] && prev_angle[i] < m_qRef.data[i] ) {
00327 total_upper_limit = std::min(ulimit, total_upper_limit);
00328 }
00329 m_servoState.data[i][0] |= (0x200 << OpenHRP::RobotHardwareService::SERVO_ALARM_SHIFT);
00330 position_limit_error = true;
00331 }
00332 }
00333
00334
00335
00336
00337 {
00338 double pos_vel_limited_angle = std::min(total_upper_limit, std::max(total_lower_limit, m_qRef.data[i]));
00339 double limit = m_robot->m_servoErrorLimit[i];
00340 double error = pos_vel_limited_angle - m_qCurrent.data[i];
00341 if ( servo_state[i] == 1 && fabs(error) > limit ) {
00342 if (loop % debug_print_freq == 0 || debug_print_error_first ) {
00343 std::cerr << "[" << m_profile.instance_name<< "] [" << m_qRef.tm
00344 << "] error limit over " << m_robot->joint(i)->name << "(" << i << "), qRef=" << pos_vel_limited_angle
00345 << ", qCurrent=" << m_qCurrent.data[i] << " "
00346 << ", Error=" << error << " > " << limit << " (limit)"
00347 << ", servo_state = " << ( 1 ? "ON" : "OFF");
00348 }
00349 if ( error > limit ) {
00350 total_upper_limit = std::min(m_qCurrent.data[i] + limit, total_upper_limit);
00351 } else {
00352 total_lower_limit = std::max(m_qCurrent.data[i] - limit, total_lower_limit);
00353 }
00354 if (loop % debug_print_freq == 0 || debug_print_error_first ) {
00355 std::cerr << ", q=" << m_qRef.data[i] << std::endl;
00356 }
00357 m_servoState.data[i][0] |= (0x040 << OpenHRP::RobotHardwareService::SERVO_ALARM_SHIFT);
00358 soft_limit_error = true;
00359 }
00360 }
00361
00362
00363 prev_angle[i] = m_qRef.data[i] = std::min(total_upper_limit, std::max(total_lower_limit, m_qRef.data[i]));
00364 }
00365
00366 debug_print_velocity_first = !velocity_limit_error;
00367 debug_print_position_first = !position_limit_error;
00368 debug_print_error_first = !soft_limit_error;
00369
00370
00371 if ( soft_limit_error ) {
00372 if (is_beep_port_connected) {
00373 if ( loop % soft_limit_error_beep_freq == 0 ) bc.startBeep(3136, soft_limit_error_beep_freq*0.8);
00374 else bc.stopBeep();
00375 } else {
00376 if ( loop % soft_limit_error_beep_freq == 0 ) start_beep(3136, soft_limit_error_beep_freq*0.8);
00377 }
00378 }else if ( position_limit_error || velocity_limit_error ) {
00379 if (is_beep_port_connected) {
00380 if ( loop % position_limit_error_beep_freq == 0 ) bc.startBeep(3520, position_limit_error_beep_freq*0.8);
00381 else bc.stopBeep();
00382 } else {
00383 if ( loop % position_limit_error_beep_freq == 0 ) start_beep(3520, position_limit_error_beep_freq*0.8);
00384 }
00385 } else {
00386 if (is_beep_port_connected) {
00387 bc.stopBeep();
00388 } else {
00389 stop_beep();
00390 }
00391 }
00392 m_qOut.write();
00393 m_servoStateOut.write();
00394 } else {
00395 if (is_beep_port_connected) {
00396 bc.startBeep(3136);
00397 } else {
00398 start_beep(3136);
00399 }
00400 if ( loop % 100 == 1 ) {
00401 std::cerr << "SoftErrorLimiter is not working..." << std::endl;
00402 std::cerr << " m_qRef " << m_qRef.data.length() << std::endl;
00403 std::cerr << " m_qCurrent " << m_qCurrent.data.length() << std::endl;
00404 std::cerr << " m_servoState " << m_servoState.data.length() << std::endl;
00405 }
00406 }
00407 if (is_beep_port_connected) {
00408 bc.setDataPort(m_beepCommand);
00409 if (bc.isWritable()) m_beepCommandOut.write();
00410 }
00411
00412 return RTC::RTC_OK;
00413 }
00414
00415
00416
00417
00418
00419
00420
00421
00422
00423
00424
00425
00426
00427
00428
00429
00430
00431
00432
00433
00434
00435
00436
00437
00438
00439
00440
00441
00442
00443
00444
00445
00446
00447
00448
00449
00450
00451
00452 extern "C"
00453 {
00454
00455 void SoftErrorLimiterInit(RTC::Manager* manager)
00456 {
00457 RTC::Properties profile(softerrorlimiter_spec);
00458 manager->registerFactory(profile,
00459 RTC::Create<SoftErrorLimiter>,
00460 RTC::Delete<SoftErrorLimiter>);
00461 }
00462
00463 };
00464
00465