encoder_diffbot.h
Go to the documentation of this file.
1 /*
2  * Author: Franz Pucher
3  */
4 
5 #ifndef DIFFBOT_ENCODER_H
6 #define DIFFBOT_ENCODER_H
7 
8 #include <Encoder.h>
9 
10 #include <ros.h>
11 
12 
13 namespace diffbot
14 {
15  struct JointState
16  {
19  };
20 
21 
35  class Encoder
36  {
37  public:
38  // Teensy Encoder class that is capable of reading rising and falling edges of two Hall effect signals.
40 
48  Encoder(ros::NodeHandle& nh, uint8_t pin1, uint8_t pin2, int encoder_resolution);
49 
58  int getRPM();
59 
60 
61  double angularPosition();
62 
69  double angularVelocity();
70 
71 
73 
83  double ticksToAngle(const int &ticks) const;
84 
89  inline int32_t read() { return encoder.read(); };
90 
97  inline void write(int32_t p) { encoder.write(p); };
98 
107 
112  inline int resolution() { return encoder_resolution_; };
113 
114 
116 
117  private:
118  // ROS node handle, which provides the current time to compute the angular velocity from the current tick count
120  // Number of tick counts for one full revolution of the wheel (not the motor shaft). Keep track of gear reduction ratio.
122  // Previous time when the \ref getRPM or \ref angularVelocity method was called to calculated the delta update time.
124  // Previous encoder tick count when the \ref getRPM or \ref angularVelocity method was called to calculated the delta tick count.
126  };
127 }
128 
129 #endif // DIFFBOT_ENCODER_H
diffbot
Definition: base_controller.h:23
diffbot::Encoder::angularPosition
double angularPosition()
Definition: encoder_diffbot.cpp:39
diffbot::JointState
Definition: encoder_diffbot.h:15
ros.h
diffbot::Encoder::jointState
JointState jointState()
Definition: encoder_diffbot.cpp:14
diffbot::Encoder::read
int32_t read()
Read the current encoder tick count.
Definition: encoder_diffbot.h:89
diffbot::Encoder::prev_update_time_
ros::Time prev_update_time_
Definition: encoder_diffbot.h:123
diffbot::Encoder::prev_encoder_ticks_
long prev_encoder_ticks_
Definition: encoder_diffbot.h:125
nh
ros::NodeHandle nh
Definition: main.cpp:8
diffbot::JointState::angular_position_
double angular_position_
Definition: encoder_diffbot.h:17
diffbot::Encoder::write
void write(int32_t p)
Set the encoder tick count.
Definition: encoder_diffbot.h:97
ros::Time
diffbot::Encoder::encoder_resolution_
int encoder_resolution_
Definition: encoder_diffbot.h:121
diffbot::Encoder::getRPM
int getRPM()
get revolutions per minute
Definition: encoder_diffbot.cpp:58
diffbot::Encoder::resolution
int resolution()
Getter for encoder resolution.
Definition: encoder_diffbot.h:112
diffbot::Encoder
Decorates the Teensy Encoder Library to read the angular wheel velocity from quadrature wheel encoder...
Definition: encoder_diffbot.h:35
diffbot::Encoder::resolution
void resolution(int resolution)
Setter for encoder resolution.
Definition: encoder_diffbot.h:106
diffbot::Encoder::nh_
ros::NodeHandle & nh_
Definition: encoder_diffbot.h:119
diffbot::Encoder::angularVelocity
double angularVelocity()
Get the measure the angular joint velocity.
Definition: encoder_diffbot.cpp:45
diffbot::Encoder::ticksToAngle
double ticksToAngle(const int &ticks) const
Convert number of encoder ticks to angle in radians.
Definition: encoder_diffbot.cpp:50
diffbot::Encoder::joint_state_
JointState joint_state_
Definition: encoder_diffbot.h:112
diffbot::Encoder::encoder
::Encoder encoder
Definition: encoder_diffbot.h:39
diffbot::Encoder::Encoder
Encoder(ros::NodeHandle &nh, uint8_t pin1, uint8_t pin2, int encoder_resolution)
Construct a diffbot::Encoder providing access to quadrature encoder ticks and angular joint velocity.
Definition: encoder_diffbot.cpp:4
diffbot::JointState::angular_velocity_
double angular_velocity_
Definition: encoder_diffbot.h:18
ros::NodeHandle


diffbot_base
Author(s):
autogenerated on Thu Sep 7 2023 02:35:23