背景
以前ラムダを利用してrosserial-arduinoのsubscriberをそれらしくクラスの変数として扱う方法を紹介しました。その記事に対して、もっと良い書き方があるとコメントで教えていただき、試してみると素晴らしく綺麗に書けました。
備忘録を兼ねて書き方を共有します。
使ったもの
- Arduinoのプログラム開発環境
ArduinoIDEやPlatformIOで開発できます。 - rosserial-arduinoで生成したArduino向けのrosserialライブラリ
今までの記事で紹介していたライブラリマネージャなどでインストールできるrosserial_arduinoでは、コードが古くて今回の記述を使えませんでした。
そのため、rosserial-arduinoをインストールしてライブラリのコードを生成してください。
Ubuntu20.04でnoeticからライブラリのコード生成は下記のコマンドでできました。sudo apt install ros-noetic-ros-serial-arduino
cd [ライブラリを置きたいフォルダ] # Arduino: ~/Ardlino/libraries, PlatformIO: [プロジェクトのフォルダ]/libs
rosrun rosserial_arduino make_libraries.py .
クラスにまとめる前のプログラム
ラムダ式を利用した時の例と同じプログラムをクラス化します。#include <Arduino.h>
#include <ros.h>
#include <std_msgs/String.h>
String targetState;
String nameSubTargetState = "target_state_sub";
void cbReceiveTargetState(const std_msgs::String& msg) {
targetState = msg.data;
}
ros::Subscriber<std_msgs::String> subTargetState(nameSubTargetState.c_str(), cbReceiveTargetState);
ros::NodeHandle nh;
void setup() {
nh.initNode();
nh.subscribe(subTargetState);
}
void loop() {
nh.spinOnce();
delay(1000);
}
クラスにまとめたプログラム
教えていただいたrosの掲示板でのやりとりを元にクラスにまとめるとこうなりました。#include <Arduino.h>
#include <ros.h>
#include <std_msgs/String.h>
class RosStateManager {
private:
String targetState;
String nameSubTargetState;
ros::Subscriber<std_msgs::String, RosStateManager>* subTargetState;
public:
RosStateManager();
void begin(ros::NodeHandle* nh);
void cbReceiveTargetState(const std_msgs::String&);
String getTargetState();
};
RosStateManager::RosStateManager() {
nameSubTargetState = "target_state_sub";
subTargetState = new ros::Subscriber<std_msgs::String, RosStateManager>(
nameSubTargetState.c_str(),
&RosStateManager::cbReceiveTargetState,
this);
}
void RosStateManager::begin(ros::NodeHandle* nh) {
nh->subscribe(*subTargetState);
}
void RosStateManager::cbReceiveTargetState(const std_msgs::String& msg) {
targetState = msg.data;
}
String RosStateManager::getTargetState() {
return targetState;
}
ros::NodeHandle nh;
RosStateManager rosStateManager;
void setup() {
nh.initNode();
rosStateManager.begin(&nh);
}
void loop() {
String targetState = rosStateManager.getTargetState();
nh.spinOnce();
delay(1000);
}
要所を解説します。
2016年の変更で上記のようにクラスの変数として扱うための定義方法が追加され、任意のクラスをsubscriberの定義時の型の第2引数として渡せるようになりました。
ros::Subscriber<std_msgs::String, RosStateManager>* subTargetState;
これにより、クラスの関数内で定義する際に自信(this)をsubscriberの第3引数として渡すことで、第2引数で指定した関数をsubscriberとして実行してくれます。
RosStateManager::RosStateManager() {
nameSubTargetState = "target_state_sub";
subTargetState = new ros::Subscriber<std_msgs::String, RosStateManager>(
nameSubTargetState.c_str(),
&RosStateManager::cbReceiveTargetState,
this);
}
そのおかげでラムダ式を利用したときは混沌としていたインスタンスの定義が、冗長な引数無しでできるようになりました。
RosStateManager rosStateManager;
0 件のコメント :
コメントを投稿