ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

ros-timer doesn't seem to start when defined in class.

asked 2020-11-06 12:32:24 -0500

Sjakio gravatar image

I'm using ROS Melodic on kubuntu 18 programming in cpp While trying to get a grip on ros::timers, I got various issues when using thenm in a class. So I went back working out some examples. link text

When I define the timers in the main program the example works, when I define the timers in the constuctor or a seperate function in the class they do not work. What I'm I doing wrong?

This works:

timers_class_3.h

#include <ros/ros.h>
#include <std_msgs/Float64.h>

#ifndef TEMPERATURESENSOR_H_
#define TEMPERATURESENSOR_H_

class TemperatureSensor
{
public:
    TemperatureSensor(ros::NodeHandle *nh);

    double readTemperatureSensorData();

    void publishTemperature();

private:
    double temperature;
    ros::Publisher temperaturePublisher;
};

#endif //=== TEMPERATURESENSOR_H_

timers_class_3.cpp

#include "timers_3/timers_class_3.h"

TemperatureSensor::TemperatureSensor(ros::NodeHandle *nh)
{
    temperature = 0.0;
    temperaturePublisher =
            nh->advertise<std_msgs::Float64>("/temperature", 10);
    ROS_INFO("TempSensor Published.");
}

double TemperatureSensor::readTemperatureSensorData()
{
    ROS_INFO("TempSensor Temperature Read.");
    return 30.0;
}

void TemperatureSensor::publishTemperature()
{
    std_msgs::Float64 msg;
    msg.data = readTemperatureSensorData();
    temperaturePublisher.publish(msg);
    ROS_INFO("TempSensor Temperature Published.");
}

timers-3.cpp

#include "timers_3/timers_class_3.h"

int main(int argc, char **argv)
{
    ros::init(argc, argv, "your_sensor_node");
    ros::NodeHandle nh;

    TemperatureSensor temperatureSensor(&nh);

    ros::Timer timerReadTemperature =
        nh.createTimer(ros::Duration(1.0 ),
                       std::bind(&TemperatureSensor::readTemperatureSensorData, temperatureSensor));
    ROS_INFO("TempSensor Read timer started.");

    ros::Timer timerPublishTemperature =
        nh.createTimer(ros::Duration(1.0 ),
                       std::bind(&TemperatureSensor::publishTemperature, temperatureSensor));
    ROS_INFO("TempSensor Publish timer started.");

    ROS_INFO("TempSensor We are going to spin.");
    ros::spin();
}

This doesn't:

timers_class_4.h

#include <ros/ros.h>
#include <std_msgs/Float64.h>

#ifndef TEMPERATURESENSOR_H_
#define TEMPERATURESENSOR_H_

class TemperatureSensor
{
public:
    TemperatureSensor(ros::NodeHandle *nh);
    double readTemperatureSensorData();
    void publishTemperature();

private:
    double temperature;
    ros::Publisher temperaturePublisher;
};

#endif //=== TEMPERATURESENSOR_H_

timers_class_4.cpp

#include "timers_4/timers_class_4.h"

TemperatureSensor::TemperatureSensor(ros::NodeHandle *nh)
{

    temperature = 0.0;
    temperaturePublisher =
            nh->advertise<std_msgs::Float64>("/temperature", 10);
    ROS_INFO("TempSensor Published.");

    ros::Timer timerReadTemperature =
            nh->createTimer(ros::Duration(1.0),
                    std::bind(&TemperatureSensor::readTemperatureSensorData, this));
    ROS_INFO("TempSensor Read timer started.");

    ros::Timer timerPublishTemperature =
            nh->createTimer(ros::Duration(1.0),
                    std::bind(&TemperatureSensor::publishTemperature, this));
    ROS_INFO("TempSensor Publish timer started.");
}

double TemperatureSensor::readTemperatureSensorData()
{
    ROS_INFO("TempSensor Temperature Read.");
    temperature = 30.0;
    return temperature;
}

void TemperatureSensor::publishTemperature()
{
    std_msgs::Float64 msg;
    msg.data = temperature;
    temperaturePublisher.publish(msg);
    ROS_INFO("TempSensor Temperature Published.");
}

timers-4.cpp

#include "timers_4/timers_class_4.h"

int main(int argc, char **argv)
{
    ros::init(argc, argv, "your_sensor_node");
    ros::NodeHandle nh;

    TemperatureSensor temperatureSensor(&nh);

    ROS_INFO("TempSensor We are going to spin.");
    ros::spin();
}

terminal output:

jac@ubuntu:~/ros_ws$ source ~/.bashrc && rosrun timers_3 timers_3
[ INFO] [1604681826.821091128]: TempSensor Published.
[ INFO] [1604681826.821680691]: TempSensor Read timer started.
[ INFO] [1604681826.821705215]: TempSensor Publish timer started.
[ INFO] [1604681826.821713941]: TempSensor We are going to spin.
[ INFO] [1604681827.822120790]: TempSensor Temperature Read.
[ INFO] [1604681827.822307041]: TempSensor Temperature Read.
[ INFO] [1604681827.822423255]: TempSensor Temperature Published.
[ INFO] [1604681831.822025383]: TempSensor Temperature Read.
[ INFO] [1604681831.822150300]: TempSensor Temperature Read.
[ INFO] [1604681831.822300088]: TempSensor Temperature Published.
^Cjac@ubuntu:~/ros_ws$ source ~/.bashrc && rosrun timers_4 timers_4
[ INFO] [1604681843.392177456]: TempSensor Published.
[ INFO] [1604681843.392787505]: TempSensor Read timer started.
[ INFO] [1604681843.392841028]: TempSensor Publish timer started.
[ INFO] [1604681843.392857652]: TempSensor We are going to spin.
^Cjac@ubuntu:~/ros_ws$
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2020-11-06 12:49:56 -0500

updated 2020-11-06 12:52:10 -0500

The issue is that your timers are going out of scope and are destroyed. You need to make timerReadTemperature and timerPublishTemperature (private) class members.

class TemperatureSensor
{
public:
    TemperatureSensor(ros::NodeHandle *nh);
    double readTemperatureSensorData();
    void publishTemperature();

private:
    double temperature;
    ros::Publisher temperaturePublisher;
    ros::Timer timerReadTemperature;
};

and

TemperatureSensor::TemperatureSensor(ros::NodeHandle *nh)
{

    temperature = 0.0;
    temperaturePublisher =
            nh->advertise<std_msgs::Float64>("/temperature", 10);
    ROS_INFO("TempSensor Published.");

    timerReadTemperature =
            nh->createTimer(ros::Duration(1.0),
                    std::bind(&TemperatureSensor::readTemperatureSensorData, this));
    ROS_INFO("TempSensor Read timer started.");

    timerPublishTemperature =
            nh->createTimer(ros::Duration(1.0),
                    std::bind(&TemperatureSensor::publishTemperature, this));
    ROS_INFO("TempSensor Publish timer started.");
}
edit flag offensive delete link more

Comments

Thank you. Now I look at it, it make sense why it didn't work as the timers only existed in the Constructor. After a couple of tries of using timers in my one code, which didn’t compile, I switched to working out some examples I found on-line. I was too focused to make sure I copied the example line be line, without reviewing the code thoroughly. It is clear that that example code is wrong.

Sjakio gravatar image Sjakio  ( 2020-11-06 13:59:12 -0500 )edit

Question Tools

Stats

Asked: 2020-11-06 12:32:24 -0500

Seen: 567 times

Last updated: Nov 06 '20