00001
00002 #include <canopen_motor_node/handle_layer.h>
00003 #include "interface_mapping.h"
00004
00005 using namespace canopen;
00006
00007
00008 template<typename T > class LimitsHandle {
00009 T limits_handle_;
00010 public:
00011 LimitsHandle(const T &handle) : limits_handle_(handle) {}
00012 virtual void enforce(const ros::Duration &period) { limits_handle_.enforceLimits(period); }
00013 virtual void reset() {}
00014 };
00015
00016 template<> void LimitsHandle<joint_limits_interface::PositionJointSaturationHandle>::reset() { limits_handle_.reset(); }
00017 template<>void LimitsHandle<joint_limits_interface::PositionJointSoftLimitsHandle>::reset() { limits_handle_.reset(); }
00018
00019 bool HandleLayer::select(const MotorBase::OperationMode &m){
00020 CommandMap::iterator it = commands_.find(m);
00021 if(it == commands_.end()) return false;
00022 jh_ = it->second;
00023 return true;
00024 }
00025
00026 HandleLayer::HandleLayer(const std::string &name, const boost::shared_ptr<MotorBase> & motor, const boost::shared_ptr<ObjectStorage> storage, XmlRpc::XmlRpcValue & options)
00027 : HandleLayerBase(name + " Handle"), motor_(motor), variables_(storage), jsh_(name, &pos_, &vel_, &eff_), jph_(jsh_, &cmd_pos_), jvh_(jsh_, &cmd_vel_), jeh_(jsh_, &cmd_eff_), jh_(0), forward_command_(false),
00028 filter_pos_("double"), filter_vel_("double"), filter_eff_("double"), options_(options), enable_limits_(true)
00029 {
00030 commands_[MotorBase::No_Mode] = 0;
00031
00032 std::string p2d("rint(rad2deg(pos)*1000)"), v2d("rint(rad2deg(vel)*1000)"), e2d("rint(eff)");
00033 std::string p2r("deg2rad(obj6064)/1000"), v2r("deg2rad(obj606C)/1000"), e2r("0");
00034
00035 if(options.hasMember("pos_unit_factor") || options.hasMember("vel_unit_factor") || options.hasMember("eff_unit_factor")){
00036 const std::string reason("*_unit_factor parameters are not supported anymore, please migrate to conversion functions.");
00037 ROS_FATAL_STREAM(reason);
00038 throw std::invalid_argument(reason);
00039 }
00040
00041 if(options.hasMember("pos_to_device")) p2d = (const std::string&) options["pos_to_device"];
00042 if(options.hasMember("pos_from_device")) p2r = (const std::string&) options["pos_from_device"];
00043
00044 if(options.hasMember("vel_to_device")) v2d = (const std::string&) options["vel_to_device"];
00045 if(options.hasMember("vel_from_device")) v2r = (const std::string&) options["vel_from_device"];
00046
00047 if(options.hasMember("eff_to_device")) e2d = (const std::string&) options["eff_to_device"];
00048 if(options.hasMember("eff_from_device")) e2r = (const std::string&) options["eff_from_device"];
00049
00050 conv_target_pos_.reset(new UnitConverter(p2d, boost::bind(assignVariable, "pos", &cmd_pos_, _1)));
00051 conv_target_vel_.reset(new UnitConverter(v2d, boost::bind(assignVariable, "vel", &cmd_vel_, _1)));
00052 conv_target_eff_.reset(new UnitConverter(e2d, boost::bind(assignVariable, "eff", &cmd_eff_, _1)));
00053
00054 conv_pos_.reset(new UnitConverter(p2r, boost::bind(&ObjectVariables::getVariable, &variables_, _1)));
00055 conv_vel_.reset(new UnitConverter(v2r, boost::bind(&ObjectVariables::getVariable, &variables_, _1)));
00056 conv_eff_.reset(new UnitConverter(e2r, boost::bind(&ObjectVariables::getVariable, &variables_, _1)));
00057 }
00058
00059 HandleLayer::CanSwitchResult HandleLayer::canSwitch(const MotorBase::OperationMode &m){
00060 if(!motor_->isModeSupported(m) || commands_.find(m) == commands_.end()){
00061 return NotSupported;
00062 }else if(motor_->getMode() == m){
00063 return NoNeedToSwitch;
00064 }else if(motor_->getLayerState() == Ready){
00065 return ReadyToSwitch;
00066 }else{
00067 return NotReadyToSwitch;
00068 }
00069 }
00070
00071 bool HandleLayer::switchMode(const MotorBase::OperationMode &m){
00072 if(motor_->getMode() != m){
00073 forward_command_ = false;
00074 jh_ = 0;
00075 if(!motor_->enterModeAndWait(m)){
00076 ROS_ERROR_STREAM(jsh_.getName() << "could not enter mode " << (int)m);
00077 LayerStatus s;
00078 motor_->halt(s);
00079 return false;
00080 }
00081 }
00082 return select(m);
00083 }
00084
00085 bool HandleLayer::forwardForMode(const MotorBase::OperationMode &m){
00086 if(motor_->getMode() == m){
00087 forward_command_ = true;
00088 return true;
00089 }
00090 return false;
00091 }
00092
00093
00094 template<typename T> void addLimitsHandle(std::vector<LimitsHandleBase::Ptr> &limits, const T &t) {
00095 limits.push_back(LimitsHandleBase::Ptr( (LimitsHandleBase *) new LimitsHandle<T> (t) ));
00096 }
00097
00098 hardware_interface::JointHandle* HandleLayer::registerHandle(hardware_interface::PositionJointInterface &iface,
00099 const joint_limits_interface::JointLimits &limits,
00100 const joint_limits_interface::SoftJointLimits *soft_limits){
00101 hardware_interface::JointHandle* h = addHandle(iface, &jph_, g_interface_mapping.getInterfaceModes("hardware_interface::PositionJointInterface"));
00102 if(h && limits.has_position_limits){
00103 addLimitsHandle(limits_, joint_limits_interface::PositionJointSaturationHandle(*h, limits));
00104 if(soft_limits){
00105 addLimitsHandle(limits_, joint_limits_interface::PositionJointSoftLimitsHandle(*h, limits, *soft_limits));
00106 }
00107 }
00108 return h;
00109 }
00110
00111 hardware_interface::JointHandle* HandleLayer::registerHandle(hardware_interface::VelocityJointInterface &iface,
00112 const joint_limits_interface::JointLimits&limits,
00113 const joint_limits_interface::SoftJointLimits *soft_limits){
00114 hardware_interface::JointHandle* h = addHandle(iface, &jvh_, g_interface_mapping.getInterfaceModes("hardware_interface::VelocityJointInterface"));
00115 if(h && limits.has_velocity_limits){
00116 addLimitsHandle(limits_, joint_limits_interface::VelocityJointSaturationHandle(*h, limits));
00117 if(soft_limits){
00118 addLimitsHandle(limits_, joint_limits_interface::VelocityJointSoftLimitsHandle(*h, limits, *soft_limits));
00119 }
00120 }
00121 return h;
00122 }
00123
00124 hardware_interface::JointHandle* HandleLayer::registerHandle(hardware_interface::EffortJointInterface &iface,
00125 const joint_limits_interface::JointLimits&limits,
00126 const joint_limits_interface::SoftJointLimits *soft_limits){
00127 hardware_interface::JointHandle* h = addHandle(iface, &jeh_, g_interface_mapping.getInterfaceModes("hardware_interface::EffortJointInterface"));
00128 if(h && limits.has_effort_limits){
00129 addLimitsHandle(limits_, joint_limits_interface::EffortJointSaturationHandle(*h, limits));
00130 if(soft_limits){
00131 addLimitsHandle(limits_, joint_limits_interface::EffortJointSoftLimitsHandle(*h, limits, *soft_limits));
00132 }
00133 }
00134 return h;
00135 }
00136
00137 void HandleLayer::handleRead(LayerStatus &status, const LayerState ¤t_state) {
00138 if(current_state > Shutdown){
00139 variables_.sync();
00140 filter_pos_.update(conv_pos_->evaluate(), pos_);
00141 filter_vel_.update(conv_vel_->evaluate(), vel_);
00142 filter_eff_.update(conv_eff_->evaluate(), eff_);
00143 }
00144 }
00145 void HandleLayer::handleWrite(LayerStatus &status, const LayerState ¤t_state) {
00146 if(current_state == Ready){
00147 hardware_interface::JointHandle* jh = 0;
00148 if(forward_command_) jh = jh_;
00149
00150 if(jh == &jph_){
00151 motor_->setTarget(conv_target_pos_->evaluate());
00152 cmd_vel_ = vel_;
00153 cmd_eff_ = eff_;
00154 }else if(jh == &jvh_){
00155 motor_->setTarget(conv_target_vel_->evaluate());
00156 cmd_pos_ = pos_;
00157 cmd_eff_ = eff_;
00158 }else if(jh == &jeh_){
00159 motor_->setTarget(conv_target_eff_->evaluate());
00160 cmd_pos_ = pos_;
00161 cmd_vel_ = vel_;
00162 }else{
00163 cmd_pos_ = pos_;
00164 cmd_vel_ = vel_;
00165 cmd_eff_ = eff_;
00166 if(jh) status.warn("unsupported mode active");
00167 }
00168 }
00169 }
00170
00171 bool prepareFilter(const std::string& joint_name, const std::string& filter_name, filters::FilterChain<double> &filter, XmlRpc::XmlRpcValue & options, canopen::LayerStatus &status){
00172 filter.clear();
00173 if(options.hasMember(filter_name)){
00174 if(!filter.configure(options[filter_name],joint_name + "/" + filter_name)){
00175 status.error("could not configure " + filter_name+ " for " + joint_name);
00176 return false;
00177 }
00178 }
00179
00180 return true;
00181 }
00182
00183 bool HandleLayer::prepareFilters(canopen::LayerStatus &status){
00184 return prepareFilter(jsh_.getName(), "position_filters", filter_pos_, options_, status) &&
00185 prepareFilter(jsh_.getName(), "velocity_filters", filter_vel_, options_, status) &&
00186 prepareFilter(jsh_.getName(), "effort_filters", filter_eff_, options_, status);
00187 }
00188
00189 void HandleLayer::handleInit(LayerStatus &status){
00190
00191 conv_pos_->reset();
00192 conv_vel_->reset();
00193 conv_eff_->reset();
00194 conv_target_pos_->reset();
00195 conv_target_vel_->reset();
00196 conv_target_eff_->reset();
00197
00198
00199 if(prepareFilters(status))
00200 {
00201 handleRead(status, Layer::Ready);
00202 }
00203 }
00204
00205 void HandleLayer::enforceLimits(const ros::Duration &period, bool reset){
00206 for(std::vector<LimitsHandleBase::Ptr>::iterator it = limits_.begin(); it != limits_.end(); ++it){
00207 if(reset) (*it)->reset();
00208 if(enable_limits_) (*it)->enforce(period);
00209 }
00210 }
00211
00212 void HandleLayer::enableLimits(bool enable){
00213 enable_limits_ = enable;
00214 }