motor_param.h
Go to the documentation of this file.
1 
31 #ifndef GPIOPARAMCONFIGURATOR_H
32 #define GPIOPARAMCONFIGURATOR_H
33 
34 #include <ros/ros.h>
35 
36 #include <roboteq_control/RoboteqParameterConfig.h>
37 #include <roboteq_control/RoboteqEncoderConfig.h>
38 #include <roboteq_control/RoboteqPIDtypeConfig.h>
39 #include <dynamic_reconfigure/server.h>
40 
42 
44 {
45 public:
53  MotorParamConfigurator(const ros::NodeHandle& nh, roboteq::serial_controller *serial, std::string name, unsigned int number);
58  void initConfigurator(bool load_from_board);
59 
60  int getOperativeMode();
72  void setOperativeMode(int type);
73 
74 private:
77 
79  string mName;
81  unsigned int mNumber;
86 
88  dynamic_reconfigure::Server<roboteq_control::RoboteqParameterConfig> *ds_param;
94  void reconfigureCBParam(roboteq_control::RoboteqParameterConfig &config, uint32_t level);
95 
97  dynamic_reconfigure::Server<roboteq_control::RoboteqPIDtypeConfig> *ds_pid_type;
103  void reconfigureCBPIDtype(roboteq_control::RoboteqPIDtypeConfig &config, uint32_t level);
104 
105  // Default parameter config
106  roboteq_control::RoboteqParameterConfig default_param_config, _last_param_config;
107  roboteq_control::RoboteqPIDtypeConfig default_pid_type_config, _last_pid_type_config;
108 
112  void getParamFromRoboteq();
113 
114 };
115 
116 #endif // GPIOPARAMCONFIGURATOR_H
void reconfigureCBParam(roboteq_control::RoboteqParameterConfig &config, uint32_t level)
reconfigureCBParam when the dynamic reconfigurator change some values start this method ...
void setOperativeMode(int type)
setOperativeMode Reference in page 321 - MMOD
Definition: motor_param.cpp:82
void reconfigureCBPIDtype(roboteq_control::RoboteqPIDtypeConfig &config, uint32_t level)
reconfigureCBEncoder when the dynamic reconfigurator change some values start this method ...
void initConfigurator(bool load_from_board)
initConfigurator Initialize all parameter and syncronize parameters between ros and roboteq board ...
Definition: motor_param.cpp:45
roboteq_control::RoboteqParameterConfig default_param_config
Definition: motor_param.h:106
unsigned int mNumber
Number motor.
Definition: motor_param.h:81
MotorParamConfigurator(const ros::NodeHandle &nh, roboteq::serial_controller *serial, std::string name, unsigned int number)
MotorParamConfigurator.
Definition: motor_param.cpp:33
roboteq::serial_controller * mSerial
Serial port.
Definition: motor_param.h:85
void getParamFromRoboteq()
getParamFromRoboteq Load parameters from Roboteq board
dynamic_reconfigure::Server< roboteq_control::RoboteqPIDtypeConfig > * ds_pid_type
Dynamic reconfigure PID.
Definition: motor_param.h:97
string mName
Associate name space.
Definition: motor_param.h:79
dynamic_reconfigure::Server< roboteq_control::RoboteqParameterConfig > * ds_param
Dynamic reconfigure parameters.
Definition: motor_param.h:88
roboteq_control::RoboteqPIDtypeConfig _last_pid_type_config
Definition: motor_param.h:107
roboteq_control::RoboteqParameterConfig _last_param_config
Definition: motor_param.h:106
bool setup_param
Setup variable.
Definition: motor_param.h:76
roboteq_control::RoboteqPIDtypeConfig default_pid_type_config
Definition: motor_param.h:107
ros::NodeHandle nh_
Private namespace.
Definition: motor_param.h:83


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