1 #ifndef CANOPEN_MOTOR_NODE_HANDLE_LAYER_H_ 2 #define CANOPEN_MOTOR_NODE_HANDLE_LAYER_H_ 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> 24 virtual void reset() = 0;
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){
39 if(!entry.get(val))
return false;
43 operator double*()
const {
return val_ptr.get(); }
45 boost::unordered_map<ObjectDict::Key, Getter>
getters_;
54 boost::mutex::scoped_lock lock(mutex_);
56 for(boost::unordered_map<canopen::ObjectDict::Key, Getter>::iterator it = getters_.begin(); it != getters_.end(); ++it){
57 ok = it->second() && ok;
62 boost::mutex::scoped_lock lock(mutex_);
64 if(n.find(
"obj") == 0){
66 boost::unordered_map<ObjectDict::Key, Getter>::const_iterator it = getters_.find(key);
67 if(it != getters_.end())
return it->second;
71 catch(
const std::exception &e){
72 ROS_ERROR_STREAM(
"Could not find variable '" << n <<
"', reason: " << boost::diagnostic_information(e));
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; }
92 boost::scoped_ptr<UnitConverter> conv_pos_,
conv_vel_, conv_eff_;
99 boost::atomic<hardware_interface::JointHandle*>
jh_;
102 typedef boost::unordered_map< MotorBase::OperationMode,hardware_interface::JointHandle* >
CommandMap;
107 bool supported =
false;
108 for(
size_t i=0; i < modes.size(); ++i){
109 if(motor_->isModeSupported(modes[i])){
114 if(!supported)
return 0;
116 iface.registerHandle(*jh);
118 for(
size_t i=0; i < modes.size(); ++i){
119 commands_[modes[i]] = jh;
125 std::vector<LimitsHandleBaseSharedPtr>
limits_;
129 static double *
assignVariable(
const std::string &name,
double * ptr,
const std::string &req) {
return name == req ? ptr : 0; }
149 void enableLimits(
bool enable);
boost::shared_ptr< HandleLayer > HandleLayerSharedPtr
static bool readObject(ObjectStorage::Entry< T > &entry, double &res)
boost::function< bool(double &)> func
virtual void handleDiag(canopen::LayerReport &report)
hardware_interface::JointHandle * addHandle(T &iface, hardware_interface::JointHandle *jh, const std::vector< MotorBase::OperationMode > &modes)
virtual ~LimitsHandleBase()
std::vector< LimitsHandleBaseSharedPtr > limits_
boost::shared_ptr< double > val_ptr
virtual void handleHalt(canopen::LayerStatus &status)
virtual void enforce(const ros::Duration &period)=0
boost::scoped_ptr< UnitConverter > conv_vel_
static double * assignVariable(const std::string &name, double *ptr, const std::string &req)
XmlRpc::XmlRpcValue options_
void registerHandle(hardware_interface::JointStateInterface &iface)
const ObjectStorageSharedPtr storage_
filters::FilterChain< double > filter_vel_
hardware_interface::JointHandle jvh_
virtual void handleRecover(canopen::LayerStatus &status)
canopen::MotorBaseSharedPtr motor_
boost::shared_ptr< LimitsHandleBase > Ptr ROS_DEPRECATED
boost::unordered_map< ObjectDict::Key, Getter > getters_
static double * func(ObjectVariables &list, const canopen::ObjectDict::Key &key)
static R * branch_type(const uint16_t data_type)
virtual void handleShutdown(canopen::LayerStatus &status)
ObjectVariables(const ObjectStorageSharedPtr storage)
boost::shared_ptr< LimitsHandleBase > LimitsHandleBaseSharedPtr
boost::atomic< hardware_interface::JointHandle * > jh_
void registerHandle(const JointStateHandle &handle)
boost::scoped_ptr< UnitConverter > conv_target_vel_
Getter(const ObjectStorage::Entry< T > &entry)
boost::atomic< bool > forward_command_
hardware_interface::JointStateHandle jsh_
boost::unordered_map< MotorBase::OperationMode, hardware_interface::JointHandle * > CommandMap
#define ROS_ERROR_STREAM(args)
double * getVariable(const std::string &n)
ObjectVariables variables_