motor_pid.h
Go to the documentation of this file.
1 
31 #ifndef GPIOPIDCONFIGURATOR_H
32 #define GPIOPICCONFIGURATOR_H
33 
34 #include <ros/ros.h>
35 #include <dynamic_reconfigure/server.h>
36 
37 #include <roboteq_control/RoboteqPIDConfig.h>
38 
40 
42 {
43 public:
52  MotorPIDConfigurator(const ros::NodeHandle& nh, roboteq::serial_controller *serial, string path, string name, unsigned int number);
53 
54  void initConfigurator(bool load_from_board);
55 
56  void setPIDconfiguration();
57 
58 private:
60  bool setup_pid;
61 
63  string mName;
64  string mType;
66  unsigned int mNumber;
71 
73  dynamic_reconfigure::Server<roboteq_control::RoboteqPIDConfig> *ds_pid;
79  void reconfigureCBPID(roboteq_control::RoboteqPIDConfig &config, uint32_t level);
80 
81  // Default parameter config
82  roboteq_control::RoboteqPIDConfig default_pid_config, _last_pid_config;
83 
87  void getPIDFromRoboteq();
88 };
89 
90 #endif // GPIOPICCONFIGURATOR_H
void reconfigureCBPID(roboteq_control::RoboteqPIDConfig &config, uint32_t level)
reconfigureCBEncoder when the dynamic reconfigurator change some values start this method ...
Definition: motor_pid.cpp:172
dynamic_reconfigure::Server< roboteq_control::RoboteqPIDConfig > * ds_pid
Dynamic reconfigure PID.
Definition: motor_pid.h:73
ros::NodeHandle nh_
Private namespace.
Definition: motor_pid.h:68
roboteq_control::RoboteqPIDConfig _last_pid_config
Definition: motor_pid.h:82
roboteq::serial_controller * mSerial
Serial port.
Definition: motor_pid.h:70
string mName
Associate name space.
Definition: motor_pid.h:63
void getPIDFromRoboteq()
getPIDFromRoboteq Load PID parameters from Roboteq board
Definition: motor_pid.cpp:63
roboteq_control::RoboteqPIDConfig default_pid_config
Definition: motor_pid.h:82
unsigned int mNumber
Number motor.
Definition: motor_pid.h:66
MotorPIDConfigurator(const ros::NodeHandle &nh, roboteq::serial_controller *serial, string path, string name, unsigned int number)
MotorPIDConfigurator Initialize the dynamic reconfigurator.
Definition: motor_pid.cpp:33
bool setup_pid
Setup variable.
Definition: motor_pid.h:60
void initConfigurator(bool load_from_board)
Definition: motor_pid.cpp:48


roboteq_control
Author(s): Raffaello Bonghi
autogenerated on Wed Jan 3 2018 03:48:23