Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Udon::Direction 導入 #229

Merged
merged 1 commit into from
Dec 25, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions src/Udon/Com/Driver/Encoder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
#include <Udon/Algorithm/DeltaTime.hpp>
#include <Udon/Com/Message/Encoder.hpp>
#include <Udon/Traits/HasMemberFunction.hpp>

#include <Udon/Traits/ReaderWriterTraits.hpp>
#include <Udon/Utility/Printf.hpp>
#include <Udon/Types/Direction.hpp>

namespace Udon
{
Expand All @@ -32,7 +32,7 @@ namespace Udon

Udon::DeltaTime deltaTime;

bool direction;
Udon::Direction direction;

int32_t count{};
int32_t deltaCount{};
Expand All @@ -43,7 +43,7 @@ namespace Udon
/// @brief コンストラクタ
/// @param reader 受信クラスオブジェクト
/// @param direction 回転方向
EncoderBy(ReaderType&& reader, bool direction)
EncoderBy(ReaderType&& reader, Udon::Direction direction = Udon::Direction::Forward)
: reader(std::move(reader))
, deltaTime()
, direction(direction)
Expand All @@ -59,7 +59,7 @@ namespace Udon

if (const auto countOpt = reader.getMessage())
{
count = countOpt->count * (direction ? 1 : -1);
count = countOpt->count * Udon::DirectionToSign(direction);
}

const auto curr = getCount();
Expand Down
7 changes: 4 additions & 3 deletions src/Udon/Com/Driver/Motor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
#include <Udon/Traits/HasMemberFunction.hpp>
#include <Udon/Utility/Show.hpp>
#include <Udon/Traits/ReaderWriterTraits.hpp>
#include <Udon/Types/Direction.hpp>

namespace Udon
{
Expand All @@ -28,14 +29,14 @@ namespace Udon

int16_t power; // 出力値 -255 ~ 255

bool direction; // 回転方向 true: forward, false: backward
Udon::Direction direction; // 回転方向

public:

/// @brief コンストラクタ
/// @param writer 送信クラスオブジェクト
/// @param direction 回転方向
MotorBy(WriterType&& writer, bool direction)
MotorBy(WriterType&& writer, Udon::Direction direction = Udon::Direction::Forward)
: writer(std::move(writer))
, power()
, direction(direction)
Expand All @@ -47,7 +48,7 @@ namespace Udon
void move(int16_t p)
{
power = Constrain(p, (int16_t)-255, (int16_t)255);
writer.setMessage({ static_cast<int16_t>(power * (direction ? 1 : -1)) });
writer.setMessage({ static_cast<int16_t>(power * Udon::DirectionToSign(direction)) });
Udon::Traits::MaybeInvokeUpdate(writer);
}

Expand Down
9 changes: 7 additions & 2 deletions src/Udon/Driver/EncoderPico.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
# include "Pio/QuadratureEncoder.pio.hpp"

# include <Udon/Algorithm/ScopedInterruptLocker.hpp>
# include <Udon/Types/Direction.hpp>

namespace Udon
{
Expand All @@ -22,15 +23,19 @@ namespace Udon
uint8_t pinA;
uint8_t pinB;

Udon::Direction direction;

Pio::StateMachine stateMachine; // PIO使用時

public:
/// @brief コンストラクタ
/// @param pinA エンコーダーのA相ピン
/// @param pinB エンコーダーのB相ピン
EncoderPico(uint8_t pinA, uint8_t pinB)
/// @param direction 回転方向
EncoderPico(uint8_t pinA, uint8_t pinB, Udon::Direction direction = Udon::Direction::Forward)
: pinA(pinA)
, pinB(pinB)
, direction(direction)
, stateMachine()
{
}
Expand Down Expand Up @@ -68,7 +73,7 @@ namespace Udon
/// @return エンコーダーの値
int32_t read() const
{
return Pio::Encoder::quadrature_encoder_get_count(stateMachine.pio, stateMachine.index);
return Pio::Encoder::quadrature_encoder_get_count(stateMachine.pio, stateMachine.index) * Udon::DirectionToSign(direction);
}

/// @brief エンコーダーの値を表示する
Expand Down
29 changes: 18 additions & 11 deletions src/Udon/Driver/Motor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

# include <Arduino.h>
# include <Udon/Algorithm/MovingAverage.hpp>
# include <Udon/Types/Direction.hpp>

namespace Udon
{
Expand All @@ -22,17 +23,20 @@ namespace Udon
const uint8_t pinA;
const uint8_t pinP;

Udon::MovingAverage<SmoothLevel> movingAverage;
Udon::Direction direction;

Udon::MovingAverage<SmoothLevel> ma;

public:

/// @brief コンストラクタ
/// @param pinA 方向ピン
/// @param pinP PWM ピン
SmoothlyMotor2(const uint8_t pinA, const uint8_t pinP)
SmoothlyMotor2(const uint8_t pinA, const uint8_t pinP, Udon::Direction direction = Udon::Direction::Forward)
: pinA(pinA)
, pinP(pinP)
, movingAverage{}
, direction(direction)
, ma{}
{
}

Expand All @@ -46,7 +50,7 @@ namespace Udon
/// @param power パワー (-250 ~ 250)
void move(const int16_t power)
{
const int16_t p = movingAverage(constrain(power, -250, 250));
const int16_t p = ma(constrain(power, -250, 250)) * Udon::DirectionToSign(direction);
digitalWrite(pinA, p >= 0 ? HIGH : LOW);
analogWrite(pinP, abs(p));
}
Expand All @@ -60,7 +64,7 @@ namespace Udon
/// @brief パワーをシリアル出力
void show() const
{
Serial.print(movingAverage.getValue());
Serial.print(ma.getValue());
Serial.print('\t');
}
};
Expand All @@ -74,19 +78,23 @@ namespace Udon
const uint8_t pinB;
const uint8_t pinP;

Udon::MovingAverage<SmoothLevel> movingAverage;
Udon::Direction direction;

Udon::MovingAverage<SmoothLevel> ma;

public:

/// @brief コンストラクタ
/// @param pinA 方向ピン
/// @param pinB 方向ピン
/// @param pinP PWM ピン
SmoothlyMotor3(const uint8_t pinA, const uint8_t pinB, const uint8_t pinP)
/// @param direction 回転方向
SmoothlyMotor3(const uint8_t pinA, const uint8_t pinB, const uint8_t pinP, Udon::Direction direction = Udon::Direction::Forward)
: pinA(pinA)
, pinB(pinB)
, pinP(pinP)
, movingAverage{}
, direction(direction)
, ma{}
{
}

Expand All @@ -101,8 +109,7 @@ namespace Udon
/// @param power パワー (-250 ~ 250)
void move(const int16_t power)
{
movingAverage.update(constrain(power, -250, 250));
const int16_t p = movingAverage.getValue();
const int16_t p = ma(constrain(power, -250, 250)) * Udon::DirectionToSign(direction);
digitalWrite(pinA, p >= 0 ? HIGH : LOW);
digitalWrite(pinB, p <= 0 ? HIGH : LOW);
analogWrite(pinP, abs(p));
Expand All @@ -117,7 +124,7 @@ namespace Udon
/// @brief パワーをシリアル出力
void show() const
{
Serial.print(movingAverage.getValue());
Serial.print(ma.getValue());
Serial.print('\t');
}
};
Expand Down
20 changes: 8 additions & 12 deletions src/Udon/Driver/RoboMasterMotor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

#include <Udon/Com/Can.hpp>
#include <Udon/Algorithm/Math.hpp>
#include <Udon/Types/Direction.hpp>

namespace Udon
{
Expand All @@ -24,7 +25,7 @@ namespace Udon
/// @param bus CAN通信バス
/// @param motorId モーターID (1~8)
/// @param direction 回転方向
RoboMasterBase(Udon::ICanBus& bus, uint8_t motorId, bool direction = true)
RoboMasterBase(Udon::ICanBus& bus, uint8_t motorId, Udon::Direction direction = Udon::Direction::Forward)
: bus{ bus }
, motorId{ motorId }
, direction{ direction }
Expand Down Expand Up @@ -62,7 +63,7 @@ namespace Udon
/// @return 角度 [rad]
double getAngle() const
{
return (angle + offsetAngle) * 2 * Udon::Pi / ppr * directionSign();
return (angle + offsetAngle) * 2 * Udon::Pi / ppr * Udon::DirectionToSign(direction);
}


Expand All @@ -71,15 +72,15 @@ namespace Udon
/// @return 角度 [rad]
double getRawAngle() const
{
return angle * 2 * Udon::Pi / ppr * directionSign();
return angle * 2 * Udon::Pi / ppr * Udon::DirectionToSign(direction);
}


/// @brief モーターの速度を取得
/// @return 速度 [rpm]
int16_t getVelocity() const
{
const auto velocity = (nodeRx->data[2] << 8 | nodeRx->data[3]) * directionSign();
const auto velocity = (nodeRx->data[2] << 8 | nodeRx->data[3]) * Udon::DirectionToSign(direction);
return static_cast<int16_t>(velocity);
}

Expand All @@ -88,7 +89,7 @@ namespace Udon
/// @return トルク電流 [mA]
int16_t getTorqueCurrent() const
{
const int current = (nodeRx->data[4] << 8 | nodeRx->data[5]) * directionSign();
const int current = (nodeRx->data[4] << 8 | nodeRx->data[5]) * Udon::DirectionToSign(direction);
return static_cast<int16_t>(current);
}

Expand All @@ -105,7 +106,7 @@ namespace Udon
/// @param current 電流値
void setCurrent(int16_t current)
{
current = current * directionSign();
current = current * Udon::DirectionToSign(direction);

const auto transmitCurrent = static_cast<int16_t>(current * 16384 / 20000);

Expand All @@ -131,7 +132,7 @@ namespace Udon
uint8_t motorId;

/// @brief 回転方向
bool direction;
Udon::Direction direction;

/// @brief 送信バッファ
Udon::CanTxNode* nodeTx;
Expand All @@ -149,11 +150,6 @@ namespace Udon
/// @brief エンコーダー分解能
static constexpr int32_t ppr = 8192;

int16_t directionSign() const
{
return direction ? 1 : -1;
}

static void onReceive(void* p)
{
auto self = static_cast<RoboMasterBase*>(p);
Expand Down
23 changes: 23 additions & 0 deletions src/Udon/Types/Direction.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#pragma once

namespace Udon
{

/// @brief 方向
/// @note 回転方向を表す
enum class Direction
{
Forward,
Backward,
};

inline int DirectionToSign(Direction direction)
{
switch (direction)
{
case Direction::Forward: return 1;
case Direction::Backward: return -1;
}
}

} // namespace Udon
4 changes: 2 additions & 2 deletions test/ArduinoLint/src/Driver/RoboMasterMotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ __attribute__((unused)) static void test()
{
DummyBus bus;
{
Udon::RoboMasterC610 motor{ bus, 0x000, true };
Udon::RoboMasterC610 motor{ bus, 0x000, Udon::Direction::Forward };
motor.setCurrent(0);
motor.getAngle();
motor.getVelocity();
Expand All @@ -29,7 +29,7 @@ __attribute__((unused)) static void test()
}

{
Udon::RoboMasterC620 motor{ bus, 0x000, true };
Udon::RoboMasterC620 motor{ bus, 0x000, Udon::Direction::Backward };
motor.setCurrent(0);
motor.getAngle();
motor.getVelocity();
Expand Down
Loading