背景
cppでコールバックを渡して初期化するインタンスをクラスの変数として保持しようとしたところ、コンストラクタの内部だけではクラスに依存する値となってしまい思うように初期化出来ませんでした。試行錯誤したところ、まとめ上げるクラスのコンストラクタにラムダ式を渡せばそれらしく初期化できたので、備忘録を兼ねてやった内容を記事に残します。
なお、更に良い書き方があれば、コメントなどで教えていただけると嬉しいです。
2020.10.31 追記
コメントで教えていただいた情報を元に、ラムダ式を使わず、rosserialのクラス変数をsubscriberに登録する機能を利用して、subscriberをクラスの変数として定義できました。
よかったらこちらもご覧ください。
Arduinoでrosserialのsubscriberをクラスの変数として扱う方法
なお、上記記事の記述方法は2016年に行われた変更が必要なため、rosserial_arduinoのコマンドを利用してライブラリのコードを生成する必要があります。
使ったもの
- VSCode
シンタックスハイライトや静的解析がArduino IDEより優れていると思うので、こちらで試行錯誤しました。 - PlatformIOプラグイン
VSCodeにインストールしておくことで変数や関数を補完してくれたり、静的解析でコンパイル前にエラー箇所を教えてくれたりするので、プログラム作成が捗ります。 - rosserial_arduinoライブラリ
platformio.iniにlib_deps = rosserial_arduinoと記述することで、古いバージョンにはなりますがコンパイル出来る環境を作れます。
最新のライブラリのコードを利用したい場合は、rosserial_arduinoコマンドでライブラリのコードを生成し、プロジェクトに配置する必要があります。
今回は最新でなくても良いので、lib_depsに依存を追加したPlatformIOのプロジェクトを利用しました。
この記事の目的はrosserial_arduinoのsubscriberをクラスのインスタンスとして保持することです。
クラスにまとめる前のプログラム
rosのsubscriberでtarget_stateという文字列の購読処理をクラス化していきます。クラスにまとめる前は、このような記述で動かせます。
#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);
}
要素をクラスにまとめたけどコンパイル時にエラーが出るプログラム
グローバルな領域に定義していた変数や関数をまとめるクラスを定義してビルドを試みました。#include <Arduino.h>
#include <ros.h>
#include <std_msgs/String.h>
class RosStateManager {
private:
String targetState;
String nameSubTargetState;
ros::Subscriber<std_msgs::String>* 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>(nameSubTargetState.c_str(), &cbReceiveTargetState);
}
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);
}
一見動きそうなのですが、Subscriber初期化時に渡すコールバックがstaticな要素でないという理由でエラーが発生し、ビルドに失敗します。
src/main.cpp: In constructor 'RosStateManager::RosStateManager()':
src/main.cpp:20:87: error: ISO C++ forbids taking the address of an unqualified or parenthesized non-static member function to form a pointer to member function. Say '&RosStateManager::cbReceiveTargetState' [-fpermissive]
subTargetState = new ros::Subscriber<std_msgs::String>(nameSubTargetState.c_str(), &cbReceiveTargetState);
^
src/main.cpp:20:107: error: no matching function for call to 'ros::Subscriber<std_msgs::String>::Subscriber(const char*, void (RosStateManager::*)(const std_msgs::String&))'
subTargetState = new ros::Subscriber<std_msgs::String>(nameSubTargetState.c_str(), &cbReceiveTargetState); ^
Stack over flowでも同様の問題を扱う質問がありましたが、解決方法は示されていませんでした。
ISO C++ forbids taking the address of an unqualified or parenthesized non-static member function to form a pointer to member function
ラムダ式を駆使してクラスに要素をまとめてコンパイルを通したプログラム
何とかしてクラスに閉じ込められないか試行錯誤したところ、コンストラクタにコールバックとして実行したい関数をラムダ式で渡すことでエラー無くコンパイルできました。エラーが発生したプログラムとの差分だけを記述するとこうなります。
class RosStateManager {
public:
RosStateManager(void (*vCbReceiveTargetState)(const std_msgs::String& msg));
};
RosStateManager::RosStateManager(void (*vCbReceiveTargetState)(const std_msgs::String& msg)) {
nameSubTargetState = "target_state_sub";
subTargetState = new ros::Subscriber<std_msgs::String>(nameSubTargetState.c_str(), vCbReceiveTargetState);
}
RosStateManager rosStateManager([](const std_msgs::String& msg) { rosStateManager.cbReceiveTargetState(msg); });
コンストラクタにコールバックで扱いたい関数を内部で呼び出すラムダ式を渡しています。
RosStateManager rosStateManager([](const std_msgs::String& msg) { rosStateManager.cbReceiveTargetState(msg); });
引数として受け取ったコールバック関数は(クラスインスタンスをグローバル変数として定義する場合)グローバルな関数となっているため、それを利用してsubscriberを初期化できます。
RosStateManager::RosStateManager(void (*vCbReceiveTargetState)(const std_msgs::String& msg)) {
nameSubTargetState = "target_state_sub";
subTargetState = new ros::Subscriber<std_msgs::String>(nameSubTargetState.c_str(), vCbReceiveTargetState);
}
エラーが発生したときと重複する部分が多いですが、全体像はこうなります。
#include <Arduino.h>
#include <ros.h>
#include <std_msgs/String.h>
class RosStateManager {
private:
String targetState;
String nameSubTargetState;
ros::Subscriber<std_msgs::String>* subTargetState;
public:
RosStateManager(void (*vCbReceiveTargetState)(const std_msgs::String& msg));
void begin(ros::NodeHandle* nh);
void cbReceiveTargetState(const std_msgs::String&);
String getTargetState();
};
RosStateManager::RosStateManager(void (*vCbReceiveTargetState)(const std_msgs::String& msg)) {
nameSubTargetState = "target_state_sub";
subTargetState = new ros::Subscriber<std_msgs::String>(nameSubTargetState.c_str(), vCbReceiveTargetState);
}
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([](const std_msgs::String& msg) { rosStateManager.cbReceiveTargetState(msg); });
void setup() {
nh.initNode();
rosStateManager.begin(&nh);
}
void loop() {
String targetState = rosStateManager.getTargetState();
nh.spinOnce();
delay(1000);
}
まとめ
コンストラクタでインスタンス初期化時にグローバルな変数ではないためエラーが出ていましたが、その変数をコンストラクタの引数として渡すことで、グローバルな変数として扱えるためビルドできました。別の書き方も分かったので、良かったらこちらもご覧ください。
Arduinoでrosserialのsubscriberをクラスの変数として扱う方法
変更履歴
2020.10.31コメントでsubscriberにクラスの変数を登録する記述方法の情報を共有していただいたので、その情報を元に別の書き方を解説した記事を作成し、それのリンクを背景に追加しました。
より良さそうな書き方を見つけたのですが,こちらはどうでしょうか?
返信削除参考に慣れば幸いです.
https://answers.ros.org/question/258249/publisher-or-subscriber-inside-a-class-rosserial/
情報ありがとうございます。
削除そのような定義方法があるとは知りませんでした。
別の記事として解説し、この記事にもリンクを追加しました。
Arduinoでrosserialのsubscriberをクラスの変数として扱う方法