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

ROS2 clock stuck within inhereted class

asked 2018-04-10 02:26:44 -0500

EwingKang gravatar image

updated 2018-04-10 21:53:42 -0500

Hello everyone, my clock always stuck at the moment the node start for the following code. I mimic the coding style of the demo talker node. Am I doing anything wrong?

#include <chrono>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/clock.hpp"

void xNode::timer_callback()
{
    // do something here
    rclcpp::TimeSource ts(shared_from_this());
    rclcpp::Clock::SharedPtr clk2 = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
    ts.attachClock(clk2);
    rclcpp::Clock clk3;//

    if(conditions)
    {
        // stuck at node start time
        RCLCPP_INFO(this->get_logger(), "CONTACT!!! time: %ld", clk2->now());
        RCLCPP_INFO(this->get_logger(), "CONTACT!!! time: %ld", clk3.now());
    }
    return;
}

//====== Constructor ======//
xNode() : Node("node_name")
{
    subscription_ = this->create_subscription<std_msgs::msg::String>(
                           "topic_sub", std::bind(&xNode::topic_callback, this, _1),
                            rmw_qos_profile_sensor_data);
    timer_ = this->create_wall_timer(10ms, std::bind(&xNode::timer_callback, this));
}

Main:

int main(int argc, char *argv[])
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<xNode>();
    rclcpp::spin(node);

    printf("stop");
    node.reset();   // calling destructor through shared_ptr
    rclcpp::shutdown();
    return 0;
}

You have my appreciation for any advice!

Edit: minimum file:

#include <stdio.h>
#include <chrono>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/time_source.hpp"
#include "std_msgs/msg/string.hpp"

#define TOPIC_CMD "string_cmd"

using namespace std::chrono_literals;
using std::placeholders::_1;

class OmniTestNode : public rclcpp::Node
{
private:
    //rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
    rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
    rclcpp::TimerBase::SharedPtr timer_;

    void topic_callback(const std_msgs::msg::String::SharedPtr msg)
    {
        // Print the received message
        printf("------- Topic <\"%s\">: \"%s\" recieved.\n", TOPIC_CMD, msg->data.c_str());
        return;
    }

    void timer_callback()
    {
        rclcpp::TimeSource ts(shared_from_this());
        rclcpp::Clock::SharedPtr clk2 = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
        ts.attachClock(clk2);
        rclcpp::Clock clk3;

        RCLCPP_INFO(this->get_logger(), "clk2 time: %ld", clk2->now());
        RCLCPP_INFO(this->get_logger(), "clk3 time: %ld", clk3.now());
        RCLCPP_INFO(this->get_logger(), "this->now time: %ld", this->now());
        RCLCPP_INFO(this->get_logger(), "CONTACT!!! time: %ld", std::chrono::system_clock::now());

        return;
    }


public:
    rclcpp::Clock::SharedPtr clock_;
    //====== Constructor ======//
    explicit OmniTestNode() : Node("test_io")
    {
        //publisher_ = this->create_publisher<std_msgs::msg::String>(
        //      TOPIC_DATA, rmw_qos_profile_sensor_data);
        subscription_ = this->create_subscription<std_msgs::msg::String>(
                TOPIC_CMD, std::bind(&OmniTestNode::topic_callback, this, _1),
                rmw_qos_profile_sensor_data);

        timer_ = this->create_wall_timer(1000ms, std::bind(&OmniTestNode::timer_callback, this));
        clock_ = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
        //ts_ = std::make_shared<rclcpp::TimeSource>(shared_from_this());
        //ts_ = rclcpp::TimeSource(this);
    }

    //====== Destructor ======//
    virtual ~OmniTestNode()
    {
        printf("Node shutting down, reset all GPIOs");
    }
};


int main(int argc, char *argv[])
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<OmniTestNode>();

    printf("spin");
    rclcpp::spin(node);
    printf("stop");
    node.reset();
    rclcpp::shutdown();

    return 0;
}

output:

[INFO] [test_io]: clk2 time: 140729497633152
[INFO] [test_io]: clk3 time: 140729497633184
[INFO] [test_io]: this->now time: 140729497633216
[INFO] [test_io]: CONTACT!!! time: 1523415521337332304
[INFO] [test_io]: clk2 time: 140729497633152
[INFO] [test_io]: clk3 time: 140729497633184
[INFO] [test_io]: this->now time: 140729497633216
[INFO] [test_io]: CONTACT!!! time: 1523415522337518648
[INFO] [test_io]: clk2 time: 140729497633152
[INFO] [test_io]: clk3 time: 140729497633184
[INFO] [test_io]: this->now time: 140729497633216
[INFO] [test_io]: CONTACT!!! time: 1523415523338464997
edit retag flag offensive close merge delete

Comments

What's the output you're getting and what is the output you expect? clk2 will use the ROS time, and clk3 will default to system time, but unless you turn on sim time they will always be the same. Each call to the timer callback should produce a different timestamp, however.

William gravatar image William  ( 2018-04-10 17:29:46 -0500 )edit

Also you can do this->now() rather than creating your own time source and clock and stuff.

William gravatar image William  ( 2018-04-10 17:30:05 -0500 )edit

Hi @William, this->now() acted as same as clk2/clk3, it stucked at something like "CONTACT!!! time: 140735253311824" no matter how many time I called the function. Calling std::chrono::system_clock::now() gives the correct, advancing value like "1523409062194556622"

EwingKang gravatar image EwingKang  ( 2018-04-10 20:06:38 -0500 )edit

Also, because this node need to access some motherboard stuff, I'm running ros2 under root access. I.e. executing after sudo -sE

EwingKang gravatar image EwingKang  ( 2018-04-10 20:08:16 -0500 )edit

That's odd, I suppose it could be an issue with ROS time, can you narrow it down to a simpler program? Ideally just a single file that causes the issue? I don't think sudo should affect it.

William gravatar image William  ( 2018-04-10 20:44:26 -0500 )edit

@William, I've posted a one-file node that's still having this issue, thanks.

EwingKang gravatar image EwingKang  ( 2018-04-10 21:52:06 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-04-11 16:54:03 -0500

William gravatar image

I can't compile your example, because I get:

/Users/william/ros2_ws/src/ros2/demos/demo_nodes_cpp/src/topics/talker.cpp:35:59: error: cannot pass object of non-trivial type 'rclcpp::Time' through variadic function; call will abort at runtime
      [-Wnon-pod-varargs]
        RCLCPP_INFO(this->get_logger(), "clk2 time: %ld", clk2->now());
                                                          ^
/Users/william/ros2_ws/src/ros2/demos/demo_nodes_cpp/src/topics/talker.cpp:36:59: error: cannot pass object of non-trivial type 'rclcpp::Time' through variadic function; call will abort at runtime
      [-Wnon-pod-varargs]
        RCLCPP_INFO(this->get_logger(), "clk3 time: %ld", clk3.now());
                                                          ^
/Users/william/ros2_ws/src/ros2/demos/demo_nodes_cpp/src/topics/talker.cpp:37:64: error: cannot pass object of non-trivial type 'rclcpp::Time' through variadic function; call will abort at runtime
      [-Wnon-pod-varargs]
        RCLCPP_INFO(this->get_logger(), "this->now time: %ld", this->now());
                                                               ^
3 errors generated.

So I think that might be the real problem. ->now() returns a Time object, so this is what I used:

    RCLCPP_INFO(this->get_logger(), "this->now time:  %zu", this->now().nanoseconds());
    std::chrono::nanoseconds now = std::chrono::system_clock::now().time_since_epoch();
    RCLCPP_INFO(this->get_logger(), "CONTACT!!! time: %zu", now.count());

And with that I get this:

% ~/ros2_ws/install_debug/lib/demo_nodes_cpp/talker
spin[INFO] [test_io]: this->now time:  1523484085024108218
[INFO] [test_io]: CONTACT!!! time: 1523484085024181000
[INFO] [test_io]: this->now time:  1523484086027860553
[INFO] [test_io]: CONTACT!!! time: 1523484086027899000
[INFO] [test_io]: this->now time:  1523484087032300023
[INFO] [test_io]: CONTACT!!! time: 1523484087032338000
[INFO] [test_io]: this->now time:  1523484088038859851
[INFO] [test_io]: CONTACT!!! time: 1523484088038897000
[INFO] [test_io]: this->now time:  1523484089039952856
[INFO] [test_io]: CONTACT!!! time: 1523484089039987000
[INFO] [test_io]: this->now time:  1523484090044948563
[INFO] [test_io]: CONTACT!!! time: 1523484090044988000
[INFO] [test_io]: this->now time:  1523484091047517423
[INFO] [test_io]: CONTACT!!! time: 1523484091047562000
[INFO] [test_io]: this->now time:  1523484092048706228
[INFO] [test_io]: CONTACT!!! time: 1523484092048766000
[INFO] [test_io]: this->now time:  1523484093047516655
[INFO] [test_io]: CONTACT!!! time: 1523484093047548000
^Csignal_handler(2)
stopNode shutting down, reset all GPIOs%

Which looks ok to me. Maybe the issue was just how you were printing it?

edit flag offensive delete link more

Comments

1

It worked!!!!!! This is such a stupid error!!! THANK YOU
But how interesting I'm getting no error at compile. :/

EwingKang gravatar image EwingKang  ( 2018-04-11 20:08:34 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-04-10 02:26:44 -0500

Seen: 1,313 times

Last updated: Apr 11 '18