31 #ifndef GPIOPIDCONFIGURATOR_H 32 #define GPIOPICCONFIGURATOR_H 35 #include <dynamic_reconfigure/server.h> 37 #include <roboteq_control/RoboteqPIDConfig.h> 73 dynamic_reconfigure::Server<roboteq_control::RoboteqPIDConfig> *
ds_pid;
79 void reconfigureCBPID(roboteq_control::RoboteqPIDConfig &config, uint32_t level);
90 #endif // GPIOPICCONFIGURATOR_H void reconfigureCBPID(roboteq_control::RoboteqPIDConfig &config, uint32_t level)
reconfigureCBEncoder when the dynamic reconfigurator change some values start this method ...
dynamic_reconfigure::Server< roboteq_control::RoboteqPIDConfig > * ds_pid
Dynamic reconfigure PID.
ros::NodeHandle nh_
Private namespace.
roboteq_control::RoboteqPIDConfig _last_pid_config
roboteq::serial_controller * mSerial
Serial port.
void setPIDconfiguration()
string mName
Associate name space.
void getPIDFromRoboteq()
getPIDFromRoboteq Load PID parameters from Roboteq board
roboteq_control::RoboteqPIDConfig default_pid_config
unsigned int mNumber
Number motor.
MotorPIDConfigurator(const ros::NodeHandle &nh, roboteq::serial_controller *serial, string path, string name, unsigned int number)
MotorPIDConfigurator Initialize the dynamic reconfigurator.
bool setup_pid
Setup variable.
void initConfigurator(bool load_from_board)