+++ /dev/null
-#ifndef CONSTANTS_H
-#define CONSTANTS_H
-
-#define BASELINE 0.3 //distance between wheels in meters
-#define MAX_DUTY_CYCLE 790
-#define TICKS_PER_REVOLUTION 148000 //x4 resolution
-#define RIGHT_WHEEL_CIRCUMFERENCE 0.8 //in meters
-#define LEFT_WHEEL_CIRCUMFERENCE 0.78 //in meters
-
-#endif
#define ENCODER_H
#include "main.h"
-#include "constants.h"
class Encoder {
public:
uint32_t current_millis_;
int32_t ticks_; //if negative the wheel is going backwards
float wheel_circumference_;
+ int ticks_per_revolution_;
Encoder() {
timer_ = NULL;
wheel_circumference_ = 0;
+ ticks_per_revolution_ = 0;
}
- Encoder(TIM_HandleTypeDef *timer, float wheel_circ);
+ Encoder(TIM_HandleTypeDef *timer, float wheel_circ,
+ int ticks_per_revolution) {
+ timer_ = timer;
+ wheel_circumference_ = wheel_circ;
+ ticks_per_revolution_ = ticks_per_revolution;
- void Setup();
+ }
int GetCount() {
int count = ((int) __HAL_TIM_GET_COUNTER(this->timer_)
void ResetCount() {
//set counter to half its maximum value
- __HAL_TIM_SET_COUNTER(timer_, (timer_->Init.Period) / 2);
+ __HAL_TIM_SET_COUNTER(timer_, (timer_->Init.Period / 2));
+ }
+
+ void Setup() {
+ HAL_TIM_Encoder_Start(timer_, TIM_CHANNEL_ALL);
+ this->ResetCount();
+ this->previous_millis_ = 0;
+ this->current_millis_ = HAL_GetTick();
}
- void UpdateValues();
+ void UpdateValues() {
+ this->previous_millis_ = this->current_millis_;
+ this->current_millis_ = HAL_GetTick();
+ this->ticks_ = this->GetCount();
+ this->ResetCount();
+ }
- float GetMeters();
+ float GetMeters() {
+ float meters = ((float) this->ticks_ * this->wheel_circumference_)
+ / ticks_per_revolution_;
+ return meters;
+ }
- float GetLinearVelocity();
+ float GetLinearVelocity() {
+ this->UpdateValues();
+ float meters = this->GetMeters();
+ float deltaTime = this->current_millis_ - this->previous_millis_;
+ if (deltaTime == 0)
+ return 0;
+ float linear_velocity = (meters / (deltaTime / 1000));
+ return linear_velocity;
+ }
};
#endif
this->dir_pin_ = dir_pin;
this->pwm_timer_ = pwm_timer;
this->pwm_channel_ = pwm_channel;
- this->max_dutycycle_ = pwm_timer->Instance->ARR;
+ this->max_dutycycle_ = 0;
}
void setup() {
HAL_TIM_PWM_Start(pwm_timer_, pwm_channel_);
+ this->max_dutycycle_ = pwm_timer_->Instance->ARR;
}
void set_speed(int duty_cycle) {
#ifndef ODOMETRY_H
#define ODOMETRY_H
-#include "constants.h"
-
class Odometry {
private:
float left_velocity_;
float right_velocity_;
-
+ float baseline_;
public:
Odometry() {
left_velocity_ = 0;
right_velocity_ = 0;
+ baseline_ = 0;
+ }
+
+ Odometry(float baseline) {
+ left_velocity_ = 0;
+ right_velocity_ = 0;
+ baseline_ = baseline;
}
void UpdateValues(float linear_vel, float angular_vel) {
- left_velocity_ = linear_vel - (BASELINE * angular_vel)/2;
- right_velocity_ = 2 * linear_vel - left_velocity_;
+ left_velocity_ = linear_vel - (baseline_ * angular_vel) / 2;
+ right_velocity_ = linear_vel + (baseline_ * angular_vel) / 2;
}
- float GetLeftVelocity(){
+ float GetLeftVelocity() {
return left_velocity_;
}
- float GetRightVelocity(){
+ float GetRightVelocity() {
return right_velocity_;
}
+++ /dev/null
-#include "encoder.h"
-
-Encoder::Encoder(TIM_HandleTypeDef *timer, float wheel_circ) {
- timer_ = timer;
- wheel_circumference_ = wheel_circ;
-}
-
-void Encoder::Setup() {
- HAL_TIM_Encoder_Start(timer_, TIM_CHANNEL_ALL);
- this->ResetCount();
- this->previous_millis_ = 0;
- this->current_millis_ = HAL_GetTick();
-}
-
-void Encoder::UpdateValues() {
- this->previous_millis_ = this->current_millis_;
- this->current_millis_ = HAL_GetTick();
- this->ticks_ = this->GetCount();
- this->ResetCount();
-}
-
-float Encoder::GetMeters() {
- this->UpdateValues();
- float meters = ((float) this->ticks_ * this->wheel_circumference_)
- / TICKS_PER_REVOLUTION;
- return meters;
-}
-
-float Encoder::GetLinearVelocity() {
- this->UpdateValues();
- float meters = ((float) this->ticks_ * this->wheel_circumference_)
- / TICKS_PER_REVOLUTION;
- float deltaTime = this->current_millis_ - this->previous_millis_;
- if (deltaTime == 0)
- return 0;
- float linear_velocity = (meters / (deltaTime / 1000));
- return linear_velocity;
-}
-
\r
/* USER CODE BEGIN PV */\r
\r
+//Parameters\r
+float baseline = 0.3;\r
+int ticks_per_revolution = 148000; //x4 resolution\r
+float right_wheel_circumference = 0.783; //in meters\r
+float left_wheel_circumference = 0.789; //in meters\r
+\r
//Odometry\r
-Encoder right_encoder = Encoder(&htim5, RIGHT_WHEEL_CIRCUMFERENCE);\r
-Encoder left_encoder = Encoder(&htim2, LEFT_WHEEL_CIRCUMFERENCE);\r
-Odometry odom = Odometry();\r
+Encoder right_encoder = Encoder(&htim5, right_wheel_circumference,\r
+ ticks_per_revolution);\r
+Encoder left_encoder = Encoder(&htim2, left_wheel_circumference,\r
+ ticks_per_revolution);\r
+Odometry odom = Odometry(baseline);\r
float left_velocity = 0;\r
float right_velocity = 0;\r
\r