0
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

More than 1 year has passed since last update.

STM32F767ZIでROSserial_stm32を使う

Last updated at Posted at 2023-03-09

 タイトルの通り,ROSserial_stm32を利用してSTM32F767ZIとROSで通信を行います。似たような記事はネット上にいくつかあるのですが,何ヵ所か詰まった部分があるので個人的なメモも兼ねて書いていこうと思います。
 前提としてUbuntu20.04にROS-noeticとCubeIDEをインストールしておいてください。

ターミナルでの作業

ROSserialなどのインストール

 ROSserialをインストールします。

$ sudo apt-get install ros-noetic-rosserial

 rosserial_stm32をSrcにcloneします。

$ cd ~/catkin_ws/src
$ git clone https://github.com/yoneken/rosserial_stm32
$ cd ..
$ catkin_make

roslibの生成

 exampleのchatterを適当な場所にコピーして,そこにroslibを生成します。

$ roscd rosserial_stm32
$ cd src/ros_lib/examples
$ cp -r chatter ~/Documents
$ cd ~/Documents/chatter

 そのフォルダ内で以下のコードを実行します。一番後ろの.を忘れないでください。

$ rosrun rosserial_stm32 make_libralies.py .

 この時、選択肢が出てきたら2を選択します。

エラーが出た場合はこちらも参考に
/usr/bin/env:'python':そのようなファイルやディレクトリはありません

と表示された場合は

$ sudo apt-get install python-is-python3

もしくは

$ sudo apt update
$ sudo apt upgrade

で改善するかも。

 最後にInc内のcppファイルをSrcに移動させておきましょう。

$ mv Inc/duration.cpp Inc/time.cpp Src

CubeIDEでの作業

 次にCubeIDEを開き、FileNewSTM32 Projectと順番にクリックします。
 STM32F767ZIのボードを選択してからNext>→適当なプロジェクト名を入力→Finishとし,プロジェクトを生成します。

.iocファイルの設定

ピン設定

PB8ピンをUSART3_TXに設定し、ユーザーラベルをVCP_TXに,
PB9ピンをUSART3_RXに設定し、ユーザーラベルをVCP_RXにしてください。
image.png

USART3の設定

ConnectivityUSART3の設定を変更します。

Mode Asynchronous
  • Parameter Settings
Baud Rate 57600
  • NVIC Settings
    USART3 global interruptをチェックします。
    image.png

  • DMA Settings
    AddUSART3TXとして,PriorityHighに変更します。
    AddUSART3RXとして,PriorityHighModeCircularに変更します。
    image.png

TIM2の設定

ClockSource InternalClock

Clock Configurationの設定

HCLK(MHz)をある程度大きな値にします(64MHzで動作確認済み)。
image.png

ソースコード関連の作業

 先程コピーしたChatterのIncSrcをコピーして,今回作成したCubeIDEのプロジェクトのCoreフォルダ内に貼り付けます。
 できたらCubeIDEに戻って,上のスタンプマークからGenerateCodeしましょう。

プロジェクト設定の変更

 Project Explorerに表示されているプロジェクト名を右クリックして
propertiesC/C++GeneralFile Typesと進み,Use project settingsにチェックを入れます。
 New...をクリックして,

Pattern:*.h
Type: C++ Header File

を追加します。Apply and Closeから閉じましょう。

 同様にプロジェクト名を右クリックしてConvert to C++をクリックします。

STM32Hardware.hの修正

Core/Inc/Stm32Hardware.hを修正します。

  • 38行目
#define STM32F3xx
↓    ↓    ↓ 変更する
#define STM32F7xx
  • 52行目
extern UART_HandleTypeDef huart2;
↓    ↓    ↓    ↓    ↓ 変更する
extern UART_HandleTypeDef huart3;
  • 69行目
huart(&huart2), rind(0), twind(0), tfind(0){
↓    ↓    ↓    ↓    ↓    ↓ 変更する
huart(&huart3), rind(0), twind(0), tfind(0){
  • 107行目
HAL_UART_Transmit_DMA(huart, &(tbuf), twind);
↓    ↓    ↓    ↓    ↓    ↓ 変更する
HAL_UART_Transmit_DMA(huart, tbuf, twind);

main.cの修正

 以下のように変更します。

/*USER CODE BEGIN Include*/
#include "mainpp.h"
/*USER CODE END Include*/

mainpp.cppの変更

 今回はROSから送られてきた文章をそのままオウム返しするコードを書きます。

コード全文
#include <mainpp.h>
#include <ros.h>
#include "std_msgs/String.h"

ros::NodeHandle nh;

void callback(const std_msgs::String&);

std_msgs::String str_msg
ros::Publisher f7_pub("f7_data", &str_msg);
ros::Subscriber<std_msgs::String> ros_sub("ros_data", &callback);

void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart){
  nh.getHardware()->flush();
}

void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart){
  nh.getHardware()->reset_rbuf();
}

void setup(void)
{
  nh.initNode();
  nh.advertise(f7_pub);
  nh.subscribe(ros_sub);
}

void loop(void)
{
  nh.spinOnce();
}

void callback(const std_msgs::String& ros_data){
	f7_pub.publish(&ros_data);
}

 ビルドできたらマイコンに書き込みましょう。

テスト

 初回は以下のコマンドを打ってください。

$ sudo adduser $USER dialout

 通常はここからです。すべて別のターミナルで起動します。

$ roscore
$ rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0
$ rostopic pub -r 2 /ros_data std_msgs/String "data: 'hello world!'"
$ rostopic echo /f7_data 

ros_serial.png
 (画像右上)rostopic echoで受信できていますね!

 ちなみに送受信のデータ量を増やしたければInc/ros.htypedefの部分をいじれば良いっぽいです。

typedef NodeHandle_<STM32Hardware, MAX_SUBSCRIBEARS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE> NodeHandle;

MAX_SUBSCRIBEARSはサブスクライバーの最大数,
MAX_PUBLISHERSはパブリッシャーの最大数,
INPUT_SIZEは最大受信データサイズ,
OUTPUT_SIZEは最大送信データサイズです。

終わり

 f303などでは割とすんなり動いたのですが,f7だとなかなかうまくいかなかず結構苦労したので,この記事が同じく苦労している人の助けになればと思います。なおcan通信と同時に行うとエラーが発生する?ので解決待ち。

0
0
1

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
0
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?