環境
この記事は以下の環境で動いています。
項目 | 値 |
---|---|
CPU | Core i5-8250U |
Ubuntu | 16.04 |
ROS | Kinetic |
インストールについてはROS講座02 インストールを参照してください。
またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。
概要
一定間隔で処理を行いたいときは基本的にはwhile文とloop_rate.sleep()
とspinOnce()
を使います。しかしこの方法ではループを1種類しか回せません。timerを使うことでメインループを使わずに一定間隔の処理を行えます。
ソースコード
ros timerを使うROSノード
#include <ros/ros.h>
#include <std_msgs/String.h>
ros::Publisher chatter_pub;
void timer_callback(const ros::TimerEvent& e)
{
std_msgs::String msg;
msg.data = "hello world!";
ROS_INFO("publish: %s", msg.data.c_str());
chatter_pub.publish(msg);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "basic_timer_talker");
ros::NodeHandle nh;
chatter_pub = nh.advertise<std_msgs::String>("chatter", 10);
ros::Timer timer = nh.createTimer(ros::Duration(0.1), timer_callback);
ros::spin();
return 0;
}
下から4行目のros::Timer timer = nh.createTimer(ros::Duration(0.1), timer_callback);
でタイマーを生成しています。1つ目の引数は実行間隔です。つまり10Hzで動作させたいならros::Duration(0.1)
と入れます。2つ目がtimerが起動したときに起動するコールバック関数です。またデフォルトだとタイマーは繰り返しになります。つまり無限に0.1秒ごとにコールバック関数が呼ばれます。
コールバック関数はvoid timer_callback(const ros::TimerEvent& e)
のように宣言します。引数でいろいろと情報をくれますが、あまり大事でないので今のところは触れません。
publishを行うのがコールバック関数内に移ったので、publisherの宣言をグローバル領域で行わないといけないことに注意です。
CmakeList
add_executable(basic_timer_talker src/basic_timer_talker.cpp)
target_link_libraries(basic_timer_talker
${catkin_LIBRARIES}
)
ビルド
cd ~/catkin_ws
catkin build
実行
3つのターミナルで実行します。
roscore
rosrun basic_lecture basic_timer_talker
rostopic echo /chatter
すると3つ目のターミナルで以下のような出力があります。およそ10Hzで出力されているのが見えます。
data: "hello world!"
---
data: "hello world!"
---
data: "hello world!"
---