Classes | |
class | SimClockActivity |
class | SimClockActivityManager |
A centralized list of all TaskContexts using SimClockActivity. More... | |
class | SimClockThread |
Functions | |
const bool | disable_sim () |
Do't use a simulated clock source. More... | |
const bool | enable_sim () |
Use a simulated clock source. More... | |
const ros::Time | host_now () |
Get the current time according to CLOCK_HOST_REALTIME or the simulation time. More... | |
const RTT::Seconds | host_offset_from_rtt () |
Get the difference in seconds between rtt_wall_now() and host_wall_now() More... | |
const ros::Time | host_wall_now () |
Get the current time according to CLOCK_HOST_REALTIME or the wall time. More... | |
const ros::Time | rtt_now () |
Get the current time according to RTT. More... | |
const ros::Time | rtt_wall_now () |
Get the current wall time according to RTT. More... | |
const bool | set_sim_clock_activity (RTT::TaskContext *t) |
Set a TaskContext to use a periodic simulation clock activity. More... | |
void | update_sim_clock (const ros::Time new_time) |
Update the current simulation time and trigger all simulated TaskContexts. More... | |
void | use_manual_clock () |
Use manual clock updates. More... | |
void | use_ros_clock_topic () |
Use ROS /clock topic for time measurement. More... | |
Variables | |
boost::shared_ptr< rtt_rosclock::SimClockThread > | sim_clock_thread |
const bool rtt_rosclock::disable_sim | ( | ) |
Do't use a simulated clock source.
Definition at line 101 of file rtt_rosclock.cpp.
const bool rtt_rosclock::enable_sim | ( | ) |
Use a simulated clock source.
Definition at line 96 of file rtt_rosclock.cpp.
const ros::Time rtt_rosclock::host_now | ( | ) |
Get the current time according to CLOCK_HOST_REALTIME or the simulation time.
This is the time source that should always be used with ROS header timestamps because it is the time that you want to use to broadcast ROS messages to other machines or processes.
When compiled against Xenomai and not running in simulation mode, this function will return the NTP-synchronized clock time via the CLOCK_HOST_REALTIME clock source. Note that this is only supported under Xenomai 2.6 and above.
When not compiled against Xenomai and not running in simulation mode, it is a pass-through to ros::Time::now().
When running in simulation mode, this will always use the simulation clock, which is based off of the ROS /clock topic. It is a pass-through to rtt_now().
Definition at line 13 of file rtt_rosclock.cpp.
const RTT::Seconds rtt_rosclock::host_offset_from_rtt | ( | ) |
Get the difference in seconds between rtt_wall_now() and host_wall_now()
Definition at line 75 of file rtt_rosclock.cpp.
const ros::Time rtt_rosclock::host_wall_now | ( | ) |
Get the current time according to CLOCK_HOST_REALTIME or the wall time.
Definition at line 34 of file rtt_rosclock.cpp.
const ros::Time rtt_rosclock::rtt_now | ( | ) |
Get the current time according to RTT.
If the simulation clock is enabled, this will return the simulated time.
Definition at line 52 of file rtt_rosclock.cpp.
const ros::Time rtt_rosclock::rtt_wall_now | ( | ) |
Get the current wall time according to RTT.
Even if the simualtion clock is enabled, this will still return the wall clock time.
Definition at line 64 of file rtt_rosclock.cpp.
const bool rtt_rosclock::set_sim_clock_activity | ( | RTT::TaskContext * | t | ) |
Set a TaskContext to use a periodic simulation clock activity.
Definition at line 90 of file rtt_rosclock.cpp.
void rtt_rosclock::update_sim_clock | ( | const ros::Time | new_time | ) |
Update the current simulation time and trigger all simulated TaskContexts.
Definition at line 106 of file rtt_rosclock.cpp.
void rtt_rosclock::use_manual_clock | ( | ) |
Use manual clock updates.
Definition at line 85 of file rtt_rosclock.cpp.
void rtt_rosclock::use_ros_clock_topic | ( | ) |
Use ROS /clock topic for time measurement.
Definition at line 80 of file rtt_rosclock.cpp.
boost::shared_ptr<rtt_rosclock::SimClockThread> rtt_rosclock::sim_clock_thread |
Definition at line 10 of file rtt_rosclock.cpp.