Use std::chrono instead of custom timestamp function
Signed-off-by: Jacob Perron <jacobmperron@gmail.com>
This commit is contained in:
parent
111b062251
commit
eaeea24a21
3 changed files with 5 additions and 16 deletions
|
@ -34,6 +34,7 @@ POSSIBILITY OF SUCH DAMAGE.
|
|||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <boost/numeric/ublas/matrix.hpp>
|
||||
#include <chrono>
|
||||
#include <string>
|
||||
#include <unistd.h>
|
||||
|
||||
|
@ -79,7 +80,7 @@ namespace create {
|
|||
float totalLeftDist;
|
||||
float totalRightDist;
|
||||
bool firstOnData;
|
||||
util::timestamp_t prevOnDataTime;
|
||||
std::chrono::time_point<std::chrono::system_clock> prevOnDataTime;
|
||||
|
||||
Matrix poseCovar;
|
||||
|
||||
|
|
|
@ -32,8 +32,6 @@ POSSIBILITY OF SUCH DAMAGE.
|
|||
#ifndef CREATE_UTIL_H
|
||||
#define CREATE_UTIL_H
|
||||
|
||||
#include <sys/time.h>
|
||||
|
||||
#define COUT(prefix,msg) (std::cout<<prefix<<msg<<std::endl)
|
||||
#define CERR(prefix,msg) (std::cerr<<prefix<<msg<<std::endl)
|
||||
|
||||
|
@ -57,16 +55,6 @@ namespace create {
|
|||
return a;
|
||||
}
|
||||
|
||||
typedef unsigned long long timestamp_t;
|
||||
|
||||
/** Get a timestamp for the current time in micro-seconds.
|
||||
*/
|
||||
inline timestamp_t getTimestamp() {
|
||||
struct timeval now;
|
||||
gettimeofday(&now, NULL);
|
||||
return now.tv_usec + (timestamp_t) now.tv_sec * 1000000;
|
||||
}
|
||||
|
||||
inline bool willFloatOverflow(const float a, const float b) {
|
||||
return ( (a < 0.0) == (b < 0.0) && std::abs(b) > std::numeric_limits<float>::max() - std::abs(a) );
|
||||
}
|
||||
|
|
|
@ -94,13 +94,13 @@ namespace create {
|
|||
prevTicksLeft = GET_DATA(ID_LEFT_ENC);
|
||||
prevTicksRight = GET_DATA(ID_RIGHT_ENC);
|
||||
}
|
||||
prevOnDataTime = util::getTimestamp();
|
||||
prevOnDataTime = std::chrono::system_clock::now();
|
||||
firstOnData = false;
|
||||
}
|
||||
|
||||
// Get current time
|
||||
util::timestamp_t curTime = util::getTimestamp();
|
||||
float dt = (curTime - prevOnDataTime) / 1000000.0;
|
||||
auto curTime = std::chrono::system_clock::now();
|
||||
float dt = static_cast<std::chrono::duration<float>>(curTime - prevOnDataTime).count();
|
||||
float deltaDist, deltaX, deltaY, deltaYaw, leftWheelDist, rightWheelDist, wheelDistDiff;
|
||||
|
||||
// Protocol versions 1 and 2 use distance and angle fields for odometry
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue