Git Product home page Git Product logo

Comments (10)

Barry-Xu-2018 avatar Barry-Xu-2018 commented on July 19, 2024 1

Please note that rclcpp::Rate use RCL_SYSTEM_TIME in default. Do you change it ?

class Rate : public RateBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(Rate)
RCLCPP_PUBLIC
explicit Rate(
const double rate,
Clock::SharedPtr clock = std::make_shared<Clock>(RCL_SYSTEM_TIME));
RCLCPP_PUBLIC
explicit Rate(
const Duration & period,
Clock::SharedPtr clock = std::make_shared<Clock>(RCL_SYSTEM_TIME));

from rclcpp.

fujitatomoya avatar fujitatomoya commented on July 19, 2024 1

I have been set use_sim_time=true
https://design.ros2.org/articles/clock_and_time.html

use_sim_time is set on the node, but Rate object. with your example, as @Barry-Xu-2018 mentions, Rate is instantiated with system time as default, not simulation time. I think you need to set RCL_SYSTEM_TIME for Rate, the it can get the time from simulation clock.

this->get_clock()->now() or this->now() can get the sim time,

assuming that this is the Node. because the use_sim_time is set to true, clock belongs to node is now set to simulation clock. so that it can get simulation clock.

from rclcpp.

Barry-Xu-2018 avatar Barry-Xu-2018 commented on July 19, 2024

How do you create timer to publish messages ?
create_wall_timer or create_timer
Simulate time doesn't affect create_wall_timer.

from rclcpp.

fengzhongsu avatar fengzhongsu commented on July 19, 2024

from rclcpp.

fengzhongsu avatar fengzhongsu commented on July 19, 2024

How do you create timer to publish messages ? create_wall_timer or create_timer Simulate time doesn't affect create_wall_timer.

Hi, Barry. In simulation, i used rclcpp::Rate loop_rate(ctrl_freq); And In a
while(rclcpp::ok()) { rclcpp::spin_some(mynode); //my program loop_rate.sleep(); }

from rclcpp.

fengzhongsu avatar fengzhongsu commented on July 19, 2024

Please note that rclcpp::Rate use RCL_SYSTEM_TIME in default. Do you change it ?

class Rate : public RateBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(Rate)
RCLCPP_PUBLIC
explicit Rate(
const double rate,
Clock::SharedPtr clock = std::make_shared<Clock>(RCL_SYSTEM_TIME));
RCLCPP_PUBLIC
explicit Rate(
const Duration & period,
Clock::SharedPtr clock = std::make_shared<Clock>(RCL_SYSTEM_TIME));

I have been set use_sim_time=true
https://design.ros2.org/articles/clock_and_time.html

from rclcpp.

Barry-Xu-2018 avatar Barry-Xu-2018 commented on July 19, 2024

As fujitatomoya said,you should modify code on creating Rate.

rclcpp::Rate loop_rate(ctrl_freq, std::make_shared(RCL_ROS_TIME));

from rclcpp.

fengzhongsu avatar fengzhongsu commented on July 19, 2024

As fujitatomoya said,you should modify code on creating Rate.

rclcpp::Rate loop_rate(ctrl_freq, std::make_shared(RCL_ROS_TIME));
I have tried add this code. But have some error in IDE, my ros2 version is foxy
error: no matching function for call to ‘make_shared(rcl_clock_type_t)’
268 | rclcpp::Rate loop_rate(ctrl_freq, std::make_shared(RCL_ROS_TIME));

from rclcpp.

fujitatomoya avatar fujitatomoya commented on July 19, 2024

I have tried add this code. But have some error in IDE, my ros2 version is foxy

Foxy is already E.O.L, can you use humble or later instead?

from rclcpp.

Barry-Xu-2018 avatar Barry-Xu-2018 commented on July 19, 2024

For Foxy, you should create a Clock with RCL_ROS_TIME

class Clock
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(Clock)
/// Default c'tor
/**
* Initializes the clock instance with the given clock_type.
*
* \param clock_type type of the clock.
* \throws anything rclcpp::exceptions::throw_from_rcl_error can throw.
*/
RCLCPP_PUBLIC
explicit Clock(rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);

Create a new "Rate" like with above Clock.

using Rate = GenericRate<std::chrono::system_clock>;

BTW, foxy is EOL.
So it's best to upgrade to the Humble or Iron version.

from rclcpp.

Related Issues (20)

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.