2 #ifndef CANOPEN_MOTOR_NODE_UNIT_CONVERTER_H_     3 #define CANOPEN_MOTOR_NODE_UNIT_CONVERTER_H_     7 #include <boost/function.hpp>     8 #include <boost/shared_ptr.hpp>    10 #include <boost/math/special_functions/fpclassify.hpp>     15     typedef boost::function<double * (const std::string &) > get_var_func_type 
__attribute__((deprecated));
    23         parser_.DefineConst(
"pi", M_PI);
    24         parser_.DefineConst(
"nan", std::numeric_limits<double>::quiet_NaN());
    37             **it = std::numeric_limits<double>::quiet_NaN();
    49             p = 
new double(std::numeric_limits<double>::quiet_NaN());
    65     static double norm(
double val, 
double min, 
double max){
    66         while(val >= max) val -= (max-min);
    67         while(val < min) val += (max-min);
    70     static double smooth(
double val, 
double old_val, 
double alpha){
    71         if(boost::math::isnan(val)) 
return 0;
    72         if(boost::math::isnan(old_val)) 
return val;
    73         return alpha*val + (1.0-alpha)*old_val;
    75     static double avg(
const double *vals, 
int num)
    80             const double &val = vals[i];
    81             if(boost::math::isnan(val)) 
break;
    84         return s / double(i+1);
 std::list< variable_ptr > variable_ptr_list
static double deg2rad(double d)
boost::function< double *(const std::string &) > GetVarFuncType
static double * createVariable(const char *name, void *userdata)
static double smooth(double val, double old_val, double alpha)
static double rad2deg(double r)
boost::shared_ptr< double > variable_ptr
UnitConverter(const std::string &expression, GetVarFuncType var_func)
static double avg(const double *vals, int num)
static double norm(double val, double min, double max)
boost::function< double *(const std::string &) > get_var_func_type __attribute__((deprecated))
variable_ptr_list var_list_