include
quori_holonomic_drive_controller
holonomic.hpp
Go to the documentation of this file.
1
#pragma once
2
3
#include <iostream>
4
5
namespace
quori_holonomic_drive_controller
6
{
7
struct
HolonomicParams
8
{
9
// This distance in meters between the center of the two wheels
10
double
wheel_distance
;
11
double
wheel_radius
;
12
13
double
max_motor_turret_vel
;
14
double
max_motor_left_vel
;
15
double
max_motor_right_vel
;
16
};
17
18
struct
HolonomicCommand
19
{
20
double
lin_x_vel
;
21
double
lin_y_vel
;
22
double
ang_z_vel
;
23
24
};
25
26
HolonomicCommand
limit_acceleration
(
const
HolonomicCommand
&prev,
const
HolonomicCommand
¤t,
const
double
limit);
27
28
29
struct
DiffDriveCommand
30
{
31
// Left motor velocity in rad/s
32
double
motor_left_vel
;
33
34
// Right motor velocity in rad/s
35
double
motor_right_vel
;
36
37
// Turret motor velocity in rad/s
38
double
motor_turret_vel
;
39
};
40
41
DiffDriveCommand
compute_ramsis_jacobian
(
const
HolonomicCommand
&command,
double
turret_pos,
const
HolonomicParams
¶ms);
42
43
}
44
45
46
std::ostream &
operator <<
(std::ostream &o,
const
quori_holonomic_drive_controller::HolonomicParams
&v);
47
std::ostream &
operator <<
(std::ostream &o,
const
quori_holonomic_drive_controller::HolonomicCommand
&v);
48
std::ostream &
operator <<
(std::ostream &o,
const
quori_holonomic_drive_controller::DiffDriveCommand
&v);
quori_holonomic_drive_controller::limit_acceleration
HolonomicCommand limit_acceleration(const HolonomicCommand &prev, const HolonomicCommand ¤t, const double limit)
Definition:
holonomic.cpp:9
operator<<
std::ostream & operator<<(std::ostream &o, const quori_holonomic_drive_controller::HolonomicParams &v)
Definition:
holonomic.cpp:85
quori_holonomic_drive_controller::HolonomicCommand::lin_y_vel
double lin_y_vel
Definition:
holonomic.hpp:21
quori_holonomic_drive_controller::HolonomicCommand
Definition:
holonomic.hpp:18
quori_holonomic_drive_controller::compute_ramsis_jacobian
DiffDriveCommand compute_ramsis_jacobian(const HolonomicCommand &command, double turret_pos, const HolonomicParams ¶ms)
Definition:
holonomic.cpp:37
quori_holonomic_drive_controller::HolonomicParams::wheel_distance
double wheel_distance
Definition:
holonomic.hpp:10
quori_holonomic_drive_controller::DiffDriveCommand
Definition:
holonomic.hpp:29
quori_holonomic_drive_controller::HolonomicParams::wheel_radius
double wheel_radius
Definition:
holonomic.hpp:11
quori_holonomic_drive_controller::HolonomicParams::max_motor_turret_vel
double max_motor_turret_vel
Definition:
holonomic.hpp:13
quori_holonomic_drive_controller::HolonomicParams::max_motor_left_vel
double max_motor_left_vel
Definition:
holonomic.hpp:14
quori_holonomic_drive_controller
Definition:
holonomic.hpp:5
quori_holonomic_drive_controller::HolonomicCommand::lin_x_vel
double lin_x_vel
Definition:
holonomic.hpp:20
quori_holonomic_drive_controller::DiffDriveCommand::motor_left_vel
double motor_left_vel
Definition:
holonomic.hpp:32
quori_holonomic_drive_controller::DiffDriveCommand::motor_turret_vel
double motor_turret_vel
Definition:
holonomic.hpp:38
quori_holonomic_drive_controller::HolonomicCommand::ang_z_vel
double ang_z_vel
Definition:
holonomic.hpp:22
quori_holonomic_drive_controller::DiffDriveCommand::motor_right_vel
double motor_right_vel
Definition:
holonomic.hpp:35
quori_holonomic_drive_controller::HolonomicParams
Definition:
holonomic.hpp:7
quori_holonomic_drive_controller::HolonomicParams::max_motor_right_vel
double max_motor_right_vel
Definition:
holonomic.hpp:15
quori_holonomic_drive_controller
Author(s):
autogenerated on Wed Mar 2 2022 00:53:24