handle_layer.h
Go to the documentation of this file.
00001 #ifndef CANOPEN_MOTOR_NODE_HANDLE_LAYER_H_
00002 #define CANOPEN_MOTOR_NODE_HANDLE_LAYER_H_
00003 
00004 #include <boost/atomic.hpp>
00005 #include <boost/bind.hpp>
00006 #include <boost/unordered_map.hpp>
00007 #include <boost/scoped_ptr.hpp>
00008 #include <boost/thread/mutex.hpp>
00009 #include <filters/filter_chain.h>
00010 #include <hardware_interface/joint_command_interface.h>
00011 #include <hardware_interface/joint_state_interface.h>
00012 #include <joint_limits_interface/joint_limits_interface.h>
00013 #include <canopen_master/objdict.h>
00014 #include <canopen_master/layer.h>
00015 #include <canopen_402/base.h>
00016 #include <canopen_motor_node/unit_converter.h>
00017 #include <canopen_motor_node/handle_layer_base.h>
00018 
00019 namespace canopen {
00020 
00021 class LimitsHandleBase {
00022 public:
00023     virtual void enforce(const ros::Duration &period) = 0;
00024     virtual void reset() = 0;
00025     virtual ~LimitsHandleBase();
00026     typedef boost::shared_ptr<LimitsHandleBase> Ptr;
00027 };
00028 
00029 
00030 class ObjectVariables {
00031     const boost::shared_ptr<ObjectStorage> storage_;
00032     struct Getter {
00033         boost::shared_ptr<double> val_ptr;
00034         boost::function<bool(double&)> func;
00035         bool operator ()() { return func(*val_ptr); }
00036         template<typename T> Getter(const ObjectStorage::Entry<T> &entry): func(boost::bind(&Getter::readObject<T>, entry, _1)), val_ptr(new double) { }
00037         template<typename T> static bool readObject(ObjectStorage::Entry<T> &entry, double &res){
00038             T val;
00039             if(!entry.get(val)) return false;
00040             res = val;
00041             return true;
00042         }
00043         operator double*() const { return val_ptr.get(); }
00044     };
00045     boost::unordered_map<ObjectDict::Key, Getter> getters_;
00046     boost::mutex mutex_;
00047 public:
00048     template<const uint16_t dt> static double* func(ObjectVariables &list, const canopen::ObjectDict::Key &key){
00049         typedef typename ObjectStorage::DataType<dt>::type type;
00050         return list.getters_.insert(std::make_pair(key, Getter(list.storage_->entry<type>(key)))).first->second;
00051     }
00052     ObjectVariables(const boost::shared_ptr<ObjectStorage> storage) : storage_(storage) {}
00053     bool sync(){
00054         boost::mutex::scoped_lock lock(mutex_);
00055         bool ok = true;
00056         for(boost::unordered_map<canopen::ObjectDict::Key, Getter>::iterator it = getters_.begin(); it != getters_.end(); ++it){
00057             ok = it->second() && ok;
00058         }
00059         return ok;
00060     }
00061     double * getVariable(const std::string &n) {
00062         boost::mutex::scoped_lock lock(mutex_);
00063         try{
00064             if(n.find("obj") == 0){
00065                 canopen::ObjectDict::Key key(n.substr(3));
00066                 boost::unordered_map<ObjectDict::Key, Getter>::const_iterator it = getters_.find(key);
00067                 if(it != getters_.end()) return it->second;
00068                 return canopen::branch_type<ObjectVariables, double * (ObjectVariables &list, const canopen::ObjectDict::Key &k)>(storage_->dict_->get(key)->data_type)(*this, key);
00069             }
00070         }
00071         catch( const std::exception &e){
00072             ROS_ERROR_STREAM("Could not find variable '" << n << "', reason: " << boost::diagnostic_information(e));
00073         }
00074         return 0;
00075     }
00076 };
00077 
00078 template<> inline double* ObjectVariables::func<canopen::ObjectDict::DEFTYPE_VISIBLE_STRING >(ObjectVariables &, const canopen::ObjectDict::Key &){ return 0; }
00079 template<> inline double* ObjectVariables::func<canopen::ObjectDict::DEFTYPE_OCTET_STRING >(ObjectVariables &, const canopen::ObjectDict::Key &){ return 0; }
00080 template<> inline double* ObjectVariables::func<canopen::ObjectDict::DEFTYPE_UNICODE_STRING >(ObjectVariables &, const canopen::ObjectDict::Key &){ return 0; }
00081 template<> inline double* ObjectVariables::func<canopen::ObjectDict::DEFTYPE_DOMAIN >(ObjectVariables &, const canopen::ObjectDict::Key &){ return 0; }
00082 
00083 
00084 class HandleLayer: public canopen::HandleLayerBase {
00085     boost::shared_ptr<canopen::MotorBase> motor_;
00086     double pos_, vel_, eff_;
00087 
00088     double cmd_pos_, cmd_vel_, cmd_eff_;
00089 
00090     ObjectVariables variables_;
00091     boost::scoped_ptr<UnitConverter>  conv_target_pos_, conv_target_vel_, conv_target_eff_;
00092     boost::scoped_ptr<UnitConverter>  conv_pos_, conv_vel_, conv_eff_;
00093 
00094     filters::FilterChain<double> filter_pos_, filter_vel_, filter_eff_;
00095     XmlRpc::XmlRpcValue options_;
00096 
00097     hardware_interface::JointStateHandle jsh_;
00098     hardware_interface::JointHandle jph_, jvh_, jeh_;
00099     boost::atomic<hardware_interface::JointHandle*> jh_;
00100     boost::atomic<bool> forward_command_;
00101 
00102     typedef boost::unordered_map< MotorBase::OperationMode,hardware_interface::JointHandle* > CommandMap;
00103     CommandMap commands_;
00104 
00105     template <typename T> hardware_interface::JointHandle* addHandle( T &iface, hardware_interface::JointHandle *jh,  const std::vector<MotorBase::OperationMode> & modes){
00106 
00107         bool supported = false;
00108         for(size_t i=0; i < modes.size(); ++i){
00109             if(motor_->isModeSupported(modes[i])){
00110                 supported = true;
00111                 break;
00112             }
00113         }
00114         if(!supported) return 0;
00115 
00116         iface.registerHandle(*jh);
00117 
00118         for(size_t i=0; i < modes.size(); ++i){
00119             commands_[modes[i]] = jh;
00120         }
00121         return jh;
00122     }
00123 
00124     bool select(const canopen::MotorBase::OperationMode &m);
00125     std::vector<LimitsHandleBase::Ptr> limits_;
00126     bool enable_limits_;
00127 public:
00128     HandleLayer(const std::string &name, const boost::shared_ptr<canopen::MotorBase> & motor, const boost::shared_ptr<canopen::ObjectStorage> storage,  XmlRpc::XmlRpcValue & options);
00129     static double * assignVariable(const std::string &name, double * ptr, const std::string &req) { return name == req ? ptr : 0; }
00130 
00131     CanSwitchResult canSwitch(const canopen::MotorBase::OperationMode &m);
00132     bool switchMode(const canopen::MotorBase::OperationMode &m);
00133     bool forwardForMode(const canopen::MotorBase::OperationMode &m);
00134 
00135     void registerHandle(hardware_interface::JointStateInterface &iface){
00136         iface.registerHandle(jsh_);
00137     }
00138     hardware_interface::JointHandle* registerHandle(hardware_interface::PositionJointInterface &iface,
00139                                                     const joint_limits_interface::JointLimits &limits,
00140                                                     const joint_limits_interface::SoftJointLimits *soft_limits = 0);
00141     hardware_interface::JointHandle* registerHandle(hardware_interface::VelocityJointInterface &iface,
00142                                                     const joint_limits_interface::JointLimits &limits,
00143                                                     const joint_limits_interface::SoftJointLimits *soft_limits = 0);
00144     hardware_interface::JointHandle* registerHandle(hardware_interface::EffortJointInterface &iface,
00145                                                     const joint_limits_interface::JointLimits &limits,
00146                                                     const joint_limits_interface::SoftJointLimits *soft_limits = 0);
00147 
00148     void enforceLimits(const ros::Duration &period, bool reset);
00149     void enableLimits(bool enable);
00150 
00151     bool prepareFilters(canopen::LayerStatus &status);
00152 
00153 private:
00154     virtual void handleRead(canopen::LayerStatus &status, const LayerState &current_state);
00155     virtual void handleWrite(canopen::LayerStatus &status, const LayerState &current_state);
00156     virtual void handleInit(canopen::LayerStatus &status);
00157     virtual void handleDiag(canopen::LayerReport &report) { /* nothing to do */ }
00158     virtual void handleShutdown(canopen::LayerStatus &status) { /* nothing to do */ }
00159     virtual void handleHalt(canopen::LayerStatus &status) { /* TODO */ }
00160     virtual void handleRecover(canopen::LayerStatus &status) { /* nothing to do */ }
00161 
00162 };
00163 
00164 }  // namespace canopen
00165 
00166 
00167 
00168 #endif /* INCLUDE_CANOPEN_MOTOR_NODE_HANDLE_LAYER_H_ */


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Sun Sep 3 2017 03:10:55