(!) 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.

Moving a FLIR PTU with asr_flir_ptu_driver using an own programm.

Description: This tutorial's goal is to show the user how to use the asr_flir_ptu_driver to move a FLIR PTU in pan/tilt direction without much configuring.

Tutorial Level: BEGINNER

Next Tutorial: Advanced movement options using asr_flir_ptu_driver Link.

Contents

  1. Setup
  2. Tutorial

Setup

This tutorial is not meant to be executed, it just provides code pieces to show how to use asr_flir_ptu_driver in your own programm. If you want to include some of the code pieces below, first start and connect your FLIR PTU and start asr_flir_ptu_driver as shown in the corresponding documentation.

Tutorial

The most obvious goal is to move the PTU to a new pan/tilt position.

First of all you need to include the needed headers, in this case:

#include "ros/ros.h"
#include "asr_flir_ptu_driver/State.h"
#include <sensor_msgs/JointState.h>

For sending the new position to the PTU a publisher is needed, as well as a subscriber for the current state of the PTU. By default they will look like this:

ros::NodeHandle nh;
ros::Publisher state_pub;
ros::Subscriber state_sub;

state_pub = nh.advertise<asr_flir_ptu_driver::State>(/asr_flir_ptu_driver/state_cmd, 1);
state_sub = nh.subscribe<asr_flir_ptu_driver::State>(/asr_flir_ptu_driver/ptu_state, 1, &[your_class_name]::[your_callback_function], this);

The above seen [your_class_name] and [your_callback_function] are placeholders for the names you want to use for your class and callback function. If you do not know how to write a subscriber to a topic browse the corresponding tutorial. Now we will have a look at how to send new pan/tilt values to the PTU. seq is the value used to identify the current request in the messages coming from. All values shown below are exemplarily.

pan_value = 22.0; //Needs to be safed globally to compare if the movement worked or not (later). Define as "double pan_value"

tilt_value = 18.0; //Needs to be safed globally to compare if the movement worked or not (later). Define as "double tilt_value"

seq = 5; //define seq not locally in the method but accessable for all the methods of the class as "int seq;"

asr_flir_ptu_driver::State movement_goal
movement_goal.state.position[0] = pan_value;
movement_goal.state.position[0] = tilt_value; movement_goal.no_check_forbidden_area = false;
movement_goal.seq_num = 5;

state_pub.publish(movement_goal);

After these steps, the message will be sent to the PTU and is processed. The current state will be read by the method bound to state_sub. Best define seq globally and just assign a new (best case random) number to it when you send a new message. Global configuration is advised to filter if the currently arrived message is relevant or not. What needs to be done in the callback method will be shown below.

void [your_class_name]::[your_callback_function](const asr_flir_ptu_driver::State::ConstPtr& msg) {
  if(msg.seq_num != seq){
     return; //In the case when seq_num is not equal to seq we are recieving
     old data that needs not to be processed.
  }
  if(msg.finished){
     //Movement has finished, it needs to be checked if the right position
     was reached. If this is not the case, the pan/tilt position was not
     reachable (no movement occured then)
     //calculate the distance between the point you sent to the ptu and the
     one you recieved. If the distance is higher than some value used to get
     rid of calculation problems (0.1 or 0.01 should be sufficient, to
     conversion from steps used by the ptu and degree used for the topic
     causes some small differences

     double tolerance = 0,1;
     //calculating the maximum distance of pan/tilt from the wanted endpoint

     max_distance = std::max(std::abs(pan_value - msg->state.position[0]),
     std::abs(tilt_value - msg->state.position[1]);

     if(max_distance){
        //The movement was successfull.
     }else{
        //The new pan/tilt values were rejected if this point is reached.
        (out of limits/ in forbidden area)
     }
     }else{
     //The final position was not reached until now
  }
}

The main problem with this usage of the PTU is that you will only see that something did not work if the PTU does not drive to the new position and tells you that it is finished with the new seq_num. Furthermore, there some other checks needed to be done. Therefore, advanced functionalities were implemented to help you performing movements easier.

Wiki: asr_flir_ptu_driver/DriverMovementTutorial (last edited 2017-05-30 10:07:43 by FelixMarek)