User Tools

Site Tools


courses:ros:class3

Differences

This shows you the differences between two versions of the page.

Link to this comparison view

Both sides previous revision Previous revision
Next revision
Previous revision
courses:ros:class3 [2016/09/16 10:57]
anton.filatov
courses:ros:class3 [2022/12/10 09:08] (current)
Line 1: Line 1:
-==== Занятие № 3Ж Базовые пакеты ROS: rviz и tf ====+==== Занятие № 3Базовые пакеты ROS: rviz и tf ==== 
 + 
 +=== rviz ===
  
 Очень часто, особенно при работе с большим количеством информации,​ отображения данных в текстовом виде бывает малоинформативным. Так, например,​ если граф представляется в виде матрицы смежности и имеет размеры 100 на 100, то по текстовому виду этой матрицы довольно сложно представить себе вид этого графа. В таких случаях гораздо удобнее использовать графическое представление данных. Конечно,​ как любой проект С++, проекты ROS могут использовать графические библиотеки,​ например,​ openGL. И, конечно,​ можно вручную описывать способы представления информации на экране. Но для этих нужд в ROS предусмотрен пакет rviZ, который представляет ноду графического представления (наприсанную с использованием openGL). Очень часто, особенно при работе с большим количеством информации,​ отображения данных в текстовом виде бывает малоинформативным. Так, например,​ если граф представляется в виде матрицы смежности и имеет размеры 100 на 100, то по текстовому виду этой матрицы довольно сложно представить себе вид этого графа. В таких случаях гораздо удобнее использовать графическое представление данных. Конечно,​ как любой проект С++, проекты ROS могут использовать графические библиотеки,​ например,​ openGL. И, конечно,​ можно вручную описывать способы представления информации на экране. Но для этих нужд в ROS предусмотрен пакет rviZ, который представляет ноду графического представления (наприсанную с использованием openGL).
Line 100: Line 102:
     msg.color.a = 1.0;     msg.color.a = 1.0;
     for (int x = -20; x <= 20; x++){     for (int x = -20; x <= 20; x++){
-    ​geometry_msgs::​Point p;+      ​geometry_msgs::​Point p;
       p.x = x;       p.x = x;
       p.y = 2*sin(x+offset);​       p.y = 2*sin(x+offset);​
Line 111: Line 113:
   }   }
 </​code>​ </​code>​
 +
 +
 +=== tf ===
 +
 +Пакет tf служит для упрощения определения в пространстве координат различных объектов. Например известно,​ что относительно объекта 1 объект 2 имеет координаты (x,y). А объект 3 относительно объекта 2 - (m,n). Для того, чтобы выяснить взаимное расположение объектов 1 и 3 можно применить формулы высшей математики,​ однако в этом нет необходимости,​ поскольку именно для этого предназначен пакет tf.
 +
 +Разберёмся в механизме работы сразу на примере. Вот, например,​ исходный код ноды, которая считывает положение черепашки из пакета //​turtlesim//​ и записывает в топик tf. Это действие полезно,​ поскольку в этом топике информация находится в том виде, в котором её можно будет легко использовать средствами функций,​ поставляемых в пакете tf. 
 +
 +<code c>
 +#include <​ros/​ros.h>​
 +#include <​tf/​transform_broadcaster.h>​
 +#include <​turtlesim/​Pose.h>​
 +
 +std::string turtle_name;​
 +
 +void poseCallback(const turtlesim::​PoseConstPtr&​ msg){
 +  static tf::​TransformBroadcaster br;
 +  tf::​Transform transform;
 +  transform.setOrigin( tf::​Vector3(msg->​x,​ msg->y, 0.0) );
 +  tf::​Quaternion q;
 +  q.setRPY(0, 0, msg->​theta);​
 +  transform.setRotation(q);​
 +  br.sendTransform(tf::​StampedTransform(transform,​ ros::​Time::​now(),​ "​world",​ turtle_name));​
 +}
 +
 +int main(int argc, char** argv){
 +  ros::​init(argc,​ argv, "​my_tf_broadcaster"​);​
 +  if (argc != 2){ROS_ERROR("​need turtle name as argument"​);​ return -1;};
 +  turtle_name = argv[1];
 +
 +  ros::​NodeHandle node;
 +  ros::​Subscriber sub = node.subscribe(turtle_name+"/​pose",​ 10, &​poseCallback);​
 +
 +  ros::​spin();​
 +  return 0;
 +}
 +</​code>​
 +
 +Как понятно из кода, в проргамме создаётся нода, которая подписывается на turtle1/​pose (имя взято по-умолчанию). В этот топик нода черепашки пишет координаты черепашки в мире. Как только в этот топик поступает какая-то информация (а поступает она туда постоянно,​ даже если черепашка стоит на месте),​ запускается функция,​ считывающая информацию с этого топика и записывающая её в tf.
 +
 +Обратите внимание на механизм создания transform: координаты задаются,​ как члены данные,​ а поворот при помощи tf:​Quaternion.
 +
 +В функции sendTransform указаны две строковые переменные:​ "​world"​ и turtle_name. Они будут записаны в сообщение,​ которое будет отправлено в топик tf. Когда сообщение будет извлекаться,​ можно будет получить доступ к этим переменным. Их смысловая нагрузка показать,​ что и в каких координатах считается. В данном случае показано,​ что в tf отправлены координаты объекта turtle_name относительно world. \\
 +Становится понятно,​ что с помощью такого механизма организации сообщений всегда можно будет восстановить координаты любого объекта,​ даже если известны лишь его координаты относительно другого объекта,​ но про тот нам всё известно. \\
 +Заметим,​ что в tf то, относительно чего считаются координаты называется base_frame_id,​ а то, чьи координты,​ называется base_frame_id.
 +
 +Теперь разберёмся,​ как считывать и обрабатывать сообщения из tf. Рассмотрим,​ например,​ такой код:
 +
 +<code c>
 +#include <​ros/​ros.h>​
 +#include <​tf/​transform_listener.h>​
 +#include <​geometry_msgs/​Twist.h>​
 +#include <​turtlesim/​Spawn.h>​
 +
 +int main(int argc, char** argv){
 +  ros::​init(argc,​ argv, "​my_tf_listener"​);​
 +
 +  ros::​NodeHandle node;
 +
 +  ros::​service::​waitForService("​spawn"​);​
 +  ros::​ServiceClient add_turtle =
 +    node.serviceClient<​turtlesim::​Spawn>​("​spawn"​);​
 +  turtlesim::​Spawn srv;
 +  add_turtle.call(srv);​
 +
 +  ros::​Publisher turtle_vel =
 +    node.advertise<​geometry_msgs::​Twist>​("​turtle2/​cmd_vel",​ 10);
 +
 +  tf::​TransformListener listener;
 +
 +  ros::Rate rate(10.0);
 +  while (node.ok()){
 +    tf::​StampedTransform transform;
 +    try{
 +      listener.lookupTransform("/​turtle2",​ "/​turtle1",​
 +                               ​ros::​Time(0),​ transform);
 +    }
 +    catch (tf::​TransformException &ex) {
 +      ROS_ERROR("​%s",​ex.what());​
 +      ros::​Duration(1.0).sleep();​
 +      continue;
 +    }
 +
 +    geometry_msgs::​Twist vel_msg;
 +    vel_msg.angular.z = 4.0 * atan2(transform.getOrigin().y(),​
 +                                    transform.getOrigin().x());​
 +    vel_msg.linear.x = 0.5 * sqrt(pow(transform.getOrigin().x(),​ 2) +
 +                                  pow(transform.getOrigin().y(),​ 2));
 +    turtle_vel.publish(vel_msg);​
 +
 +    rate.sleep();​
 +  }
 +  return 0;
 +}
 +</​code>​
 +
 +В программе вызывается сервис "​spawn"​. Таким образом,​ теперь в turtle_sim_node будет находится две черепашки. Для корректной работы необходимо запустить двух бродкастеров:​ для turtle1 и для turtle2.
 +
 +Разберёмся подробно,​ что делает такой код. \\
 +Выходным параметром является направление движения для turtle2, записанное в turtle2/​cmd_vel.
 +
 +Самую важную роль здесь играет функция listener.lookupTransform,​ которая в переменную transform записывает координаты turtle1 относительно turtle2. Обратите внимание,​ что в этой функции переменные base_frame_id и child_frame_id стоят в том же порядке,​ что в sendTransform:​ сначала base - относительно чего, а потом child - тот, кого.
 +
 +Теперь,​ когда координаты первой черепашки посчитаны (нам не пришлось прилагать усилий для подсчёта этих координат),​ можно сформировать сообщение и послать в топик, который прослушивает turtle2.
 +
 +Резюмируя,​ можно сказать,​ что tf это очень сильный механизм определения относительных координат объектов. В реальных роботах необходимо ослеживать перемещения десятков движущихся механизмов и конечностей робота. Для того, чтобы легко рассчитывать их взаимное расположение и используется tf.
courses/ros/class3.1474023444.txt.gz · Last modified: 2022/12/10 09:08 (external edit)