UdonLibrary 1.0.0
機械システム研究部 C++ ライブラリ
読み取り中…
検索中…
一致する文字列を見つけられません
ロボマスモーター

ロボマスモーターは CAN 通信経由で制御できるモーターです。

電流値を指定することで動作し、またエンコーダーを搭載しているため、回転数や回転角を取得できます。

個別インクルード

概要

以下の表に示すように、使用するドライバによってクラスが異なります。また指定できる電流範囲も異なります。

使用される CAN ID は 0x200, 0x1FF, 0x200+モーターID です。ドライバは 1ms 間隔で CAN フレームを送信するため、ドライバが接続されている CAN バスには、他の CAN デバイスを接続しないことをお勧めします。

C610 ドライバ C620 ドライバ
イメージ
対応モーター
クラス Udon::RoboMasterC610 Udon::RoboMasterC620
電流範囲 (mA) -10,000 ~ 10,000 -20,000 ~ 20,000

電流値の指定

setCurrent で電流値を指定することで動作します。電流範囲は先ほどの表のとおりです。

#include <Udon.hpp>
static Udon::RoboMasterC620 motor{ bus, 1 }; // ロボマスモーター (モーターID: 1)
void setup()
{
bus.begin();
}
void loop()
{
bus.update();
// 動作電流値を設定 (mA)
motor.setCurrent(5000);
}
Teensy用 CANバスクラス
Definition CanBusTeensy.hpp:31
void update()
バス更新
Definition CanBusTeensy.hpp:89
void begin()
通信開始
Definition CanBusTeensy.hpp:37
RoboMasterC620クラス
Definition RoboMasterMotor.hpp:212

指定可能な電流の範囲は CurrentMin CurrentMax メンバ定数より取得できます。フィードバック制御の制御値を制限する場合などに有用です。

// 指定できる最小電流値 [mA]
const int16_t currentMin = motor.CurrentMin;
const int16_t currentMin = Udon::RoboMasterC620::CurrentMin; // static メンバなのでこちらでも可 モーターの種類が変わった時にクラス名も書き換える必要があるため注意
// 指定できる最大電流値 [mA]
const int16_t currentMax = motor.CurrentMax;
const int16_t currentMax = Udon::RoboMasterC620::CurrentMax;
static constexpr int16_t CurrentMin
指定可能電流最小値
Definition RoboMasterMotor.hpp:221
static constexpr int16_t CurrentMax
指定可能電流最大値
Definition RoboMasterMotor.hpp:224

センサー値取得

回転角度、回転速度、トルク電流、モーター温度を取得可能です。位置制御や速度制御をする場合、フィードバック制御と組み合わせて使用してください。

ドライバは駆動電源で動作するため、駆動電源が切れるとドライバに保存されているエンコーダー角が消去される点に注意してください。

void loop()
{
// 回転角度(無限角対応) [rad]
const double angle = motor.getAngle();
// 回転角度(無限角非対応) [rad]
const double rawAngle = motor.getRawAngle();
// 回転速度 [rpm]
const int16_t rpm = motor.getVelocity();
// トルク電流 [mA]
const int16_t torqueCurrent = motor.getTorqueCurrent();
// モーターの温度 [℃]
const uint8_t temp = motor.getTemperature();
}

複数モーターの場合

モーター ID ごとにオブジェクトを生成することで、1 つの CAN バスに対して最大 8 つまでモーターを接続可能です。

モーター ID はドライバについている SET ボタンを押した後、加えて ID 番号回ボタンを押すことで設定できます。モーター ID は緑に点滅する LED の点滅回数で確認できます。

#include <Udon.hpp>
// C620
static Udon::RoboMasterC620 motor1{ bus, 1 };
static Udon::RoboMasterC620 motor2{ bus, 2 };
// C610
static Udon::RoboMasterC610 motor3{ bus, 3 };
static Udon::RoboMasterC610 motor4{ bus, 4 };
RoboMasterC610クラス
Definition RoboMasterMotor.hpp:185

複数 CAN バスの場合

複数の CAN バスを使用する場合、CAN バスクラスのオブジェクトを複数作成し、それぞれのモーターに対して対応する CAN バスを指定してください。

例えば Teensy の場合次のようになります。詳細

#include <Udon.hpp>
static Udon::RoboMasterC620 motor1{ bus1, 1 }; // CAN1 バスに接続されたモーター (モーターID: 1)
static Udon::RoboMasterC620 motor2{ bus2, 1 }; // CAN2 バスに接続されたモーター (モーターID: 1)

Raspberry Pi Pico での使用例

CAN バスクラスに Udon::CanBusSpi を使用してください。詳細

#include <Udon.hpp>
static Udon::CanBusSpi bus;
static Udon::RoboMasterC620 motor{ bus, 1 };
Raspberry Pi Pico用バスクラス
Definition CanBusSpiPico.hpp:24

スケッチ例 (電流制御)

//
// Copyright (c) 2022-2024 udonrobo
//
#include <Udon.hpp>
// CAN通信バス
// ロボマスモーター (C620ドライバ経由 モーターID: 2)
static Udon::RoboMasterC620 motor{ bus, 2 };
void setup()
{
// CAN通信を開始
bus.begin();
}
void loop()
{
// CAN通信を更新
bus.update();
// 動作電流値を設定
motor.setCurrent(10000);
}

スケッチ例 (速度フィードバック制御)

//
// Copyright (c) 2022-2024 udonrobo
//
#include <Udon.hpp>
// ループ周期制御 (PID制御器のサンプリング周期を設定するために使用)
static Udon::LoopCycleController loopCtrl{ 1000 };
// CAN通信バス
// ロボマスモーター (C620ドライバ経由 モーターID: 2)
static Udon::RoboMasterC620 motor{ bus, 2 };
// 速度をフィードバック制御するPID制御器
static Udon::PidController pid{ 2, 0, 0.03, loopCtrl.cycleUs() };
void setup()
{
bus.begin();
}
void loop()
{
bus.update();
// 目標速度 (rpm)
const double targetSpeed = 5000;
// 速度フィードバック制御をして目標速度に制御する
const double sendCurrent = pid(motor.getVelocity(), targetSpeed, motor.CurrentMin, motor.CurrentMax);
motor.setCurrent(sendCurrent);
loopCtrl.update();
}
PID制御器
Definition PidController.hpp:19

スケッチ例 (速度制御クラスの作成例)

実用的な例として、ロボマスモーターの速度をフィードバック制御するクラスを作成します。複数のモーターを制御する場合、クラスを作成することでコードの見通しを良くすることができます。

//
// Copyright (c) 2022-2024 udonrobo
//
// MotorSpeedFeedback.hpp
//
#pragma once
#include <Udon.hpp>
class MotorSpeedFeedback
{
public:
MotorSpeedFeedback(Udon::RoboMasterC620&& motor, Udon::PidController&& pid)
: motor{ std::move(motor) }
, pid{ std::move(pid) }
{
}
void move(const double rpm)
{
const auto sendCurrent = pid(motor.getVelocity(), rpm, motor.CurrentMin, motor.CurrentMax);
motor.setCurrent(sendCurrent);
}
void stop()
{
pid.clearPower();
motor.setCurrent(0);
}
};
int16_t getVelocity() const
モーターの速度を取得
Definition RoboMasterMotor.hpp:80
void clearPower() noexcept
操作量のクリア
Definition PidController.hpp:124
void setCurrent(int16_t current)
モーターの電流を設定
Definition RoboMasterMotor.hpp:228
Definition Typedef.hpp:94
//
// Copyright (c) 2022-2024 udonrobo
//
// Main.ino
//
#include "MotorSpeedFeedback.hpp"
static Udon::LoopCycleController loopCtrl{ 1000 };
static MotorSpeedFeedback motor1 {
Udon::PidController{ 2, 0, 0.03, loopCtrl.cycleUs() }
};
static MotorSpeedFeedback motor2 {
Udon::PidController{ 2, 0, 0.03, loopCtrl.cycleUs() }
};
static MotorSpeedFeedback motor3 {
Udon::PidController{ 2, 0, 0.03, loopCtrl.cycleUs() }
};
void setup()
{
bus.begin();
}
void loop()
{
bus.update();
motor1.move(5000);
motor2.move(5000);
motor3.move(5000);
loopCtrl.update();
}