0
1

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 3 years have passed since last update.

CLI版PlatformIOでArduino開発

Last updated at Posted at 2020-12-06

#概要
Raspberry Pi - Arduino間でのrosserialプログラムを開発環境PlatformIOを使用して作成し,実行するまでをまとめた.

#実行環境

  • Arduino Uno
  • Raspberry Pi 3 model B+
  • Ubuntu Mate 18.04.5 LTS (arm64)

以降,Raspberry Pi にPlatformIOの開発環境が用意出来ている前提ですすめる.

rosserialのインストール

$ rosversion -d
melodic
$ sudo apt-get install ros-melodic-rosserial-arduino
$ sudo apt-get install ros-melodic-rosserial

#プロジェクトの作成
platformio init -b {ボードID}でプロジェクトを作成する.

$ mkdir myproject
$ cd myproject
$ platformio init -b uno

使用したいボードのIDはplatformio boards "{ボード名}"で検索可能.
例)使用するボードがArduino Mega 2560ならIDはmegaatmega2560

#rosserialプログラムの作成
プロジェクトのディレクトリsrc内でC++のファイルを作成する.

$ ls
README.md  include  lib  platformio.ini  src  test
$ cd src
$ vi main.cpp

動作確認用として,Arduinoのデジタル11番ピンに接続したLEDをRaspberry Piのコンソールで入力した数値ぶんだけ点滅させるサンプルプログラムを用意した.

main.cpp
#include "Arduino.h"
#include <ros.h>                                                                                     
#include <std_msgs/Int16.h>

ros::NodeHandle nh;

void messageCb(const std_msgs::Int16& msg){
	for(int i=0; msg.data>i; i++){
		digitalWrite(11, HIGH);
		delay(100);
		digitalWrite(11, LOW);
		delay(100);
	}
}

ros::Subscriber<std_msgs::Int16> sub("blink_times", &messageCb );

void setup(){
	pinMode(11, OUTPUT);
	digitalWrite(11, LOW); 

	nh.initNode();
	nh.subscribe(sub);
}

void loop(){
	nh.spinOnce();
	delay(1);
}
/****** END OF FILE *********/        

またRaspberry Piからの送信用として,適当なパッケージに以下のプログラムを用意しておく.

led_ctl.py
#!/usr/bin/env python                                                                                  
import rospy
from std_msgs.msg import Int16

rospy.init_node('led_ctl')
pub = rospy.Publisher('blink_times', Int16, queue_size=1)
blink = Int16()

while not rospy.is_shutdown():
    print 'Input blink_times:'
    blink.data = input()
    pub.publish(blink)

#---- END OF FILE ----

ROSのパッケージの作成や環境変数の設定などに関する説明は省く.

#プログラムのビルド
ArduinoをRaspberry Piのポートに接続する.

デバイスファイルのパーミッションを読み書き可能に設定しておく.

$ sudo chmod 666 /dev/ttyACM0

pio run --target uploadでビルド,ボードへの書き込みを実行.

$ cd ../
$ pio run --target upload

#ライブラリの追加
ここで,ROSのヘッダファイルが無いと,下記のようなエラーが出てくる.

Processing uno (platform: atmelavr; board: uno; framework: arduino)
---------------------------------------------------------------------------------------------------------
Verbose mode can be enabled via `-v, --verbose` option
CONFIGURATION: https://docs.platformio.org/page/boards/atmelavr/uno.html
PLATFORM: Atmel AVR (3.0.0) > Arduino Uno
HARDWARE: ATMEGA328P 16MHz, 2KB RAM, 31.50KB Flash
DEBUG: Current (avr-stub) On-board (avr-stub, simavr)
PACKAGES: 
 - framework-arduino-avr 5.1.0 
 - tool-avrdude 1.60300.200527 (6.3.0) 
 - toolchain-atmelavr 1.50400.190710 (5.4.0)
LDF: Library Dependency Finder -> http://bit.ly/configure-pio-ldf
LDF Modes: Finder ~ chain, Compatibility ~ soft
Found 5 compatible libraries
Scanning dependencies...
No dependencies
Building in release mode
Compiling .pio/build/uno/src/main.cpp.o
src/main.cpp:1:47: fatal error: ros.h: No such file or directory

*************************************************************
* Looking for ros.h dependency? Check our library registry!
*
* CLI  > platformio lib search "header:ros.h"
* Web  > https://platformio.org/lib/search?query=header:ros.h
*
*************************************************************

compilation terminated.
*** [.pio/build/uno/src/main.cpp.o] Error 1
====================================== [FAILED] Took 4.75 seconds ======================================

CLI > platformio lib search "header:ros.h"と書いてあるので調べてみる.

$ platformio lib search "header:ros.h"

いろいろライブラリが出てくるので,Ardunoでのrosserialに関係してそうなものを選び,以下のようにplatformio.iniの末尾に追記する.

※ライブラリ名の前の空白はTabで入力しないとエラーを吐く

platformio.ini
lib_deps =
    ros_lib_melodic
    rosserial_arduino
    Rosserial Arduino Library
    ros_lib Arduino

platformio.iniを保存してもう一度ビルドすると,ライブラリを自動的にインストールして書き込んでくれる.

$ pio run --target upload

エラーを吐かずに書き込みまで成功するはず.

#動作確認
作成したサンプルプログラムを実行してみる.

$ roscore
$ rosrun rosserial_python serial_node.py /dev/ttyACM0

送信側のled_ctl.pyを実行すると,コンソールにInput blink_times:と出力される.

$ chmod +x led_ctl.py
$ ./led_ctl.py
Input blink_times:

数値を入力するとその回数だけArduinoに接続したLEDが点滅する.

#参考文献

ROSのrosserialを使ってArduinoでLチカをする - Qiita
(https://qiita.com/nnn112358/items/059487952eb3f9a5489b 最終閲覧日:2020/12/6)

ゆっくりラズパイ活用講座 - RaspberryPiとArduinoを連携する【USBシリアル】 
(http://7th-chord.jp/sara_tsukiyono/index.php?cl=rp&rp=zw&zw=02_02 最終閲覧日:2020/12/6)

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

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?