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::Baseapp Class Reference

#include <baseapp.h>

Inheritance diagram for adore_if_ros_scheduling::Baseapp:
Inheritance graph
Collaboration diagram for adore_if_ros_scheduling::Baseapp:
Collaboration graph

Public Member Functions

 Baseapp ()
 
void init (int argc, char **argv, double rate, std::string nodename)
 
void initSim ()
 
virtual void resume ()
 
virtual void pause ()
 
virtual void run ()
 
virtual void addTimerCallback (std::function< void()> &callbackFcn, double rate_factor=1.0)
 
template<typename T >
bool getParam (const std::string name, T &val)
 
template<typename T >
bool getParam (const std::string name, T &val, const T &default_val)
 

Static Public Member Functions

static void schedulerCallback (const ros::TimerEvent &e)
 
static ros::NodeHandle * getRosNodeHandle ()
 
static void func (std::function< void()> &callback, const ros::TimerEvent &te)
 

Private Attributes

std::vector< ros::Timer > timers_
 
bool useScheduler_
 
double rate_
 

Static Private Attributes

static ros::NodeHandle * m_pN = 0
 
static adore_if_ros_scheduling::SchedulerNotificationManagersnm_
 

Detailed Description

Base class for ros nodes - Baseapp provides functions that can be used by derived ros nodes. It handles the communication with the scheduler node.

Constructor & Destructor Documentation

◆ Baseapp()

adore_if_ros_scheduling::Baseapp::Baseapp ( )
inline

Member Function Documentation

◆ addTimerCallback()

virtual void adore_if_ros_scheduling::Baseapp::addTimerCallback ( std::function< void()> &  callbackFcn,
double  rate_factor = 1.0 
)
inlinevirtual

addTimerCallback - add a function that should be called periodically

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

◆ func()

static void adore_if_ros_scheduling::Baseapp::func ( std::function< void()> &  callback,
const ros::TimerEvent &  te 
)
inlinestatic
Here is the caller graph for this function:

◆ getParam() [1/2]

template<typename T >
bool adore_if_ros_scheduling::Baseapp::getParam ( const std::string  name,
T &  val 
)
inline

getParam - retrieve ros parameter

Here is the caller graph for this function:

◆ getParam() [2/2]

template<typename T >
bool adore_if_ros_scheduling::Baseapp::getParam ( const std::string  name,
T &  val,
const T &  default_val 
)
inline

getParam - retrieve ros parameter with default

◆ getRosNodeHandle()

static ros::NodeHandle* adore_if_ros_scheduling::Baseapp::getRosNodeHandle ( )
inlinestatic

getRosNodeHandle - return ros::NodeHandle pointer

Here is the caller graph for this function:

◆ init()

void adore_if_ros_scheduling::Baseapp::init ( int  argc,
char **  argv,
double  rate,
std::string  nodename 
)
inline

init - initializes the ros node

◆ initSim()

void adore_if_ros_scheduling::Baseapp::initSim ( )
inline

initSim - intilizes functionalites for simulation

Here is the call graph for this function:

◆ pause()

virtual void adore_if_ros_scheduling::Baseapp::pause ( )
inlinevirtual

pause - pauses updating the upper time bound

Here is the call graph for this function:

◆ resume()

virtual void adore_if_ros_scheduling::Baseapp::resume ( )
inlinevirtual

resume - resumes updating the upper time bound

Here is the call graph for this function:

◆ run()

virtual void adore_if_ros_scheduling::Baseapp::run ( )
inlinevirtual

run

Here is the caller graph for this function:

◆ schedulerCallback()

static void adore_if_ros_scheduling::Baseapp::schedulerCallback ( const ros::TimerEvent &  e)
inlinestatic

schedulerCallback - notifies scheduler of the new upper bound in time

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

Member Data Documentation

◆ m_pN

ros::NodeHandle* adore_if_ros_scheduling::Baseapp::m_pN = 0
inlinestaticprivate

◆ rate_

double adore_if_ros_scheduling::Baseapp::rate_
private

◆ snm_

adore_if_ros_scheduling::SchedulerNotificationManager* adore_if_ros_scheduling::Baseapp::snm_
inlinestaticprivate
Initial value:
=
0

◆ timers_

std::vector<ros::Timer> adore_if_ros_scheduling::Baseapp::timers_
private

◆ useScheduler_

bool adore_if_ros_scheduling::Baseapp::useScheduler_
private

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