ros Namespace Reference

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  NoHighPerformanceTimersException
 Thrown if windoze high perf. timestamping is unavailable. More...
class  Rate
 Class to help run loops at a desired frequency. 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...

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)
void normalizeSecNSec (uint32_t &sec, uint32_t &nsec)
void normalizeSecNSec (uint64_t &sec, uint64_t &nsec)
void normalizeSecNSecSigned (int32_t &sec, int32_t &nsec)
void normalizeSecNSecSigned (int64_t &sec, int64_t &nsec)
void normalizeSecNSecUnsigned (int64_t &sec, int64_t &nsec)
std::ostream & operator<< (std::ostream &os, const WallTime &rhs)
std::ostream & operator<< (std::ostream &os, const Time &rhs)
std::ostream & operator<< (std::ostream &os, const WallDuration &rhs)
std::ostream & operator<< (std::ostream &os, const Duration &rhs)
int ros_nanosleep (const uint32_t &sec, const uint32_t &nsec)
 Simple representation of the rt library nanosleep function.
bool ros_wallsleep (uint32_t sec, uint32_t nsec)
 Go to the wall!
void ros_walltime (uint32_t &sec, uint32_t &nsec) throw (NoHighPerformanceTimersException)
const Time TIME_MAX (std::numeric_limits< uint32_t >::max(), 999999999)
const Time TIME_MIN (0, 1)

Variables

const Duration DURATION_MAX
const Duration DURATION_MIN
static Time g_sim_time (0, 0)
static boost::mutex g_sim_time_mutex
const Time TIME_MAX
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 ( uint32_t &  sec,
uint32_t &  nsec 
) [inline]

Definition at line 107 of file time.h.

void ros::normalizeSecNSec ( uint64_t &  sec,
uint64_t &  nsec 
) [inline]

Definition at line 95 of file time.h.

void ros::normalizeSecNSecSigned ( int32_t &  sec,
int32_t &  nsec 
) [inline]

Definition at line 70 of file duration.h.

void ros::normalizeSecNSecSigned ( int64_t &  sec,
int64_t &  nsec 
) [inline]

Definition at line 47 of file duration.h.

void ros::normalizeSecNSecUnsigned ( int64_t &  sec,
int64_t &  nsec 
) [inline]

Definition at line 118 of file time.h.

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

Definition at line 392 of file time.cpp.

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

Definition at line 303 of file time.cpp.

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

Definition at line 406 of file time.cpp.

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

Definition at line 309 of file 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 162 of file 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 198 of file time.cpp.

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

Definition at line 88 of file time.cpp.

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

Variable Documentation

Time ros::g_sim_time(0, 0) [static]
boost::mutex ros::g_sim_time_mutex [static]

Definition at line 75 of file time.cpp.

const Time ros::TIME_MIN(0, 1)
 All Classes Namespaces Files Functions Variables Defines


rostime
Author(s): Josh Faust
autogenerated on Fri Jan 11 10:03:29 2013