Scheduler is a class which provides functionality for stepped simulation. More...
#include <adore_scheduler.h>

Public Member Functions | |
| void | init () |
| void | updateClientUpperTimeLimit (const adore_if_ros_scheduling_msg::SchedulerNotification::ConstPtr &msg) |
| void | setNewTime (bool incrementalIncrease=false) |
| void | togglePause () |
| void | limitSimulationSpeed () |
| void | write () |
| uint32_t | getTimeDiff (TimeKeyType subtrahend, TimeKeyType minuend) |
| void | printTime () |
| void | saveClientName (const std_msgs::String::ConstPtr &msg) |
| void | printInfo () |
| void | start () |
Static Public Member Functions | |
| static Scheduler * | getInstance (ros::NodeHandle &n, int minRegisters, bool autostart, bool tcp_no_delay) |
Private Types | |
| using | ScheduleMap = std::multimap< TimeKeyType, RegistreeInfo > |
Private Member Functions | |
| void | updateSchedule (RegistreeInfo ri, TimeKeyType tk) |
| Scheduler (ros::NodeHandle &n, int minRegisters, bool autostart, bool tcp_no_delay) | |
Private Attributes | |
| ros::Subscriber | m_notificationReader |
| ros::Subscriber | m_clientNameReader |
| ros::Publisher | m_simulationTimeWriter |
| ros::Publisher | m_clockTimeWriter |
| SchedulerNotificationConversion | m_schedulerNotificationConversion |
| ClockTimeConversion | m_clockTimeConversion |
| bool | m_pause |
| int | m_minRegisters |
| bool | m_autostart |
| bool | m_started |
| int | m_printIntervalS |
| bool | m_limitSimulationSpeed |
| std::pair< uint32_t, uint32_t > | m_lastWallTime |
| std::pair< uint32_t, uint32_t > | m_lastRosTime |
| ScheduleMap * | m_schedule |
| TimeKeyType | m_now |
| std::pair< TimeKeyType, std::pair< uint32_t, uint32_t > > | m_lastTimeSet |
| std::unordered_map< RegistreeInfo, std::string > | m_clientNames |
Scheduler is a class which provides functionality for stepped simulation.
|
private |
|
inlineprivate |


|
inlinestatic |
|
inline |
get time differnce in nano seconds

|
inline |
init
|
inline |
limit the speed of simulation to the speed of ros::WallTime (inaccurate)
|
inline |
print information to std::cout

|
inline |
print time information to std::cout

|
inline |
save name of client associated with id

|
inline |
set new simulation and clock time
incrementalIncrease must be used in order to trigger initial timer event in ros based python nodes


|
inline |
start the scheduling

|
inline |
pause and unpause the time

|
inline |
update uppter time limit associated with certain client


|
inlineprivate |
Search for the registree info in m_schedule and replace the associated time key
If the registree info is not found, it is added to the m_schedule
| ri | registree info |
| tk | time key |


|
inline |
publisch new time signal


|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |