Namespaces | Classes | Typedefs | Functions | Variables
ros Namespace Reference

Namespaces

 debug
 

Classes

class  Duration
 Duration representation for use with the Time class. More...
 
class  DurationBase
 Base class for Duration implementations. Provides storage, common functions and operator overloads. This should not need to be used directly. More...
 
class  Exception
 
class  Header
 
class  NoHighPerformanceTimersException
 Thrown if windows high perf. timestamping is unavailable. More...
 
class  Rate
 Class to help run loops at a desired frequency. More...
 
class  SteadyTime
 Time representation. Always steady-clock time. More...
 
class  Time
 Time representation. May either represent wall clock time or ROS clock time. More...
 
class  TimeBase
 Base class for Time implementations. Provides storage, common functions and operator overloads. This should not need to be used directly. More...
 
class  TimeNotInitializedException
 Thrown if the ros subsystem hasn't been initialised before use. More...
 
class  WallDuration
 Duration representation for use with the WallTime class. More...
 
class  WallRate
 Class to help run loops at a desired frequency. This version always uses wall-clock time. More...
 
class  WallTime
 Time representation. Always wall-clock time. More...
 

Typedefs

typedef std::map< std::string, std::string > M_string
 
typedef boost::shared_ptr< M_stringM_stringPtr
 
typedef std::set< std::string > S_string
 
typedef std::pair< std::string, std::string > StringPair
 
typedef std::vector< std::string > V_string
 
typedef std::vector< std::pair< std::string, std::string > > VP_string
 

Functions

const Duration DURATION_MAX (std::numeric_limits< int32_t >::max(), 999999999)
 
const Duration DURATION_MIN (std::numeric_limits< int32_t >::min(), 0)
 
static bool g_initialized (false)
 
static bool g_stopped (false)
 
static bool g_use_sim_time (true)
 
bool get_environment_variable (std::string &str, const char *environment_variable)
 
ROSTIME_DECL void normalizeSecNSec (uint64_t &sec, uint64_t &nsec)
 
ROSTIME_DECL void normalizeSecNSec (uint32_t &sec, uint32_t &nsec)
 
ROSTIME_DECL void normalizeSecNSecSigned (int64_t &sec, int64_t &nsec)
 
ROSTIME_DECL void normalizeSecNSecSigned (int32_t &sec, int32_t &nsec)
 
ROSTIME_DECL void normalizeSecNSecUnsigned (int64_t &sec, int64_t &nsec)
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const Duration &rhs)
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const WallDuration &rhs)
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const Time &rhs)
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const WallTime &rhs)
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const SteadyTime &rhs)
 
int ros_nanosleep (const uint32_t &sec, const uint32_t &nsec)
 Simple representation of the rt library nanosleep function. More...
 
ROSTIME_DECL void ros_steadytime (uint32_t &sec, uint32_t &nsec)
 
bool ros_wallsleep (uint32_t sec, uint32_t nsec)
 Go to the wall! More...
 
ROSTIME_DECL void ros_walltime (uint32_t &sec, uint32_t &nsec)
 
const Time TIME_MAX (std::numeric_limits< uint32_t >::max(), 999999999)
 
const Time TIME_MIN (0, 1)
 

Variables

ROSTIME_DECL const Duration DURATION_MAX
 
ROSTIME_DECL const Duration DURATION_MIN
 
static Time g_sim_time (0, 0)
 
static boost::mutex g_sim_time_mutex
 
ROSTIME_DECL const Time TIME_MAX
 
ROSTIME_DECL const Time TIME_MIN
 

Function Documentation

const Duration ros::DURATION_MAX ( std::numeric_limits< int32_t >  ::max(),
999999999   
)
const Duration ros::DURATION_MIN ( std::numeric_limits< int32_t >  ::min(),
 
)
static bool ros::g_initialized ( false  )
static
static bool ros::g_stopped ( false  )
static
static bool ros::g_use_sim_time ( true  )
static
void ros::normalizeSecNSec ( uint64_t &  sec,
uint64_t &  nsec 
)

Definition at line 473 of file src/time.cpp.

void ros::normalizeSecNSec ( uint32_t &  sec,
uint32_t &  nsec 
)

Definition at line 485 of file src/time.cpp.

void ros::normalizeSecNSecSigned ( int64_t &  sec,
int64_t &  nsec 
)

Definition at line 47 of file src/duration.cpp.

void ros::normalizeSecNSecSigned ( int32_t &  sec,
int32_t &  nsec 
)

Definition at line 64 of file src/duration.cpp.

void ros::normalizeSecNSecUnsigned ( int64_t &  sec,
int64_t &  nsec 
)

Definition at line 496 of file src/time.cpp.

std::ostream & ros::operator<< ( std::ostream &  os,
const Duration rhs 
)

Definition at line 320 of file src/time.cpp.

std::ostream & ros::operator<< ( std::ostream &  os,
const WallDuration rhs 
)

Definition at line 454 of file src/time.cpp.

std::ostream & ros::operator<< ( std::ostream &  os,
const Time rhs 
)

Definition at line 313 of file src/time.cpp.

std::ostream & ros::operator<< ( std::ostream &  os,
const WallTime rhs 
)

Definition at line 424 of file src/time.cpp.

std::ostream & ros::operator<< ( std::ostream &  os,
const SteadyTime rhs 
)

Definition at line 431 of file src/time.cpp.

int ros::ros_nanosleep ( const uint32_t &  sec,
const uint32_t &  nsec 
)

Simple representation of the rt library nanosleep function.

Definition at line 171 of file src/time.cpp.

void ros::ros_steadytime ( uint32_t &  sec,
uint32_t &  nsec 
)

Definition at line 133 of file src/time.cpp.

bool ros::ros_wallsleep ( uint32_t  sec,
uint32_t  nsec 
)

Go to the wall!

Todo:
Fully implement the win32 parts, currently just like a regular sleep.

Definition at line 187 of file src/time.cpp.

void ros::ros_walltime ( uint32_t &  sec,
uint32_t &  nsec 
)

Definition at line 104 of file src/time.cpp.

const Time ros::TIME_MAX ( std::numeric_limits< uint32_t >  ::max(),
999999999   
)
const Time ros::TIME_MIN ( ,
 
)

Variable Documentation

ROSTIME_DECL const Duration ros::DURATION_MAX
ROSTIME_DECL const Duration ros::DURATION_MIN
Time ros::g_sim_time(0, 0)
static
boost::mutex ros::g_sim_time_mutex
static

Definition at line 95 of file src/time.cpp.

ROSTIME_DECL const Time ros::TIME_MAX
const Time ros::TIME_MIN(0, 1)


rostime
Author(s): Josh Faust
autogenerated on Mon Jul 27 2020 03:22:42