ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType > Class Template Reference

Scheduler is a class which provides functionality for stepped simulation. More...

#include <adore_scheduler.h>

Collaboration diagram for adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >:
Collaboration graph

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 SchedulergetInstance (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
 
ScheduleMapm_schedule
 
TimeKeyType m_now
 
std::pair< TimeKeyType, std::pair< uint32_t, uint32_t > > m_lastTimeSet
 
std::unordered_map< RegistreeInfo, std::string > m_clientNames
 

Detailed Description

template<typename RegistreeInfo, typename TimeKeyType>
class adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >

Scheduler is a class which provides functionality for stepped simulation.

Member Typedef Documentation

◆ ScheduleMap

template<typename RegistreeInfo , typename TimeKeyType >
using adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::ScheduleMap = std::multimap<TimeKeyType, RegistreeInfo>
private

Constructor & Destructor Documentation

◆ Scheduler()

template<typename RegistreeInfo , typename TimeKeyType >
adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::Scheduler ( ros::NodeHandle &  n,
int  minRegisters,
bool  autostart,
bool  tcp_no_delay 
)
inlineprivate
Here is the call graph for this function:
Here is the caller graph for this function:

Member Function Documentation

◆ getInstance()

template<typename RegistreeInfo , typename TimeKeyType >
static Scheduler* adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::getInstance ( ros::NodeHandle &  n,
int  minRegisters,
bool  autostart,
bool  tcp_no_delay 
)
inlinestatic

return instance of Scheduler class

Here is the call graph for this function:

◆ getTimeDiff()

template<typename RegistreeInfo , typename TimeKeyType >
uint32_t adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::getTimeDiff ( TimeKeyType  subtrahend,
TimeKeyType  minuend 
)
inline

get time differnce in nano seconds

Here is the caller graph for this function:

◆ init()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::init ( )
inline

init

◆ limitSimulationSpeed()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::limitSimulationSpeed ( )
inline

limit the speed of simulation to the speed of ros::WallTime (inaccurate)

◆ printInfo()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::printInfo ( )
inline

print information to std::cout

Here is the call graph for this function:

◆ printTime()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::printTime ( )
inline

print time information to std::cout

Here is the caller graph for this function:

◆ saveClientName()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::saveClientName ( const std_msgs::String::ConstPtr &  msg)
inline

save name of client associated with id

Here is the caller graph for this function:

◆ setNewTime()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::setNewTime ( bool  incrementalIncrease = false)
inline

set new simulation and clock time

incrementalIncrease must be used in order to trigger initial timer event in ros based python nodes

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::start ( )
inline

start the scheduling

Here is the call graph for this function:

◆ togglePause()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::togglePause ( )
inline

pause and unpause the time

Here is the call graph for this function:

◆ updateClientUpperTimeLimit()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::updateClientUpperTimeLimit ( const adore_if_ros_scheduling_msg::SchedulerNotification::ConstPtr &  msg)
inline

update uppter time limit associated with certain client

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateSchedule()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::updateSchedule ( RegistreeInfo  ri,
TimeKeyType  tk 
)
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

Parameters
riregistree info
tktime key
Here is the call graph for this function:
Here is the caller graph for this function:

◆ write()

template<typename RegistreeInfo , typename TimeKeyType >
void adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::write ( )
inline

publisch new time signal

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ m_autostart

template<typename RegistreeInfo , typename TimeKeyType >
bool adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_autostart
private

◆ m_clientNameReader

template<typename RegistreeInfo , typename TimeKeyType >
ros::Subscriber adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_clientNameReader
private

◆ m_clientNames

template<typename RegistreeInfo , typename TimeKeyType >
std::unordered_map<RegistreeInfo, std::string> adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_clientNames
private

◆ m_clockTimeConversion

template<typename RegistreeInfo , typename TimeKeyType >
ClockTimeConversion adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_clockTimeConversion
private

◆ m_clockTimeWriter

template<typename RegistreeInfo , typename TimeKeyType >
ros::Publisher adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_clockTimeWriter
private

◆ m_lastRosTime

template<typename RegistreeInfo , typename TimeKeyType >
std::pair<uint32_t, uint32_t> adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_lastRosTime
private

◆ m_lastTimeSet

template<typename RegistreeInfo , typename TimeKeyType >
std::pair<TimeKeyType, std::pair<uint32_t, uint32_t> > adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_lastTimeSet
private

◆ m_lastWallTime

template<typename RegistreeInfo , typename TimeKeyType >
std::pair<uint32_t, uint32_t> adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_lastWallTime
private

◆ m_limitSimulationSpeed

template<typename RegistreeInfo , typename TimeKeyType >
bool adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_limitSimulationSpeed
private

◆ m_minRegisters

template<typename RegistreeInfo , typename TimeKeyType >
int adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_minRegisters
private

◆ m_notificationReader

template<typename RegistreeInfo , typename TimeKeyType >
ros::Subscriber adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_notificationReader
private

◆ m_now

template<typename RegistreeInfo , typename TimeKeyType >
TimeKeyType adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_now
private

◆ m_pause

template<typename RegistreeInfo , typename TimeKeyType >
bool adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_pause
private

◆ m_printIntervalS

template<typename RegistreeInfo , typename TimeKeyType >
int adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_printIntervalS
private

◆ m_schedule

template<typename RegistreeInfo , typename TimeKeyType >
ScheduleMap* adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_schedule
private

◆ m_schedulerNotificationConversion

template<typename RegistreeInfo , typename TimeKeyType >
SchedulerNotificationConversion adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_schedulerNotificationConversion
private

◆ m_simulationTimeWriter

template<typename RegistreeInfo , typename TimeKeyType >
ros::Publisher adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_simulationTimeWriter
private

◆ m_started

template<typename RegistreeInfo , typename TimeKeyType >
bool adore_if_ros_scheduling::Scheduler< RegistreeInfo, TimeKeyType >::m_started
private

The documentation for this class was generated from the following file: