handle_layer.h
Go to the documentation of this file.
1 #ifndef CANOPEN_MOTOR_NODE_HANDLE_LAYER_H_
2 #define CANOPEN_MOTOR_NODE_HANDLE_LAYER_H_
3 
4 #include <boost/atomic.hpp>
5 #include <boost/bind.hpp>
6 #include <boost/unordered_map.hpp>
7 #include <boost/scoped_ptr.hpp>
8 #include <boost/thread/mutex.hpp>
9 #include <filters/filter_chain.h>
13 #include <canopen_master/objdict.h>
14 #include <canopen_master/layer.h>
15 #include <canopen_402/base.h>
18 
19 namespace canopen {
20 
22 public:
23  virtual void enforce(const ros::Duration &period) = 0;
24  virtual void reset() = 0;
25  virtual ~LimitsHandleBase();
27 };
29 
32  struct Getter {
34  boost::function<bool(double&)> func;
35  bool operator ()() { return func(*val_ptr); }
36  template<typename T> Getter(const ObjectStorage::Entry<T> &entry): func(boost::bind(&Getter::readObject<T>, entry, _1)), val_ptr(new double) { }
37  template<typename T> static bool readObject(ObjectStorage::Entry<T> &entry, double &res){
38  T val;
39  if(!entry.get(val)) return false;
40  res = val;
41  return true;
42  }
43  operator double*() const { return val_ptr.get(); }
44  };
45  boost::unordered_map<ObjectDict::Key, Getter> getters_;
46  boost::mutex mutex_;
47 public:
48  template<const uint16_t dt> static double* func(ObjectVariables &list, const canopen::ObjectDict::Key &key){
49  typedef typename ObjectStorage::DataType<dt>::type type;
50  return list.getters_.insert(std::make_pair(key, Getter(list.storage_->entry<type>(key)))).first->second;
51  }
52  ObjectVariables(const ObjectStorageSharedPtr storage) : storage_(storage) {}
53  bool sync(){
54  boost::mutex::scoped_lock lock(mutex_);
55  bool ok = true;
56  for(boost::unordered_map<canopen::ObjectDict::Key, Getter>::iterator it = getters_.begin(); it != getters_.end(); ++it){
57  ok = it->second() && ok;
58  }
59  return ok;
60  }
61  double * getVariable(const std::string &n) {
62  boost::mutex::scoped_lock lock(mutex_);
63  try{
64  if(n.find("obj") == 0){
65  canopen::ObjectDict::Key key(n.substr(3));
66  boost::unordered_map<ObjectDict::Key, Getter>::const_iterator it = getters_.find(key);
67  if(it != getters_.end()) return it->second;
68  return canopen::branch_type<ObjectVariables, double * (ObjectVariables &list, const canopen::ObjectDict::Key &k)>(storage_->dict_->get(key)->data_type)(*this, key);
69  }
70  }
71  catch( const std::exception &e){
72  ROS_ERROR_STREAM("Could not find variable '" << n << "', reason: " << boost::diagnostic_information(e));
73  }
74  return 0;
75  }
76 };
77 
78 template<> inline double* ObjectVariables::func<canopen::ObjectDict::DEFTYPE_VISIBLE_STRING >(ObjectVariables &, const canopen::ObjectDict::Key &){ return 0; }
79 template<> inline double* ObjectVariables::func<canopen::ObjectDict::DEFTYPE_OCTET_STRING >(ObjectVariables &, const canopen::ObjectDict::Key &){ return 0; }
80 template<> inline double* ObjectVariables::func<canopen::ObjectDict::DEFTYPE_UNICODE_STRING >(ObjectVariables &, const canopen::ObjectDict::Key &){ return 0; }
81 template<> inline double* ObjectVariables::func<canopen::ObjectDict::DEFTYPE_DOMAIN >(ObjectVariables &, const canopen::ObjectDict::Key &){ return 0; }
82 
83 
86  double pos_, vel_, eff_;
87 
88  double cmd_pos_, cmd_vel_, cmd_eff_;
89 
90  ObjectVariables variables_;
91  boost::scoped_ptr<UnitConverter> conv_target_pos_, conv_target_vel_, conv_target_eff_;
92  boost::scoped_ptr<UnitConverter> conv_pos_, conv_vel_, conv_eff_;
93 
94  filters::FilterChain<double> filter_pos_, filter_vel_, filter_eff_;
96 
99  boost::atomic<hardware_interface::JointHandle*> jh_;
100  boost::atomic<bool> forward_command_;
101 
102  typedef boost::unordered_map< MotorBase::OperationMode,hardware_interface::JointHandle* > CommandMap;
103  CommandMap commands_;
104 
105  template <typename T> hardware_interface::JointHandle* addHandle( T &iface, hardware_interface::JointHandle *jh, const std::vector<MotorBase::OperationMode> & modes){
106 
107  bool supported = false;
108  for(size_t i=0; i < modes.size(); ++i){
109  if(motor_->isModeSupported(modes[i])){
110  supported = true;
111  break;
112  }
113  }
114  if(!supported) return 0;
115 
116  iface.registerHandle(*jh);
117 
118  for(size_t i=0; i < modes.size(); ++i){
119  commands_[modes[i]] = jh;
120  }
121  return jh;
122  }
123 
124  bool select(const canopen::MotorBase::OperationMode &m);
125  std::vector<LimitsHandleBaseSharedPtr> limits_;
127 public:
128  HandleLayer(const std::string &name, const canopen::MotorBaseSharedPtr & motor, const canopen::ObjectStorageSharedPtr storage, XmlRpc::XmlRpcValue & options);
129  static double * assignVariable(const std::string &name, double * ptr, const std::string &req) { return name == req ? ptr : 0; }
130 
132  bool switchMode(const canopen::MotorBase::OperationMode &m);
133  bool forwardForMode(const canopen::MotorBase::OperationMode &m);
134 
136  iface.registerHandle(jsh_);
137  }
140  const joint_limits_interface::SoftJointLimits *soft_limits = 0);
143  const joint_limits_interface::SoftJointLimits *soft_limits = 0);
146  const joint_limits_interface::SoftJointLimits *soft_limits = 0);
147 
148  void enforceLimits(const ros::Duration &period, bool reset);
149  void enableLimits(bool enable);
150 
151  bool prepareFilters(canopen::LayerStatus &status);
152 
153 private:
154  virtual void handleRead(canopen::LayerStatus &status, const LayerState &current_state);
155  virtual void handleWrite(canopen::LayerStatus &status, const LayerState &current_state);
156  virtual void handleInit(canopen::LayerStatus &status);
157  virtual void handleDiag(canopen::LayerReport &report) { /* nothing to do */ }
158  virtual void handleShutdown(canopen::LayerStatus &status) { /* nothing to do */ }
159  virtual void handleHalt(canopen::LayerStatus &status) { /* TODO */ }
160  virtual void handleRecover(canopen::LayerStatus &status) { /* nothing to do */ }
161 
162 };
163 
165 
166 } // namespace canopen
167 
168 
169 
170 #endif /* INCLUDE_CANOPEN_MOTOR_NODE_HANDLE_LAYER_H_ */
boost::shared_ptr< HandleLayer > HandleLayerSharedPtr
Definition: handle_layer.h:164
static bool readObject(ObjectStorage::Entry< T > &entry, double &res)
Definition: handle_layer.h:37
boost::function< bool(double &)> func
Definition: handle_layer.h:34
virtual void handleDiag(canopen::LayerReport &report)
Definition: handle_layer.h:157
hardware_interface::JointHandle * addHandle(T &iface, hardware_interface::JointHandle *jh, const std::vector< MotorBase::OperationMode > &modes)
Definition: handle_layer.h:105
std::vector< LimitsHandleBaseSharedPtr > limits_
Definition: handle_layer.h:125
boost::shared_ptr< double > val_ptr
Definition: handle_layer.h:33
virtual void handleHalt(canopen::LayerStatus &status)
Definition: handle_layer.h:159
virtual void reset()=0
virtual void enforce(const ros::Duration &period)=0
boost::scoped_ptr< UnitConverter > conv_vel_
Definition: handle_layer.h:92
static double * assignVariable(const std::string &name, double *ptr, const std::string &req)
Definition: handle_layer.h:129
XmlRpc::XmlRpcValue options_
Definition: handle_layer.h:95
void registerHandle(hardware_interface::JointStateInterface &iface)
Definition: handle_layer.h:135
const ObjectStorageSharedPtr storage_
Definition: handle_layer.h:31
filters::FilterChain< double > filter_vel_
Definition: handle_layer.h:94
hardware_interface::JointHandle jvh_
Definition: handle_layer.h:98
virtual void handleRecover(canopen::LayerStatus &status)
Definition: handle_layer.h:160
canopen::MotorBaseSharedPtr motor_
Definition: handle_layer.h:85
boost::shared_ptr< LimitsHandleBase > Ptr ROS_DEPRECATED
Definition: handle_layer.h:26
boost::unordered_map< ObjectDict::Key, Getter > getters_
Definition: handle_layer.h:45
static double * func(ObjectVariables &list, const canopen::ObjectDict::Key &key)
Definition: handle_layer.h:48
ROSCPP_DECL bool ok()
static R * branch_type(const uint16_t data_type)
virtual void handleShutdown(canopen::LayerStatus &status)
Definition: handle_layer.h:158
ObjectVariables(const ObjectStorageSharedPtr storage)
Definition: handle_layer.h:52
boost::shared_ptr< LimitsHandleBase > LimitsHandleBaseSharedPtr
Definition: handle_layer.h:28
boost::atomic< hardware_interface::JointHandle * > jh_
Definition: handle_layer.h:99
void registerHandle(const JointStateHandle &handle)
boost::scoped_ptr< UnitConverter > conv_target_vel_
Definition: handle_layer.h:91
Getter(const ObjectStorage::Entry< T > &entry)
Definition: handle_layer.h:36
boost::atomic< bool > forward_command_
Definition: handle_layer.h:100
hardware_interface::JointStateHandle jsh_
Definition: handle_layer.h:97
boost::unordered_map< MotorBase::OperationMode, hardware_interface::JointHandle * > CommandMap
Definition: handle_layer.h:102
#define ROS_ERROR_STREAM(args)
double * getVariable(const std::string &n)
Definition: handle_layer.h:61
ObjectVariables variables_
Definition: handle_layer.h:90


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Sat May 4 2019 02:40:47