* Fix roslib doxygen according to review

* Fix ros::TIME_MAX/MIN
This commit is contained in:
Josh Faust 2010-01-13 03:58:44 +00:00
parent 810a12e0a1
commit e58c0e6337
4 changed files with 53 additions and 6 deletions

View File

@ -82,6 +82,10 @@ inline void normalizeSecNSecSigned(int32_t& sec, int32_t& nsec)
nsec = (int32_t)nsec64;
}
/**
* \brief Base class for Duration implementations. Provides storage, common functions and operator overloads.
* This should not need to be used directly.
*/
template<class T>
class DurationBase
{
@ -111,6 +115,11 @@ public:
bool isZero();
};
/**
* \brief Duration representation for use with the Time class.
*
* ros::DurationBase provides most of its functionality.
*/
class Duration : public DurationBase<Duration>
{
public:
@ -133,6 +142,11 @@ public:
extern const Duration DURATION_MAX;
extern const Duration DURATION_MIN;
/**
* \brief Duration representation for use with the WallTime class.
*
* ros::DurationBase provides most of its functionality.
*/
class WallDuration : public DurationBase<WallDuration>
{
public:

View File

@ -96,6 +96,10 @@ inline void normalizeSecNSecUnsigned(int64_t& sec, int64_t& nsec)
nsec = nsec_part;
}
/**
* \brief Base class for Time implementations. Provides storage, common functions and operator overloads.
* This should not need to be used directly.
*/
template<class T, class D>
class TimeBase
{
@ -131,6 +135,11 @@ public:
inline bool is_zero() const { return isZero(); }
};
/**
* \brief Time representation. May either represent wall clock time or ROS clock time.
*
* ros::TimeBase provides most of its functionality.
*/
class Time : public TimeBase<Time, Duration>
{
public:
@ -144,7 +153,14 @@ public:
explicit Time(double t) { fromSec(t); }
/**
* \brief Retrieve the current time. If ROS clock time is in use, this returns the time according to the
* ROS clock. Otherwise returns the current wall clock time.
*/
static Time now();
/**
* \brief Sleep until a specific time has been reached.
*/
static bool sleepUntil(const Time& end);
static void init();
@ -156,9 +172,14 @@ private:
static bool use_system_time_;
};
static const Time TIME_MAX = ros::Time(UINT_MAX, 999999999);
static const Time TIME_MIN = ros::Time(0, 0);
extern const Time TIME_MAX;
extern const Time TIME_MIN;
/**
* \brief Time representation. Always wall-clock time.
*
* ros::TimeBase provides most of its functionality.
*/
class WallTime : public TimeBase<WallTime, WallDuration>
{
public:
@ -172,8 +193,14 @@ public:
explicit WallTime(double t) { fromSec(t); }
/**
* \brief Returns the current wall clock time.
*/
static WallTime now();
/**
* \brief Sleep until a specific time has been reached.
*/
static bool sleepUntil(const WallTime& end);
};

View File

@ -3,7 +3,7 @@
\htmlinclude manifest.html
\b roslib is the base library support for ROS <a href="http://ros.org/wiki/Client Libraries">client implementations</a> as well as ROS tools. It includes:
\b %roslib is the base library support for ROS <a href="http://ros.org/wiki/Client Libraries">client implementations</a> as well as ROS tools. It includes:
- common message definitions used in ROS clients (e.g. Header)
- a Python library for manipulating ROS system resources (e.g. .msg files, names)
@ -11,6 +11,8 @@
\section codeapi Code API
- Time-related: ros::Time, ros::Duration, ros::Rate, ros::WallTime, ros::WallDuration, ros::WallRate. Also see the <a href="http://ros.org/wiki/roscpp/Overview/Time">roscpp Time overview</a>.
- Package-related: ros::package namespace
- Debug-related: ros::debug namespace
*/

View File

@ -37,6 +37,7 @@
#include <time.h>
#include <iomanip>
#include <stdexcept>
#include <limits>
#include <config.h>
@ -58,8 +59,11 @@ using namespace std;
ros::Time ros::Time::sim_time_(0, 0);
bool ros::Time::use_system_time_(true);
const Duration ros::DURATION_MAX(INT_MAX, 999999999);
const Duration ros::DURATION_MIN(INT_MIN, 0);
const Duration ros::DURATION_MAX(std::numeric_limits<int32_t>::max(), 999999999);
const Duration ros::DURATION_MIN(std::numeric_limits<int32_t>::min(), 0);
const Time ros::TIME_MAX(std::numeric_limits<uint32_t>::max(), 999999999);
const Time ros::TIME_MIN(0, 0);
// This is declared here because it's set from the Time class but read from
// the Duration class, and need not be exported to users of either.