Chassis v2.1.1
Chassisはロボコンでの足回り制御を行うためのC++ライブラリである。
Loading...
Searching...
No Matches
ChassisAuto.h
Go to the documentation of this file.
1#ifndef RCT_CHASSIS_AUTO_H_
2#define RCT_CHASSIS_AUTO_H_
7#include <CoordinateUnit.h>
8#include <Pid.h>
9
10#include <chrono>
11#include <cmath>
12#include <cstdint>
13#include <utility>
14
15namespace rct {
16
19
22template<class T>
28 template<class F>
29 ChassisAuto(F&& f, const PidGain& pos_gain) : t_{std::forward<F>(f)}, pos_pid_{pos_gain} {}
30
32 void auto_move(const Coordinate& dst, const Coordinate& pos, const std::chrono::microseconds& delta_time) {
33 const auto out_vel = pos_pid_.calc(dst, pos, delta_time) / std::chrono::seconds{1};
34 t_.move(out_vel);
35 }
36
37 private:
38 T t_;
39 Pid<Coordinate> pos_pid_;
40};
41
43
44} // namespace rct
45
46#endif // RCT_CHASSIS_AUTO_H_
座標、速度を表す構造体 CoordinateUnit を提供する。
PID制御を行う Pid クラスを提供する。
robot control library
Definition Chassis.h:16
足回りの位置のPID制御を行う。
Definition ChassisAuto.h:23
void auto_move(const Coordinate &dst, const Coordinate &pos, const std::chrono::microseconds &delta_time)
自動制御用。変位のPID制御を行い、出力をT型のcalcに渡す。
Definition ChassisAuto.h:32
ChassisAuto(F &&f, const PidGain &pos_gain)
コンストラクタ。T型をfで初期化し、変位と速度のPIDゲインをセットする。
Definition ChassisAuto.h:29
N輪オムニの制御を行うクラス。
Definition Omni.h:25
void move(const Velocity &vel, const float offset_rad=0.0)
モータへのPWM出力を計算する。その後callback関数にPWM出力を渡す。
Definition Omni.h:43
PID制御のゲイン
Definition Pid.h:21