Chassis v2.1.1
Chassisはロボコンでの足回り制御を行うためのC++ライブラリである。
Loading...
Searching...
No Matches
main.cpp File Reference

速度PID制御 More...

#include <../snippets/Motor.h>
#include <Chassis.h>
#include <Odom.h>
#include <Omni.h>
#include <mbed.h>
#include <array>
#include <functional>
Include dependency graph for main.cpp:

Go to the source code of this file.

Functions

int main ()
 

Variables

Timer timer
 
Odom< 3 > odom {}
 
Motor motors [3] = {{D10, D11}, {D12, D13}, {D12, D13}}
 
Chassis< Omni< 3 > > chassis
 

Detailed Description

速度PID制御

Definition in file main.cpp.

Function Documentation

◆ main()

int main ( )

Definition at line 24 of file main.cpp.

Variable Documentation

◆ chassis

Chassis<Omni<3> > chassis
Initial value:
{[](std::array<float,3> pwm) {
for(int i = 0; i < 3; ++i) {
motors[i] = pwm[i];
}
},
PidGain{0.1}, PidGain{0.1}}
N輪オムニの制御を行うクラス。
Definition Omni.h:25
PID制御のゲイン
Definition Pid.h:21

Definition at line 17 of file main.cpp.

◆ motors

Motor motors[3] = {{D10, D11}, {D12, D13}, {D12, D13}}

Definition at line 16 of file main.cpp.

◆ odom

Odom<3> odom {}

Definition at line 15 of file main.cpp.

◆ timer

Timer timer

Definition at line 14 of file main.cpp.