gpio_encoder.h
Go to the documentation of this file.
1 
31 #ifndef GPIOENCODERCONFIGURATOR_H
32 #define GPIOENCODERCONFIGURATOR_H
33 
34 #include <ros/ros.h>
35 
36 #include <roboteq_control/RoboteqEncoderConfig.h>
37 #include <dynamic_reconfigure/server.h>
38 
40 
41 #include "roboteq/motor.h"
43 
45 {
46 public:
53  GPIOEncoderConfigurator(const ros::NodeHandle& nh, roboteq::serial_controller *serial, std::vector<roboteq::Motor *> motor, string name, unsigned int number);
58  void initConfigurator(bool load_from_board);
63  double getConversion(double reduction);
64 
65 private:
68 
70  string mName;
72  unsigned int mNumber;
77  // List of all motors
78  std::vector<roboteq::Motor *> _motor;
79 
80  // reduction value
81  double _reduction;
82 
84  dynamic_reconfigure::Server<roboteq_control::RoboteqEncoderConfig> *ds_encoder;
90  void reconfigureCBEncoder(roboteq_control::RoboteqEncoderConfig &config, uint32_t level);
91 
92  roboteq_control::RoboteqEncoderConfig default_encoder_config, _last_encoder_config;
93 
97  void getEncoderFromRoboteq();
98 };
99 
100 #endif // GPIOENCODERCONFIGURATOR_H
bool setup_encoder
Setup variable.
Definition: gpio_encoder.h:67
string mName
Associate name space.
Definition: gpio_encoder.h:70
void getEncoderFromRoboteq()
getEncoderFromRoboteq Load Encoder parameters from Roboteq board
void initConfigurator(bool load_from_board)
initConfigurator Initialize all parameter and syncronize parameters between ros and roboteq board ...
std::vector< roboteq::Motor * > _motor
Definition: gpio_encoder.h:78
double getConversion(double reduction)
getConversion Get conversion from pulse value to real value
ros::NodeHandle nh_
Private namespace.
Definition: gpio_encoder.h:74
void reconfigureCBEncoder(roboteq_control::RoboteqEncoderConfig &config, uint32_t level)
reconfigureCBEncoder when the dynamic reconfigurator change some values start this method ...
unsigned int mNumber
Number motor.
Definition: gpio_encoder.h:72
GPIOEncoderConfigurator(const ros::NodeHandle &nh, roboteq::serial_controller *serial, std::vector< roboteq::Motor * > motor, string name, unsigned int number)
GPIOEncoderConfigurator.
roboteq_control::RoboteqEncoderConfig _last_encoder_config
Definition: gpio_encoder.h:92
dynamic_reconfigure::Server< roboteq_control::RoboteqEncoderConfig > * ds_encoder
Dynamic reconfigure encoder.
Definition: gpio_encoder.h:84
roboteq_control::RoboteqEncoderConfig default_encoder_config
Definition: gpio_encoder.h:92
roboteq::serial_controller * mSerial
Serial port.
Definition: gpio_encoder.h:76


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