Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Enkoder Konum Bilgisini Okumak icin Basit Subscriber Yazma
Description: Bilgisayarda, konum bilgisi için c++ ile Subscriber yazmaTutorial Level: BEGINNER
Catkin çalışma alanında evarobot_odom_subs adında paket oluşturulur.
> cd ~/catkin_ws/src > catkin_create_pkg evarobot_odom_subs nav_msgs rospy roscpp
Oluşturulan paketin içerinde /src klasörü altında odom_listener.cpp isminde c++ dosyası oluşturulur.
> cd ~/catkin_ws/src/evarobot_odom_subs > mkdir -p ~/catkin_ws/src/evarobot_odom_subs/src > cd src > gedit odom_listener.cpp
odom_listener.cpp dosyasının içerisine yazılacak kod aşağıda verilmektedir.
1 #include "ros/ros.h"
2 #include "nav_msgs/Odometry.h"
3
4 /**
5 * Bu örnekte evarobot üzerindeki bağıl konum ve hız ROS sistemi üzerinden okuyan basit bir subscriber yapılmaktadır.
6 */
7
8 /**
9 * Dinlenen topikten veri geldiğinde çalışacak callback fonksiyonudur.
10 * Bu örnekte, görevi gelen mesafe verileri ekrana yazdırmakdır.
11 */
12 void chatterCallback(const nav_msgs::Odometry::ConstPtr& msg)
13 {
14 ROS_INFO("Seq: [%d]", msg->header.seq);
15 ROS_INFO("Position-> x: [%f], y: [%f], z: [%f]", msg->pose.pose.position.x,msg->pose.pose.position.y, msg->pose.pose.position.z);
16 ROS_INFO("Orientation-> x: [%f], y: [%f], z: [%f], w: [%f]", msg->pose.pose.orientation.x, msg->pose.pose.orientation.y, msg->pose.pose.orientation.z, msg->pose.pose.orientation.w);
17 ROS_INFO("Vel-> Linear: [%f], Angular: [%f]", msg->twist.twist.linear.x,msg->twist.twist.angular.z);
18 }
19
20 int main(int argc, char **argv)
21 {
22 /**
23 * ROS ilklendiriliyor.
24 */
25 ros::init(argc, argv, "odom_listener");
26
27 ros::NodeHandle n;
28
29 /**
30 * Subscriber tanımlanıyor.
31 * İlk parametre olarak dinlenecek topiğin adı, ardından bufferın büyüklüğü ve callback fonksiyonu tanımlanmaktadır.
32 */
33 ros::Subscriber sub = n.subscribe("odom", 1000, chatterCallback);
34
35 ros::spin();
36
37 return 0;
38 }
Paket derlenirken yazdığımız cpp dosyasını derlemesi için CMakeLists.txt dosyasını aşağıdaki gibi düzenliyoruz.
> cd .. > gedit CMakeLists.txt
cmake_minimum_required(VERSION 2.8.3) project(evarobot_odom_subs) find_package(catkin REQUIRED COMPONENTS nav_msgs roscpp rospy ) catkin_package() include_directories( ${catkin_INCLUDE_DIRS} ) add_executable(odom_listener src/odom_listener.cpp) add_dependencies(odom_listener nav_msgs_generate_messages_cpp) target_link_libraries(odom_listener ${catkin_LIBRARIES} )
Yazdığımız ROS paketini derliyoruz.
> cd ~/catkin_ws/ > catkin_make
Yazdığımız odom_listener düğümünü aşağıdaki gibi çalıştırıldığında, okunan verilerin ekrana yazılması beklenmektedir.
> rosrun evarobot_odom_subs odom_listener