gpio_pulse.h
Go to the documentation of this file.
1 
31 #ifndef GPIOPULSECONFIGURATOR_H
32 #define GPIOPULSECONFIGURATOR_H
33 
34 #include <ros/ros.h>
35 
36 #include <roboteq_control/RoboteqPulseInputConfig.h>
37 #include <dynamic_reconfigure/server.h>
38 
41 #include "roboteq/motor.h"
42 
44 {
45 public:
52  GPIOPulseConfigurator(const ros::NodeHandle& nh, roboteq::serial_controller *serial, std::vector<roboteq::Motor *> motor, string name, unsigned int number);
57  void initConfigurator(bool load_from_board);
62  double getConversion(double reduction)
63  {
64  return 0;
65  }
66 
67 private:
70 
72  string mName;
74  unsigned int mNumber;
79  // List of all motors
80  std::vector<roboteq::Motor *> _motor;
81 
83  dynamic_reconfigure::Server<roboteq_control::RoboteqPulseInputConfig> *ds_param;
89  void reconfigureCBParam(roboteq_control::RoboteqPulseInputConfig &config, uint32_t level);
90 
91  // Default parameter config
92  roboteq_control::RoboteqPulseInputConfig default_param_config, _last_param_config;
93 
97  void getParamFromRoboteq();
98 };
99 
100 #endif // GPIOPULSECONFIGURATOR_H
void getParamFromRoboteq()
getParamFromRoboteq Load parameters from Roboteq board
Definition: gpio_pulse.cpp:62
void reconfigureCBParam(roboteq_control::RoboteqPulseInputConfig &config, uint32_t level)
reconfigureCBParam when the dynamic reconfigurator change some values start this method ...
Definition: gpio_pulse.cpp:152
bool setup_param
Setup variable.
Definition: gpio_pulse.h:69
double getConversion(double reduction)
getConversion Get conversion from pulse value to real value
Definition: gpio_pulse.h:62
roboteq::serial_controller * mSerial
Serial port.
Definition: gpio_pulse.h:78
dynamic_reconfigure::Server< roboteq_control::RoboteqPulseInputConfig > * ds_param
Dynamic reconfigure parameters.
Definition: gpio_pulse.h:83
ros::NodeHandle nh_
Private namespace.
Definition: gpio_pulse.h:76
std::vector< roboteq::Motor * > _motor
Definition: gpio_pulse.h:80
void initConfigurator(bool load_from_board)
initConfigurator Initialize all parameter and syncronize parameters between ros and roboteq board ...
Definition: gpio_pulse.cpp:48
string mName
Associate name space.
Definition: gpio_pulse.h:72
roboteq_control::RoboteqPulseInputConfig default_param_config
Definition: gpio_pulse.h:92
roboteq_control::RoboteqPulseInputConfig _last_param_config
Definition: gpio_pulse.h:92
GPIOPulseConfigurator(const ros::NodeHandle &nh, roboteq::serial_controller *serial, std::vector< roboteq::Motor * > motor, string name, unsigned int number)
GPIOPulseConfigurator.
Definition: gpio_pulse.cpp:35
unsigned int mNumber
Number motor.
Definition: gpio_pulse.h:74


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