MotorController
inc
position.h
Go to the documentation of this file.
1
/** @file */
2
3
#ifndef POSITION_H
4
#define POSITION_H
5
6
/******************************************************************************/
7
/* Includes */
8
/******************************************************************************/
9
#include "ch.h"
10
11
/******************************************************************************/
12
/* Types */
13
/******************************************************************************/
14
typedef
struct
{
15
int32_t left;
16
int32_t right;
17
}
ticks_t
;
18
19
typedef
struct
{
20
float
x;
21
float
y;
22
}
position_t
;
23
24
/******************************************************************************/
25
/* Variables */
26
/******************************************************************************/
27
/**
28
* For tests only.
29
*/
30
extern
ticks_t
previous_ticks
;
31
32
/**
33
* Variation of the coding wheels, in ticks.
34
*/
35
extern
ticks_t
delta_ticks
;
36
37
/**
38
* Current cartesian coordinates of the robot center, in mm.
39
*/
40
extern
position_t
cur_pos
;
41
42
/******************************************************************************/
43
/* Functions prototypes */
44
/******************************************************************************/
45
/**
46
* @brief Compute the coding wheels movements.
47
*/
48
extern
void
compute_movement
(
void
);
49
50
/**
51
* @brief Update the position according to the information given by the coding wheels.
52
*
53
* @details This function must be called AFTER update_orientation(), as it
54
* considers that the 'orientation' variable holds the new orientation.
55
*/
56
extern
void
update_position
(
void
);
57
58
#endif
/* POSITION_H */
delta_ticks
ticks_t delta_ticks
Definition:
position.c:20
previous_ticks
ticks_t previous_ticks
Definition:
position.c:18
update_position
void update_position(void)
Update the position according to the information given by the coding wheels.
Definition:
position.c:48
position_t
Definition:
position.h:19
ticks_t
Definition:
position.h:14
cur_pos
position_t cur_pos
Definition:
position.c:22
compute_movement
void compute_movement(void)
Compute the coding wheels movements.
Definition:
position.c:39
Generated on Sun Dec 17 2017 17:21:06 for MotorController by
1.8.13