31 #ifndef GPIOANALOGCONFIGURATOR_H 32 #define GPIOANALOGCONFIGURATOR_H 36 #include <roboteq_control/RoboteqAnalogInputConfig.h> 37 #include <dynamic_reconfigure/server.h> 80 std::vector<roboteq::Motor *>
_motor;
83 dynamic_reconfigure::Server<roboteq_control::RoboteqAnalogInputConfig> *
ds_param;
89 void reconfigureCBParam(roboteq_control::RoboteqAnalogInputConfig &config, uint32_t level);
100 #endif // GPIOANALOGCONFIGURATOR_H
bool setup_param
Setup variable.
void initConfigurator(bool load_from_board)
initConfigurator Initialize all parameter and syncronize parameters between ros and roboteq board ...
dynamic_reconfigure::Server< roboteq_control::RoboteqAnalogInputConfig > * ds_param
Dynamic reconfigure parameters.
void reconfigureCBParam(roboteq_control::RoboteqAnalogInputConfig &config, uint32_t level)
reconfigureCBParam when the dynamic reconfigurator change some values start this method ...
roboteq::serial_controller * mSerial
Serial port.
double getConversion(double reduction)
getConversion Get conversion from pulse value to real value
unsigned int mNumber
Number motor.
std::vector< roboteq::Motor * > _motor
string mName
Associate name space.
roboteq_control::RoboteqAnalogInputConfig default_param_config
roboteq_control::RoboteqAnalogInputConfig _last_param_config
ros::NodeHandle nh_
Private namespace.
GPIOAnalogConfigurator(const ros::NodeHandle &nh, roboteq::serial_controller *serial, std::vector< roboteq::Motor * > motor, string name, unsigned int number)
GPIOAnalogConfigurator.
void getParamFromRoboteq()
getParamFromRoboteq Load parameters from Roboteq board