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

CAN 通信は自動車内部の通信等工業系で主に用いられる通信手法です。差動通信であるためノイズ耐性が高く、またバス型方式をとっているため容易に配線が可能です。

送信者は送信ノードと呼ばれ、各送信ノードは自由なタイミングで送信を行えます。他の送信ノードが送信中の場合、調停を行い送信タイミングを自動的に調整します。受信者は受信ノードと呼ばれ、送信者が持つ識別子を識別し受信を行います。

CAN 通信クラスは、通信バスクラス、送受信ノードクラスから構成され、組み合わせて使用します。

  • 通信バスクラス
  • 送信ノードクラス
  • 受信ノードクラス
  • バイト列を直接送受信
  • デバッグ
  • クラスの組み合わせ色々

個別インクルード

通信バスクラス

送受信処理、通信が行えているかどうかのチェックを行います。使用するマイコンや CAN コントローラーによって適切なバスクラスを選択します。

CAN2.0A プロトコルで通信を行います。そのため ID は 0x000~0x7FF の範囲で使用できます。

CAN2.0A は 一度に 8 バイトのデータしか送信できません。8 バイトより長いデータは分割して送受信します。この時、1 バイト目にインデックス番号が付与されます。8 バイト以下のデータはインデックスを付与せず送受信するため、他の CAN デバイス (市販モーター等) との通信にも使用できます。詳しくは バイト列を直接送受信 を参照ください。

■ Teensy

内臓 CAN コントローラーを使用し CAN 通信を行います。受信ノードが 8 個以内の場合、受信フィルタの設定を行います。

flowchart LR
subgraph 基板
Teensy --CAN TX/RX--> CANトランシーバー
end
CANトランシーバー --CAN H/L--> CANバス

クラスのテンプレートパラメーターに使用する CAN ポートを指定します。

Teensy用 CANバスクラス
Definition CanBusTeensy.hpp:31
詳細な設定

Udon::CanBusTeensy::Config 構造体を用いて詳細な設定が可能です。構造体は次のように定義されています。

struct Config
{
uint32_t transmitInterval = 5; // 送信間隔 [ms]
uint32_t transmitTimeout = 100; // 送信タイムアウト時間 [ms]
uint32_t receiveTimeout = 100; // 受信タイムアウト時間 [ms]
uint32_t canBaudrate = 1'000'000; // CAN通信速度 [bps]
};
.transmitInterval = 5,
.transmitTimeout = 100,
.receiveTimeout = 100,
.canBaudrate = 1'000'000,
});

回路

Teensy4.0 + MCP2562 の例を示します。

image

部品名 会社名 URL
Teensy4.0 スイッチサイエンス https://www.switch-science.com/products/5877
MCP2562 秋月電子通商 https://akizukidenshi.com/catalog/g/g114383/
終端抵抗用スイッチ 秋月電子通商 https://akizukidenshi.com/catalog/g/g102627/
  • Teensy4.0 の CAN1 ポートのデフォルト端子と接続しています。
  • CAN の信号は CAN-H CAN-L 線から出力されます。
  • 同じ名前の配線は内部的に接続されています。
  • 終端抵抗の有無を切り替えられるようにする必要があります。
  • MCP2562 の VIO 端子は、トランシーバー側 IO 端子の基準電源として機能します。マイコン側の IO 端子電圧(0〜3.3V)に一致するように、この端子は 3.3V に接続されています。

■ Raspberry Pi Pico

外部 CAN コントローラー (MCP2515 or MCP25625) を使用し CAN 通信を行います。受信ノードが 6 個以内の場合、受信フィルタの設定を行います。受信フィルタが有効の場合、登録していない ID の受信を関知しないため、不要な処理の削減につながります。

flowchart LR
subgraph 基板
RaspberryPiPico --SPI--> CANコントローラー --CAN TX/RX--> CANトランシーバー
end
CANトランシーバー --CAN H/L--> CANバス
static Udon::CanBusSpi bus;
Raspberry Pi Pico用バスクラス
Definition CanBusSpiPico.hpp:24
詳細な設定

ピン設定等は設定値を格納するための構造体 Udon::CanBusSpi::Config を用いて設定します。これらの構造体は次のように定義されています。

struct Config
{
// SPI 関連
spi_inst_t* channel = spi_default; // SPI チャンネル (spi0, spi1)
uint8_t cs = PICO_DEFAULT_SPI_CSN_PIN; // チップセレクトピン
uint8_t mosi = PICO_DEFAULT_SPI_TX_PIN; // MOSIピン (TX)
uint8_t miso = PICO_DEFAULT_SPI_RX_PIN; // MISOピン (RX)
uint8_t sck = PICO_DEFAULT_SPI_SCK_PIN; // クロックピン
uint8_t interrupt = 20; // 受信割り込みピン
uint32_t spiClock = 1'000'000; // SPIクロック周波数 [Hz]
// CAN 関連
uint32_t transmitInterval = 5; // 送信間隔 [ms]
uint32_t transmitTimeout = 100; // 送信タイムアウト時間 [ms]
uint32_t receiveTimeout = 100; // 受信タイムアウト時間 [ms]
CAN_SPEED canBaudrate = CAN_1000KBPS; // CAN通信速度
CAN_CLOCK mcpClock = MCP_16MHZ; // トランシーバー動作クロック周波数 [Hz]
};

回路

Raspberry Pi Pico + MCP25625 の例を示します。MCP25625 は CAN コントローラー、トランシーバーが統合されたチップで、外付け発振子を必要とします。

image

部品名 会社名 URL
Raspberry Pi Pico 秋月電子通商 https://akizukidenshi.com/catalog/g/g116132/
MCP25625 秋月電子通商 https://akizukidenshi.com/catalog/g/g112663/
セラミック発振子 16MHz 秋月電子通商 https://akizukidenshi.com/catalog/g/g109576/
終端抵抗用スイッチ 秋月電子通商 https://akizukidenshi.com/catalog/g/g102627/
  • Raspberry Pi Pico の spi0 のデフォルト端子と接続しています。
  • CAN の信号は CAN-H CAN-L 線から出力されます。
  • 同じ名前の配線は内部的に接続されています。
  • 終端抵抗の有無を切り替えられるようにする必要があります。
  • MCP25625 の VIO 端子は、トランシーバー側 IO 端子の基準電源として機能します。マイコン側の IO 端子電圧(0〜3.3V)に一致するように、この端子は 3.3V に接続されています。

送信ノードクラス

Udon::CanWriter<T>

T に指定された型のオブジェクトをバスへ送信します。

static Udon::CanWriter<Udon::Vec2> writer{ bus, 0x010 }; // Udon::Vec2 をノードID 0x010 として送信
void setup()
{
bus.begin();
}
void loop()
{
bus.update();
Udon::Vec2 vector{ 100.0, 200.0 }; // 送信するオブジェクトをインスタンス化
writer.setMessage(vector); // オブジェクトを登録
delay(10);
}
void begin()
通信開始
Definition CanBusSpiPico.hpp:23
void update()
バス更新
Definition CanBusSpiPico.hpp:121
CAN通信 送信クラス
Definition CanWriter.hpp:23
二次元ベクトル
Definition Vector2D.hpp:22

受信ノードクラス

Udon::CanReader<T>

T に指定された型のオブジェクトをバスから取得します。送信ノードの T と同じ型である必要があります。

static Udon::CanReader<Udon::Vec2> reader{ bus, 0x010 }; // ノードID 0x010 から Udon::Vec2を受信
void setup()
{
bus.begin();
}
void loop()
{
bus.update();
if (const Udon::Optional<Udon::Vec2> vector = reader.getMessage()) // データ取得
{
// 受信成功
Serial.print(vector->x); Serial.print('\t');
Serial.print(vector->y); Serial.print('\n');
}
else
{
// 受信失敗(データ破損検出、通信タイムアウト等)
Serial.println("receive failed!!");
}
delay(10);
}
void update()
バス更新
Definition CanBusTeensy.hpp:89
void begin()
通信開始
Definition CanBusTeensy.hpp:37
CAN通信 受信クラス
Definition CanReader.hpp:24
オプショナル型
Definition Optional.hpp:62

getMessage は正常にオブジェクトが受信できたかどうか判定できるように Udon::Optional<T> を返します。通信エラー時は Udon::nullopt が返されます。 Udon::Optional は値と値が有効であるかを持つクラスで、 operator bool によって値を保持するか取得できます。if 文で正常に受信できたかどうかで分岐できます。

Udon::Optional<T>::operator-> で保持しているオブジェクトのメンバへアクセスでき、Udon::Optional<T>::operator* で optional が持っているオブジェクトの参照を取得できます。

バイト列を直接送受信

ロボマスモーター等の CAN 通信を用いる市販のモーターをドライブするには、バイト列で直接やり取りする必要があります。この場合、チェックサムを付与する CanReader CanWriter クラスは使用できません。バイト列を直接やり取りするには送受信ノードを createTx createRx 関数を用いて作成し、作成したノードに対しデータの書き込み、読み出しを行います。

8バイトより長いデータは分割して送受信されます。この時、1 バイト目にインデックス番号が付与されます。8 バイト以下のデータはインデックスを付与せず送受信します。

■ 送信ノード

送信ノードの構造

struct CanTxNode
{
const uint32_t id; // メッセージ ID (バスが書き込み、ユーザーが読み取り)
std::vector<uint8_t> data; // 送信データ (ユーザーが書き込み、バスが読み取り)
uint32_t transmitMs; // 最終通信時刻 (バスが書き込み、ユーザーが読み取り)
};

基本的な例

static Udon::CanTxNode* txNode = bus.createTx(0x000 /*id*/, 8 /*length*/);
void setup()
{
bus.begin();
}
void loop()
{
txNode->data[0] = 0x11; // データを登録
txNode->data[1] = 0x22;
txNode->data[2] = 0x11;
txNode->data[3] = 0x22;
txNode->data[4] = 0x11;
txNode->data[5] = 0x22;
txNode->data[6] = 0x11;
txNode->data[7] = 0x22;
bus.update();
}
CanTxNode * createTx(uint32_t id, size_t length) override
送信ノードをバスに参加させる
Definition CanBusTeensy.hpp:177
CAN送信ノード
Definition ICanBus.hpp:17
std::vector< uint8_t > data
Definition ICanBus.hpp:20

ラッパークラスを作成する例

#include <Udon.hpp>
class MyCanWriter
{
Udon::CanTxNode* txNode;
public:
MyCanWriter(Udon::ICanBus& bus, uint8_t id, size_t length)
: txNode(bus.createTx(id, length))
{
}
void update()
{
txNode->data[0] = 0x11; // データを登録
txNode->data[1] = 0x22;
}
};
static MyCanWriter writer{ bus, 0x000, 10 };
void setup()
{
bus.begin();
}
void loop()
{
bus.update();
writer.update();
}
CANバス管理クラス インターフェース
Definition ICanBus.hpp:49

■ 受信ノード

受信ノードの構造

struct CanRxNode
{
const uint32_t id; // メッセージID (バスが書き込み、ユーザーが読み取り)
std::vector<uint8_t> data; // 受信データ (バスが書き込み、ユーザーが読み取り)
void (*onReceive)(void*); // 受信時コールバック (ユーザーが書き込み)
void* param; // コールバックパラメータ (ユーザーが書き込み)
uint32_t transmitMs; // 最終通信時刻 (バスが書き込み、ユーザーが読み取り)
};

基本的な例

static Udon::CanRxNode* rxNode = bus.createRx(0x000 /*id*/, 8 /*length*/);
void setup()
{
bus.begin();
}
void loop()
{
bus.update();
Serial.print(rxNode->data[0]); Serial.print('\t');
Serial.print(rxNode->data[1]); Serial.print('\n');
}
CanRxNode * createRx(uint32_t id, size_t length) override
受信ノードをバスに参加させる
Definition CanBusTeensy.hpp:192
CAN受信ノード
Definition ICanBus.hpp:28
std::vector< uint8_t > data
Definition ICanBus.hpp:31

コールバックを行う例

受信ノードには、受信時に呼び出すコールバック関数を登録できます。一つのバイト列に対して毎度コールバック関数を呼ぶため、データの取りこぼしが起きません。

8 バイトより長いバイト列は複数のフレームに分割されて送信されます。この時、コールバック関数が呼び出されるのは最終フレーム受信時です。

コールバック関数には param メンバを通じて任意の void ポインタを渡せます。以下の例では CanRxNode ポインタを渡しています。

static Udon::CanRxNode* rxNode = bus.createRx(0x000 /*id*/, 8 /*length*/);
// コールバック関数
void onReceive(void* param)
{
auto node = static_cast<Udon::CanRxNode*>(param); // 受信ノードを void ポインタから復元
Serial.print(node->id); Serial.print('\t');
Serial.print(node->data[0]); Serial.print('\t');
Serial.print(node->data[1]); Serial.print('\t');
Serial.print(node->data[2]); Serial.print('\t');
Serial.print(node->data[3]); Serial.print('\t');
Serial.print(node->data[4]); Serial.print('\t');
Serial.print(node->data[5]); Serial.print('\t');
Serial.print(node->data[6]); Serial.print('\t');
Serial.print(node->data[7]); Serial.print('\n');
}
void setup()
{
bus.begin();
rxNode->onReceive = onReceive; // 受信時コールバック関数を登録
rxNode->param = rxNode; // コールバック関数の引数へ受信ノードを渡すよう指定
}
void loop()
{
bus.update();
}
void * param
Definition ICanBus.hpp:34
void(* onReceive)(void *)
Definition ICanBus.hpp:33

ラッパークラスを作成する例

param メンバを通じて this ポインタを渡すことで、メンバへアクセスできます。CanReader クラスもこの機能を用いてメンバ関数のコールバックを行っています。

#include <Udon.hpp>
class MyCanReader
{
Udon::CanRxNode* rxNode;
int16_t value;
public:
MyCanReader(Udon::ICanBus& bus, uint8_t id, size_t length)
: rxNode(bus.createRx(id, length))
{
rxNode->onReceive = onReceive;
rxNode->param = this; // this ポインタを登録
}
MyCanReader(MyCanReader&& other)
: rxNode(other.rxNode)
{
rxNode.param = this; // 移動した場合、コールバック時にアクセスしたいインスタンスが変わるので this ポインタを登録しなおす。
}
void update()
{
Serial.println(value);
}
private:
static void onReceive(void* param)
{
auto self = static_cast<MyCanReader*>(param); // this ポインタを復元
self->value = (self->rxNode->data[0] << 8) | self->rxNode->data[1];
}
};
static MyCanReader reader{ bus, 0x000, 10 };
void setup()
{
bus.begin();
}
void loop()
{
bus.update();
reader.update();
}

デバッグ

全 CAN 通信クラスは show() メンバ関数を持っており、通信の状態をシリアルモニターへ送信します。

bus.show(); // バスに参加している送受信ノードの列挙、送受信データ(バイト列)を表示
reader.show(); // 受信データを表示
writer.show(); // 送信データを表示
void show() const
バス情報を表示する
Definition CanBusTeensy.hpp:125

クラスの組み合わせ色々

一つのバスへ複数送受信ノードが参加する(よくある)

static Udon::CanWriter<Udon::Vec2> writer1{ bus, 0x011 };
static Udon::CanWriter<Udon::Vec2> writer2{ bus, 0x012 };
static Udon::CanReader<Udon::Vec2> reader1{ bus, 0x013 };
static Udon::CanReader<Udon::Vec2> reader2{ bus, 0x014 };

二つのバスへ受信ノードが参加する(バスの負荷分散目的)

static Udon::CanWriter<Udon::Vec2> writer1{ bus1, 0x011 };
static Udon::CanReader<Udon::Vec2> reader1{ bus1, 0x012 };
static Udon::CanWriter<Udon::Vec2> writer2{ bus2, 0x011 }; // バスが異なるのでID重複してもOK
static Udon::CanReader<Udon::Vec2> reader2{ bus2, 0x012 };

異なる種類のバスへ参加する(激レア)

static Udon::CanWriter<Udon::Vec2> writer1{ bus1, 0x011 };
static Udon::CanReader<Udon::Vec2> reader1{ bus1, 0x013 };
static Udon::CanBusSpi bus2({ ... });
static Udon::CanWriter<Udon::Vec2> writer2{ bus2, 0x012 };
static Udon::CanReader<Udon::Vec2> reader2{ bus2, 0x014 };