SoftErrorLimiter.cpp
Go to the documentation of this file.
00001 // -*- C++ -*-
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 // Module specification
00023 // <rtc-template block="module_spec">
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     // Configuration variables
00037     "conf.default.debugLevel", "0",
00038     ""
00039   };
00040 // </rtc-template>
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     // <rtc-template block="initializer">
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     // </rtc-template>
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   // <rtc-template block="bind_config">
00083   // Bind variables and configuration variable
00084   bindParameter("debugLevel", m_debugLevel, "0");
00085   
00086   // </rtc-template>
00087 
00088   // Registration: InPort/OutPort/Service
00089   // <rtc-template block="registration">
00090   // Set InPort buffers
00091   addInPort("qRef", m_qRefIn);
00092   addInPort("qCurrent", m_qCurrentIn);
00093   addInPort("servoState", m_servoStateIn);
00094   
00095   // Set OutPort buffer
00096   addOutPort("q", m_qOut);
00097   addOutPort("servoState", m_servoStateOut);
00098   addOutPort("beepCommand", m_beepCommandOut);
00099   
00100   // Set service provider to Ports
00101   m_SoftErrorLimiterServicePort.registerProvider("service0", "SoftErrorLimiterService", m_service0);
00102   
00103   // Set service consumers to Ports
00104   
00105   // Set CORBA Service Ports
00106   addPort(m_SoftErrorLimiterServicePort);
00107   
00108   // </rtc-template>
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   /* Calculate count for beep sound frequency */
00145   coil::stringTo(dt, prop["dt"].c_str());
00146   soft_limit_error_beep_freq = static_cast<int>(1.0/(4.0*dt)); // soft limit error => 4 times / 1[s]
00147   position_limit_error_beep_freq = static_cast<int>(1.0/(2.0*dt)); // position limit error => 2 times / 1[s]
00148   debug_print_freq = static_cast<int>(0.2/dt); // once per 0.2 [s]
00149   /* If you print debug message for all controller loop, please comment in here */
00150   // debug_print_freq = 1;
00151   m_beepCommand.data.length(bc.get_num_beep_info());
00152 
00153   // load joint limit table
00154   hrp::readJointLimitTableFromProperties (joint_limit_tables, m_robot, prop["joint_limit_table"], std::string(m_profile.instance_name));
00155 
00156   // read ignored joint
00157   m_joint_mask.resize(m_robot->numJoints(), false);
00158   coil::vstring ijoints = coil::split(prop["mask_joint_limit"], ",");
00159   for(int i = 0; i < ijoints.size(); i++) {
00160       hrp::Link *lk = m_robot->link(std::string(ijoints[i]));
00161       if((!!lk) && (lk->jointId >= 0)) {
00162           std::cout << "[" << m_profile.instance_name << "] "
00163                     << "disable ErrorLimit, joint : " << ijoints[i]
00164                     << " (id = " << lk->jointId << ")" << std::endl;
00165           m_joint_mask[lk->jointId] = true;
00166       }
00167   }
00168 
00169   return RTC::RTC_OK;
00170 }
00171 
00172 /*
00173 RTC::ReturnCode_t SoftErrorLimiter::onFinalize()
00174 {
00175   return RTC::RTC_OK;
00176 }
00177 */
00178 
00179 /*
00180 RTC::ReturnCode_t SoftErrorLimiter::onStartup(RTC::UniqueId ec_id)
00181 {
00182   return RTC::RTC_OK;
00183 }
00184 */
00185 
00186 /*
00187 RTC::ReturnCode_t SoftErrorLimiter::onShutdown(RTC::UniqueId ec_id)
00188 {
00189   return RTC::RTC_OK;
00190 }
00191 */
00192 
00193 RTC::ReturnCode_t SoftErrorLimiter::onActivated(RTC::UniqueId ec_id)
00194 {
00195   std::cerr << "[" << m_profile.instance_name<< "] onActivated(" << ec_id << ")" << std::endl;
00196   return RTC::RTC_OK;
00197 }
00198 
00199 RTC::ReturnCode_t SoftErrorLimiter::onDeactivated(RTC::UniqueId ec_id)
00200 {
00201   std::cerr << "[" << m_profile.instance_name<< "] onDeactivated(" << ec_id << ")" << std::endl;
00202   return RTC::RTC_OK;
00203 }
00204 
00205 RTC::ReturnCode_t SoftErrorLimiter::onExecute(RTC::UniqueId ec_id)
00206 {
00207   //std::cout << m_profile.instance_name<< ": onExecute(" << ec_id << ")" << std::endl;
00208   static int loop = 0;
00209   static bool debug_print_velocity_first = false;
00210   static bool debug_print_position_first = false;
00211   static bool debug_print_error_first = false;
00212   loop ++;
00213 
00214   // Connection check of m_beepCommand to BeeperRTC
00215   //   If m_beepCommand is not connected to BeeperRTC and sometimes, check connection.
00216   //   If once connection is found, never check connection.
00217   if (!is_beep_port_connected && (loop % 500 == 0) ) {
00218     if ( m_beepCommandOut.connectors().size() > 0 ) {
00219       is_beep_port_connected = true;
00220       quit_beep();
00221       std::cerr << "[" << m_profile.instance_name<< "] beepCommand data port connection found! Use BeeperRTC." << std::endl;
00222     }
00223   }
00224 
00225   if (m_qRefIn.isNew()) {
00226     m_qRefIn.read();
00227   }
00228   if (m_qCurrentIn.isNew()) {
00229     m_qCurrentIn.read();
00230   }
00231   if (m_servoStateIn.isNew()) {
00232     m_servoStateIn.read();
00233   }
00234 
00235   /*
00236     0x001 : 'SS_OVER_VOLTAGE',
00237     0x002 : 'SS_OVER_LOAD',
00238     0x004 : 'SS_OVER_VELOCITY',
00239     0x008 : 'SS_OVER_CURRENT',
00240     0x010 : 'SS_OVER_HEAT',
00241     0x020 : 'SS_TORQUE_LIMIT',
00242     0x040 : 'SS_VELOCITY_LIMIT',
00243     0x080 : 'SS_FORWARD_LIMIT',
00244     0x100 : 'SS_REVERSE_LIMIT',
00245     0x200 : 'SS_POSITION_ERROR',
00246     0x300 : 'SS_ENCODER_ERROR',
00247     0x800 : 'SS_OTHER'
00248   */
00249   bool soft_limit_error = false;
00250   bool velocity_limit_error = false;
00251   bool position_limit_error = false;
00252   if ( m_qRef.data.length() == m_qCurrent.data.length() &&
00253        m_qRef.data.length() == m_servoState.data.length() ) {
00254     // prev_angle is previous output
00255     static std::vector<double> prev_angle;
00256     if ( prev_angle.size() != m_qRef.data.length() ) { // initialize prev_angle
00257       prev_angle.resize(m_qRef.data.length(), 0);
00258       for ( unsigned int i = 0; i < m_qRef.data.length(); i++ ){
00259         prev_angle[i] = m_qCurrent.data[i];
00260       }
00261     }
00262     std::vector<int> servo_state;
00263     servo_state.resize(m_qRef.data.length(), 0);
00264     for ( unsigned int i = 0; i < m_qRef.data.length(); i++ ){
00265         servo_state[i] = (m_servoState.data[i][0] & OpenHRP::RobotHardwareService::SERVO_STATE_MASK) >> OpenHRP::RobotHardwareService::SERVO_STATE_SHIFT; // enum SwitchStatus {SWITCH_ON, SWITCH_OFF};
00266     }
00267 
00268       /*
00269         From hrpModel/Body.h
00270         inline Link* joint(int id) const
00271            This function returns a link that has a given joint ID.
00272            If there is no link that has a given joint ID,
00273            the function returns a dummy link object whose ID is minus one.
00274            The maximum id can be obtained by numJoints().
00275 
00276          inline Link* link(int index) const
00277            This function returns the link of a given index in the whole link sequence.
00278            The order of the sequence corresponds to a link-tree traverse from the root link.
00279            The size of the sequence can be obtained by numLinks().
00280 
00281          So use m_robot->joint(i) for llimit/ulimit, lvlimit/ulimit
00282        */
00283 
00284     // Velocity limitation for reference joint angles
00285     for ( unsigned int i = 0; i < m_qRef.data.length(); i++ ){
00286       if(m_joint_mask[i]) continue;
00287       // Determin total upper-lower limit considering velocity, position, and error limits.
00288       // e.g.,
00289       //  total lower limit = max (vel, pos, err) <= severest lower limit
00290       //  total upper limit = min (vel, pos, err) <= severest upper limit
00291       double total_upper_limit = std::numeric_limits<double>::max(), total_lower_limit = -std::numeric_limits<double>::max();
00292       {
00293       double qvel = (m_qRef.data[i] - prev_angle[i]) / dt;
00294       double lvlimit = m_robot->joint(i)->lvlimit + 0.000175; // 0.01 deg / sec
00295       double uvlimit = m_robot->joint(i)->uvlimit - 0.000175;
00296       // fixed joint has ulimit = vlimit
00297       if ( servo_state[i] == 1 && (lvlimit < uvlimit) && ((lvlimit > qvel) || (uvlimit < qvel)) ) {
00298         if (loop % debug_print_freq == 0 || debug_print_velocity_first ) {
00299           std::cerr << "[" << m_profile.instance_name<< "] [" << m_qRef.tm
00300                     << "] velocity limit over " << m_robot->joint(i)->name << "(" << i << "), qvel=" << qvel
00301                     << ", lvlimit =" << lvlimit
00302                     << ", uvlimit =" << uvlimit
00303                     << ", servo_state = " <<  ( servo_state[i] ? "ON" : "OFF");
00304         }
00305         double limited;
00306         // fix joint angle
00307         if ( lvlimit > qvel ) {
00308             limited = total_lower_limit = std::max(prev_angle[i] + lvlimit * dt, total_lower_limit);
00309         }
00310         if ( uvlimit < qvel ) {
00311             limited = total_upper_limit = std::min(prev_angle[i] + uvlimit * dt, total_upper_limit);
00312         }
00313         if (loop % debug_print_freq == 0 || debug_print_velocity_first ) {
00314             std::cerr << ", q(limited) = " << limited << std::endl;
00315         }
00316         velocity_limit_error = true;
00317       }
00318       }
00319 
00320       // Position limitation for reference joint angles
00321       {
00322       double llimit = m_robot->joint(i)->llimit;
00323       double ulimit = m_robot->joint(i)->ulimit;
00324       if (joint_limit_tables.find(m_robot->joint(i)->name) != joint_limit_tables.end()) {
00325           std::map<std::string, hrp::JointLimitTable>::iterator it = joint_limit_tables.find(m_robot->joint(i)->name);
00326           llimit = it->second.getLlimit(m_qRef.data[it->second.getTargetJointId()]);
00327           ulimit = it->second.getUlimit(m_qRef.data[it->second.getTargetJointId()]);
00328       }
00329       // fixed joint have vlimit = ulimit
00330       bool servo_limit_state = (llimit < ulimit) && ((llimit > m_qRef.data[i]) || (ulimit < m_qRef.data[i]));
00331       if ( servo_state[i] == 1 && servo_limit_state ) {
00332         if (loop % debug_print_freq == 0 || debug_print_position_first) {
00333           std::cerr << "[" << m_profile.instance_name<< "] [" << m_qRef.tm
00334                     << "] position limit over " << m_robot->joint(i)->name << "(" << i << "), qRef=" << m_qRef.data[i]
00335                     << ", llimit =" << llimit
00336                     << ", ulimit =" << ulimit
00337                     << ", servo_state = " <<  ( servo_state[i] ? "ON" : "OFF")
00338                     << ", prev_angle = " << prev_angle[i];
00339         }
00340         double limited;
00341         // fix joint angle
00342         if ( llimit > m_qRef.data[i] && prev_angle[i] > m_qRef.data[i] ) { // ref < llimit and prev < ref -> OK
00343             limited = total_lower_limit = std::max(llimit, total_lower_limit);
00344         }
00345         if ( ulimit < m_qRef.data[i] && prev_angle[i] < m_qRef.data[i] ) { // ulimit < ref and ref < prev -> OK
00346             limited = total_upper_limit = std::min(ulimit, total_upper_limit);
00347         }
00348         if (loop % debug_print_freq == 0 || debug_print_position_first ) {
00349             std::cerr << ", q(limited) = " << limited << std::endl;
00350         }
00351         m_servoState.data[i][0] |= (0x200 << OpenHRP::RobotHardwareService::SERVO_ALARM_SHIFT);
00352         position_limit_error = true;
00353       }
00354       }
00355 
00356       // Servo error limitation between reference joint angles and actual joint angles
00357       //   pos_vel_limited_angle is current output joint angle which arleady finished position limit and velocity limit.
00358       //   Check and limit error between pos_vel_limited_angle and current actual joint angle.
00359       {
00360       double pos_vel_limited_angle = std::min(total_upper_limit, std::max(total_lower_limit, m_qRef.data[i]));
00361       double limit = m_robot->m_servoErrorLimit[i];
00362       double error = pos_vel_limited_angle - m_qCurrent.data[i];
00363       if ( servo_state[i] == 1 && fabs(error) > limit ) {
00364         if (loop % debug_print_freq == 0 || debug_print_error_first ) {
00365           std::cerr << "[" << m_profile.instance_name<< "] [" << m_qRef.tm
00366                     << "] error limit over " << m_robot->joint(i)->name << "(" << i << "), qRef=" << pos_vel_limited_angle
00367                     << ", qCurrent=" << m_qCurrent.data[i] << " "
00368                     << ", Error=" << error << " > " << limit << " (limit)"
00369                     << ", servo_state = " <<  ( 1 ? "ON" : "OFF");
00370         }
00371         double limited;
00372         if ( error > limit ) {
00373             limited = total_upper_limit = std::min(m_qCurrent.data[i] + limit, total_upper_limit);
00374         } else {
00375             limited = total_lower_limit = std::max(m_qCurrent.data[i] - limit, total_lower_limit);
00376         }
00377         if (loop % debug_print_freq == 0 || debug_print_error_first ) {
00378           std::cerr << ", q(limited) = " << limited << std::endl;
00379         }
00380         m_servoState.data[i][0] |= (0x040 << OpenHRP::RobotHardwareService::SERVO_ALARM_SHIFT);
00381         soft_limit_error = true;
00382       }
00383       }
00384 
00385       // Limitation of current output considering total upper and lower limits
00386       prev_angle[i] = m_qRef.data[i] = std::min(total_upper_limit, std::max(total_lower_limit, m_qRef.data[i]));
00387     }
00388     // display error info if no error found
00389     debug_print_velocity_first = !velocity_limit_error;
00390     debug_print_position_first = !position_limit_error;
00391     debug_print_error_first = !soft_limit_error;
00392 
00393     // Beep sound
00394     if ( soft_limit_error ) { // play beep
00395       if (is_beep_port_connected) {
00396         if ( loop % soft_limit_error_beep_freq == 0 ) bc.startBeep(3136, soft_limit_error_beep_freq*0.8);
00397         else bc.stopBeep();
00398       } else {
00399         if ( loop % soft_limit_error_beep_freq == 0 ) start_beep(3136, soft_limit_error_beep_freq*0.8);
00400       }
00401     }else if ( position_limit_error || velocity_limit_error ) { // play beep
00402       if (is_beep_port_connected) {
00403         if ( loop % position_limit_error_beep_freq == 0 ) bc.startBeep(3520, position_limit_error_beep_freq*0.8);
00404         else bc.stopBeep();
00405       } else {
00406         if ( loop % position_limit_error_beep_freq == 0 ) start_beep(3520, position_limit_error_beep_freq*0.8);
00407       }
00408     } else {
00409       if (is_beep_port_connected) {
00410         bc.stopBeep();
00411       } else {
00412         stop_beep();
00413       }
00414     }
00415     m_qOut.write();
00416     m_servoStateOut.write();
00417   } else {
00418     if (is_beep_port_connected) {
00419       bc.startBeep(3136);
00420     } else {
00421       start_beep(3136);
00422     }
00423     if ( loop % 100 == 1 ) {
00424         std::cerr << "SoftErrorLimiter is not working..." << std::endl;
00425         std::cerr << "         m_qRef " << m_qRef.data.length() << std::endl;
00426         std::cerr << "     m_qCurrent " << m_qCurrent.data.length() << std::endl;
00427         std::cerr << "   m_servoState " << m_servoState.data.length() << std::endl;
00428     }
00429   }
00430   if (is_beep_port_connected) {
00431     bc.setDataPort(m_beepCommand);
00432     if (bc.isWritable()) m_beepCommandOut.write();
00433   }
00434 
00435   return RTC::RTC_OK;
00436 }
00437 
00438 /*
00439 RTC::ReturnCode_t SoftErrorLimiter::onAborting(RTC::UniqueId ec_id)
00440 {
00441   return RTC::RTC_OK;
00442 }
00443 */
00444 
00445 /*
00446 RTC::ReturnCode_t SoftErrorLimiter::onError(RTC::UniqueId ec_id)
00447 {
00448   return RTC::RTC_OK;
00449 }
00450 */
00451 
00452 /*
00453 RTC::ReturnCode_t SoftErrorLimiter::onReset(RTC::UniqueId ec_id)
00454 {
00455   return RTC::RTC_OK;
00456 }
00457 */
00458 
00459 /*
00460 RTC::ReturnCode_t SoftErrorLimiter::onStateUpdate(RTC::UniqueId ec_id)
00461 {
00462   return RTC::RTC_OK;
00463 }
00464 */
00465 
00466 /*
00467 RTC::ReturnCode_t SoftErrorLimiter::onRateChanged(RTC::UniqueId ec_id)
00468 {
00469   return RTC::RTC_OK;
00470 }
00471 */
00472 
00473 
00474 
00475 extern "C"
00476 {
00477 
00478   void SoftErrorLimiterInit(RTC::Manager* manager)
00479   {
00480     RTC::Properties profile(softerrorlimiter_spec);
00481     manager->registerFactory(profile,
00482                              RTC::Create<SoftErrorLimiter>,
00483                              RTC::Delete<SoftErrorLimiter>);
00484   }
00485 
00486 };
00487 
00488 


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:19