LoginSignup
1
2

More than 1 year has passed since last update.

RXマイコン C++ フレームワークによる CAN 通信

Posted at

GR-CITRUS と RX72T ボードの CAN 通信


RX マイコンに備わっている CAN ペリフェラル

RX マイコンには、CAN 通信(ISO11898-1仕様準拠)を行う機能を備えた品種が数多くあります。
又、複数チャネルを持った品種もあり、様々な構成に対応可能です。

外部に付加するハードウェアーは、CAN バスに対応したトランシーバーを追加するだけで良く、高品質な通信を簡単に行う事が出来ます。

CAN 通信では、最大8バイトのパケットを、1M B.P.S. 程度で送信、受信し、複数の機器をバス状に接続出来ます。
通信信号は、差動で行い、ノイズに強く、長い通信路でも品質を維持します。
パケットは、ID で管理され、ネゴシエーションが自動で行われ、送信タイミングに特別な制限がありません。
※詳しくは、CAN の解説を参照して下さい。


RXマイコン内蔵の CAN ペリフェラルを使い、実際にソフトウェアを実装して利用するには、それなりのハードルがあるものと思います。
※スマートコンフィギュレーターを使って設定を生成する等も一つの選択肢ではありますが、C++ フレームワークの導入は、それより遥かに簡単で、有意義と思います。
※「can_io.hpp」をインクルードするだけですから・・

RX マイコン C++ フレームワークでは、CAN 通信における運用を一般化して、アプリケーションの実装に専念できるようにしています。
C++ を使ったクラスは、簡単で柔軟性があり、間違いが少ない方法で、データ通信が可能なように設計されています。
CAN レジスターや振る舞いに対する知識は殆ど必要ありません。

サンプルプログラムは、RX62N, RX631, RX64M, RX71M, RX66T, RX72T, RX72N に対応したプロジェクトを用意してあります。
※RX63T、RX651/RX65N でも、Makefile を用意すれば同じように利用可能です。

アプリケーションは、フレームワークに従えば、どのRXマイコンでも同じように動作するように実装出来るので、ソースコードの再利用が可能です。

RX62N: FRK-RX62N(CQ 出版社) / BlueBoard-RX62N_100pin を利用
RX631: GR-CITRUS を利用
RX72N: RX72N Envision Kit を利用

RSCAN について

RX マイコンには、RSCAN と呼ばれるペリフェラルを備えた品種も存在します。(RX220、RX24T など)
RSCAN は、周波数が低めの RX マイコン向けのようで、ソフトウェアの比重を少なくし、なるべくハードウェアーで処理させるものと思います。
※その為、制限もあるものと思います。
現在、C++ フレームワークではサポートしていません。


CAN バス・トランシーバーの接続

RX マイコンの CAN 信号は、CTX、CRX の二本で、RX マイコンの品種によって異なりますが、多くの選択肢からポートにアサイン可能です。

バス・トランシーバーは、3.3V、5V 品があり、電源電圧に対応した IC を選択する必要があります。

CAN バス・トランシーバーの代表的な品種

Texas Instruments: SN65HVD23x

  • 3.3V 動作
  • 5V 不可
  • 最大 1 Mbit/s

NXP Semiconductors: TJA1441

  • 5V 動作
  • I/O 電圧 3.3V、5V 選択可
  • 最大 5 Mbit/s

秋月電子では、現在、3種類の CAN バス・トランシーバーを扱っていますが、電源電圧は 5V なので、マイコンが 3.3V 品の場合、別途 5V が必要です。

Amazon:
SN65HVD230 CANバストランシーバー通信モジュール

SN65HVD230 の参考回路:
CAN_IF.png

CAN バスポート選択肢

RX マイコン C++ フレームワークでは、ポートの選択肢を変更する機構を備えています。

	typedef device::CAN0 CAN0_CH;
	static constexpr auto CAN0_PORT = device::port_map::ORDER::FIRST;

	typedef device::can_io<CAN0_CH, CAN_RXB, CAN_TXB, CAN0_PORT> CAN0;
	CAN0	can0_;

上記のように「device::port_map::ORDER」型を使って、can_io テンプレートクラスに指示します。

選択肢は、各マイコンの「port_map.hpp」に実装があります。
※ハードウェアーマニュアルの「マルチファンクションピンコントローラ(MPC)」の表に記された順番に準拠しています。
上記の場合、FIRST は、以下のように定義されています。

			case peripheral::CAN0:
			// P33/CRX0
			// P32/CTX0
				{
					uint8_t sel = enable ? 0b1'0000 : 0;
					PORT3::PMR.B3 = 0;
					PORT3::PMR.B2 = 0;
					MPC::P33PFS.PSEL = sel;  // ok
					MPC::P32PFS.PSEL = sel;  // ok
					PORT3::PMR.B3 = enable;
					PORT3::PMR.B2 = enable;
				}
				break;

「device::port_map::ORDER::SECOND」とすると、PD2/CRX0、PD1/CTX0 が選択されます。
詳しくは、各マイコンの port_map.hpp を参照して下さい。

GR-CITRUS の場合 (FIRST):
P33/RXD3/SCL3(11) : CRX
P32/TXD3/SDA3(10) : CTX


サンプルプログラムのダウンロードとコンパイル

  • RX マイコン C++ フレームワークは、Github で入手可能です。
  • C++ コンパイラ、gcc-8.3.0 は、ルネサスエレクトロニクスからダウンロード可能です。
  • コンパイルには、MSYS2(Windows)をインストールする必要があります。
  • boost-1.74.0 が必要です。
  • テキストエディターが必要なら、VSCode をインストールして下さい。
  • Windows のターミナルソフトは TeraTerm が便利です。

参照:

コンパイル

GR-CITRUS の場合:
CAN_sample/RX631 に移動、「make」します。

/d/Git/RX/CAN_sample/RX631 % make

...

   text    data     bss     dec     hex filename
  96428   16880   10836  124144   1e4f0 can_sample.elf
rx-elf-objcopy --srec-forceS3 --srec-len 32 -O srec can_sample.elf can_sample.mot
rx-elf-objdump -h -S can_sample.elf > can_sample.lst

※CC-RX コンパイラは、C++11 以降に対応していない為、コンパイルする事が出来ません。


CAN サンプルの使い方

CAN サンプルでは、シリアルターミナルを接続して、対話形式によって CAN 通信を行います。
※通常二台で通信するので、通信実験を行うには、CAN 対応RXマイコン、USB シリアルなど二組必要です。

CAN サンプルでは、CAN0 のインスタンスに対して「can_analizer」クラスによるデータ収集、解析を提供しています。
複数チャネルを有効にした場合、CAN1 のインスタンスに対して、ID フィルターを行うコンパイルオプションがあります。

下記の例は、GR-CITRUS と RX72T-DIY ボードによるものです。
共にシングルチャネルで、双方でデータ送信、受信を実験します。

CAN_command.png


対話コマンド

対話形式で、CAN データ送信、受信の確認等が出来ます。

  • プログラムを起動すると、常に全ての ID を受信します。
  • ID の収集は「can_analizer」クラスで行っており、boost::unoderd_map を使っています。
  • ID の収集がメモリの限界を超えると、メモリ不足でエクセプションがスローされてクラッシュすると思われます。
  • send_loop コマンドにより、乱数で生成した ID、データを連続で送信します。
  • ID を補足する機能(map)は、チャネル0番のみに備わっています。
  • RX64M/RX71M では、2チャネルの CAN を有効にします。
  • CAN1 の受信では、受信したデータを常に表示します。
  • MB-no はメールボックスの番号です。
  • メールボックス関係のコマンドは、デバッグ用です。
  • 受信した CAN フレームは、メモリに格納され、「dump」コマンドで確認出来ます。
  • 同じ ID に新しいデータフレームが来ると、上書きされ、カウンタが進みます。
CAN command version: 1.00
    ext                    set ext-id mode
    std                    set std-id mode
    send CAN-ID [data...]  send data frame
    stat MB-no             stat MCTLx register (MB-no: 0 to 31)
    list MB-no             list MBx register (MB-no: 0 to 31)
    status                 list recv/send error count
    clear [CAN-ID]         clear map
    map [CAN-ID]           Display all collected IDs
    dump CAN-ID            dump frame data
    send_loop NUM [-rtr]   random ID, random DATA, send loop (RTR)
    help                   command list (this)

  Input number: nnn decimal, xnnn hexa-decimal, bnnn binary

ch コマンド

  • 「#define MULTI」を有効にした場合で、CAN1 のインスタンスがある場合に、カレントチャネルを変更する。

valid コマンド

  • VALID フィルターを有効にする、無効にする。

valist コマンド

  • 有効な ID リストを表示。

ext コマンド

  • 拡張 ID モードにする。

std コマンド

  • 標準 ID モードにする。

send CAN-ID [data...] コマンド

  • ID を指定して、データ列を送信。
  • ID のみの場合、リモートフレームの送信。
  • 最大8バイトのデータ列送信。
  • 数値は、10進数、16進数(先頭に x を付ける)、2進数(先頭に b を付ける)を入力可能。

stat MB-no コマンド(デバッグ用)

  • CAN MCTLx レジスターの表示。
  • MB-no は、0~31

list MB-no コマンド(デバッグ用)

  • CAN MBx レジスターの表示。
  • MB-no は、0~31

clear [CAN-ID] コマンド

  • can_analizer クラスの個別 ID 情報のクリア。
  • can_analizer クラスの収集履歴を全てクリア。

map [CAN-ID] コマンド

  • can_analizer クラスが収集した ID の表示。
  • 個別 ID の詳細表示。

dump [CAN-ID] コマンド

  • can_analizer クラスの個別 ID に関するフレームデータ表示。
  • フレームデータは、その ID が最後に取得したものになります。

send_loop [num] コマンド

  • ID を乱数で生成して、データ送信を行う。
  • データ送信を繰り返す数を指定する。

help コマンド

  • コマンドの簡単な説明を表示。

can_io クラス

  • can_io クラスは、CAN フレームを FIFO バッファを通してやりとりし、CAN ハードウェアーの操作を隠蔽しています。
  • 基本的に、ID を指定して、データ列を送るだけです。
  • 受信動作では、CAN フレームクラスにデータがセットされてバッファに積まれます。
  • アプリケーションは、バッファに積まれたデータをディスパッチして所定の動作を行うだけです。
  • 必要な情報を取得する事も出来ます。
  • 詳細は「common/can_io.hpp」を参照下さい。

CAN チャネル

  • RXマイコンの種類により、利用出来るチャネル数が異なります。
  • CAN の通信ラインを利用可能なポートにアサイン出来ない場合があります。
  • ポートのアサインは、port_map.hpp を参照して下さい。
  • 「ハードウェアーマニュアル、マルチファンクションピンコントローラ(MPC)、マルチプル端子の割り当て端子一覧」でも確認する事が出来ます。
  • インスタンスを定義する時、「device::CAN0」のように指定します。
マイコン RX621/RX62N RX631/RX63N RX64M/RX71M RX651/RX65N RX72N RX66T/RX72T
CAN0(CAN)
CAN1
CAN2

受信、送信バッファのサイズ指定

  • utils::fixed_fifo テンプレートクラスを使い、「device::can_frame」型(クラス)で定義します。

can_io テンプレートクラスの「typedef」で、以下のように定義します。(受信、送信、256 フレームの場合)

	// CAN 受信バッファの定義
	typedef utils::fixed_fifo<device::can_frame, 256> CAN_RXB;
	// CAN 送信バッファの定義
	typedef utils::fixed_fifo<device::can_frame, 256> CAN_TXB;

	typedef device::can_io<CAN0_CH, CAN_RXB, CAN_TXB, CAN0_PORT> CAN0;
	CAN0	can0_;
  • サイズは、メインループのリフレッシュレート、CAN フレームの通信頻度により適切な値を定義します。
  • メインループを 1/100 秒で回すのなら、1M B.P.S の通信速度なら、最大のフレーム数は 160 位なので、256 あれば十分でしょう。
  • 16 フレーム以下のサイズを指定した場合、static_assert によりコンパイルを失敗します。

通信速度の指定

CAN の通信速度は、125K ~ 1M の間で選択出来ます。

		//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++//
		/*!
			@brief  CAN スピード型
		*/
		//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++//
		enum class SPEED {
			_50K  =    50'000,	///<  50 Kbps(標準ではない)
			_100K =   100'000,	///< 100 Kbps(標準ではない)
			_125K =   125'000,	///< 125 Kbps
			_250K =   250'000,	///< 250 Kbps
			_500K =   500'000,	///< 500 Kbps
			_750K =   750'000,	///< 750 Kbps(標準ではない)
			_1M   = 1'000'000	///< 1 Mbps
		};

CAN の開始

  • 通信速度を指定して、「start」を呼ぶだけです。
  • 必要な設定は、全て、can_io クラスが行います。
  • 何等かの理由で、開始出来ない場合「false」が返ります。
  • 何も指定しない場合、割り込みの優先度はレベル「1」が使われます。
		if(!can0_.start(CAN::SPEED::_1M)) {
			utils::format("Can't start CAN0...\n");
		} else {
			utils::format("CAN0: SPEED: %u [bps], BRP: %u, TSEG1: %u, TSEG2: %u, SJW: %u\n")
				% can0_.get_speed()
				% can0_.get_bcr_brp() % can0_.get_bcr_tseg1() % can0_.get_bcr_tseg2()
				% can0_.get_bcr_sjw();
			utils::format("    RX Interrupt level: %u, TX Interrupt level: %u\n")
				% static_cast<uint16_t>(can0_.get_rxm_level())
				% static_cast<uint16_t>(can0_.get_txm_level());
		}

フレームの送信

  • フレームの送信は、ID、データ列、データサイズのパラメータで行います。
		//-----------------------------------------------------------------//
		/*!
			@brief  データ送信 @n
					src が「nullptr」、又は「len」が「0」の場合、リモートフレーム送信。
			@param[in]	id		SID+EID の ID
			@param[in]	src		送信データポインター
			@param[in]	len		送信データ数
			@param[in]	ide		拡張モードの場合「true」
			@return 成功なら「true」
		*/
		//-----------------------------------------------------------------//
		bool send(uint32_t id, const void* src, uint32_t len, bool ide = false) noexcept

ID: 1000 で、データ列:1, 2, 3, 0xa, 0xb, 0xc を送信。

    uint8_t data[] = { 1, 2, 3, 0xa, 0xb, 0xc };
    can0_.send(1000, data, sizeof(data));

ID: 900 のリモートフレーム(データ列が無い)を送信。

    can0_.send(900, nullptr, 0);

拡張 ID: 0x10000 のリモートフレーム送信。

    can0_.send(0x10000, nullptr, 0, true);

何等かの理由で送信に失敗すると「false」が返ります。


フレームの受信

  • 受信したフレームは、FIFO バッファに格納されます。
  • 受信したフレーム数を取得します。
  • フレーム数分、受信フレームを取り出して処理します。
  • この処理は、メインループ内で常に動かして、バッファが溢れないように配慮する必要があります。
  • サンプルでは、メインループを 100Hz で動かしています。(一つのターンが 10 ミリ秒)
  • タイミング的に、フレームを受信して応答するまでに、最悪 10 ミリ秒かかります。
  • メインループのリフレッシュレートは、通信の頻度、バッファのサイズ、応答速度などにより決定します。
		while(can0_.get_recv_num() > 0) {
			auto frm = can0_.get_recv_frame();
			utils::format("\nCAN0:\n");
			CAN::list(frm, "  ");
		}

can_frame クラス

  • 受信したフレームは、このクラスにコピーされます。
  • 詳細は、can_frame クラスを参照下さい。

CAN/ID フィルター

  • CAN では、パケットは ID で管理する為、誰かが、パケットを送信すると、全員に同じ物が届きます。
  • その為、自分に必要が無いパケットは無視する事になります。
  • CAN ペリフェラルは、特定の ID にだけ応答するような設定も可能ですが、個数に制限があり、開始する前に決めなければなりません。
  • この仕様では一般化が難しいので、常に全てのパケットを受信するようにしています。
  • RX マイコンは、非常の性能が高いので、全てのパケットに応答しても、全体のパフォーマンスが低下する事は少ないです。
  • C++ を使うと、特定のパケットにだけ応答する機能を簡単に、効率良く実装出来ます。
  • ビットマスクも併用すれば、効率はさらに上がります。(ビットマスクだけなら、さらに簡単)
  • フィルタ処理をソフトウェアで行えば柔軟性は無限大です。

main.cpp には、通過する事が出来る ID リストを使った、フィルターのサンプルコードが含まれます。
※この機能は、「MULTI」チャネルの場合に利用されています。
※シングルチャネルの場合、「can_analizer」クラスが標準で、このクラスが、ID の収集を自動で行っています。

フィルターには、「boost/unordered_set.hpp」を利用しています。

main.cpp の先頭で、「#define VALID_FILTER」をコメントアウトすると、フィルターをスルーします。

有効な ID テーブルは、以下のように定義します。
boost::unordered_set を使っています。

	// 有効な ID だけ通すフィルター
	typedef boost::unordered_set<uint32_t> VALID;
	VALID	valid_{ 0x123, 0x200, 0x300, 0xaaa, 15, 21, 33 };

メインループで、CAN の受信フレームをディスパッチする際に、ID が有効か確認し、無効な ID を無視します。

		while(can1_.get_recv_num() > 0) {
			auto frm = can1_.get_recv_frame();
#ifdef VALID_FILTER
			if(valid_.find(frm.get_id()) != valid_.end()) {  // ID がマッチするか?
#else
			{
#endif
				utils::format("\nCAN1:\n");
				CAN::list(frm, "  ");
			}
		}
  • 「boost::unordered_set」はハッシュを使ったテンプレートクラスで、フィルターの数は、メモリ(RAM)の容量に依存します。
  • ハッシュを使っているので、効率よく(少ないコストで)探します。
  • ID を動的に追加したり、削除したりが簡単に行えます。
  • 「unordered_map」を使えば、指定 ID での挙動(コールバック関数)などをコントロールする事も出来ます。
  • このような実装は、C++ の本領発揮で、本当に便利で簡単です。

まとめ

C++ で実装された CAN 通信クラスのおかげで、CAN 通信を手軽に行う事が出来ます。
組み込みマイコンで、C++ を積極利用する人は少ないのですが、高性能な RX マイコンなら、習得する価値は十分大きいと思います。


ライセンス

boost:

Boost Software License

C++ フレームワーク:

MIT License

1
2
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
1
2