|
From: <tf...@us...> - 2009-01-22 02:22:11
|
Revision: 9948
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=9948&view=rev
Author: tfoote
Date: 2009-01-22 01:30:15 +0000 (Thu, 22 Jan 2009)
Log Message:
-----------
disambiguating ros::Time constructors
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp
pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/highlevel_controller.hh
pkg/trunk/mapping/collision_map/src/collision_map.cpp
pkg/trunk/nav/trajectory_rollout/src/governor_node.cpp
pkg/trunk/vision/people/src/face_detection.cpp
pkg/trunk/vision/people/src/train_leg_detector.cpp
pkg/trunk/world_models/costmap_2d/src/observation_buffer.cc
pkg/trunk/world_models/map_server/test/rtest.cpp
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp 2009-01-22 01:06:42 UTC (rev 9947)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp 2009-01-22 01:30:15 UTC (rev 9948)
@@ -495,7 +495,7 @@
{
if (publisher_->trylock())
{
- publisher_->msg_.header.stamp = ros::Time((uint64_t) (c_->getTime()*1000000000)) ;
+ publisher_->msg_.header.stamp = ros::Time().fromSec(c_->getTime()) ;
publisher_->msg_.signal = m_scanner_signal_.signal ;
publisher_->unlockAndPublish() ;
need_to_send_msg_ = false ;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp 2009-01-22 01:06:42 UTC (rev 9947)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp 2009-01-22 01:30:15 UTC (rev 9948)
@@ -146,7 +146,7 @@
libTF::Vector ang_rates;
ros::Time start_time = ros::Time::now();
- ros::Duration sleep_time(0.01);
+ ros::Duration sleep_time = ros::Duration().fromSec(0.01);
std::ofstream odom_log_file;
odom_log_file.open("odom_log.txt");
Modified: pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/highlevel_controller.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/highlevel_controller.hh 2009-01-22 01:06:42 UTC (rev 9947)
+++ pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/highlevel_controller.hh 2009-01-22 01:30:15 UTC (rev 9948)
@@ -413,7 +413,7 @@
ros::Duration diff = desiredCycleEnd - curr;
- if(diff <= ros::Duration(0)){
+ if(diff <= ros::Duration()){
ROS_DEBUG("Missed deadline and not sleeping; check machine load. Started %f, ended %f, wanted end %f. Wanted delta %f, got %f. Tryed to correct %f sec.\n",
loopstart.toSec(), curr.toSec(), desiredCycleEnd.toSec(), cycleTime.toSec(), (curr - loopstart).toSec(), diff.toSec());
} else {
Modified: pkg/trunk/mapping/collision_map/src/collision_map.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map.cpp 2009-01-22 01:06:42 UTC (rev 9947)
+++ pkg/trunk/mapping/collision_map/src/collision_map.cpp 2009-01-22 01:30:15 UTC (rev 9948)
@@ -218,7 +218,7 @@
PointStamped base_origin, torso_lift_origin;
base_origin.point.x = base_origin.point.y = base_origin.point.z = 0.0;
base_origin.header.frame_id = "torso_lift_link";
- base_origin.header.stamp = ros::Time(0.0);
+ base_origin.header.stamp = ros::Time();
try
{
Modified: pkg/trunk/nav/trajectory_rollout/src/governor_node.cpp
===================================================================
--- pkg/trunk/nav/trajectory_rollout/src/governor_node.cpp 2009-01-22 01:06:42 UTC (rev 9947)
+++ pkg/trunk/nav/trajectory_rollout/src/governor_node.cpp 2009-01-22 01:30:15 UTC (rev 9948)
@@ -212,7 +212,7 @@
ros::Duration sleepTime = ros::Time::now() - end;
- if (sleepTime <= ros::Duration(0))
+ if (sleepTime <= ros::Duration())
printf("Governor Node missed deadline and is not sleeping\n");
else
sleepTime.sleep();
Modified: pkg/trunk/vision/people/src/face_detection.cpp
===================================================================
--- pkg/trunk/vision/people/src/face_detection.cpp 2009-01-22 01:06:42 UTC (rev 9947)
+++ pkg/trunk/vision/people/src/face_detection.cpp 2009-01-22 01:30:15 UTC (rev 9948)
@@ -206,7 +206,7 @@
if (it == pos_list_.end()) {
pos_list_.insert(pair<string, RestampedPositionMeasurement>(pos_.object_id, rpm));
}
- else if (pos_.header.stamp - (*it).second.pos.header.stamp > ros::Duration(-1.0) ){
+ else if (pos_.header.stamp - (*it).second.pos.header.stamp > ros::Duration().fromSec(-1.0) ){
(*it).second = rpm;
}
lock.unlock();
Modified: pkg/trunk/vision/people/src/train_leg_detector.cpp
===================================================================
--- pkg/trunk/vision/people/src/train_leg_detector.cpp 2009-01-22 01:06:42 UTC (rev 9947)
+++ pkg/trunk/vision/people/src/train_leg_detector.cpp 2009-01-22 01:30:15 UTC (rev 9948)
@@ -86,7 +86,7 @@
}
ros::record::Player p;
- if (p.open(file, ros::Time(0ull)))
+ if (p.open(file, ros::Time()))
{
mask_.clear();
mask_count_ = 0;
Modified: pkg/trunk/world_models/costmap_2d/src/observation_buffer.cc
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/observation_buffer.cc 2009-01-22 01:06:42 UTC (rev 9947)
+++ pkg/trunk/world_models/costmap_2d/src/observation_buffer.cc 2009-01-22 01:30:15 UTC (rev 9948)
@@ -85,7 +85,7 @@
void ObservationBuffer::get_observations(std::vector<Observation>& observations){
// If the duration is 0, then we just keep the latest one, so we must have a limit of one.
// If the duration is non-zero, we want to delete all the observations.
- unsigned int min_observations = (keep_alive_ == ros::Duration(0)) ? 1 : 0;
+ unsigned int min_observations = (keep_alive_ == ros::Duration()) ? 1 : 0;
while(buffer_.size() > min_observations){
std::list<Observation>::iterator it = buffer_.begin();
Modified: pkg/trunk/world_models/map_server/test/rtest.cpp
===================================================================
--- pkg/trunk/world_models/map_server/test/rtest.cpp 2009-01-22 01:06:42 UTC (rev 9947)
+++ pkg/trunk/world_models/map_server/test/rtest.cpp 2009-01-22 01:30:15 UTC (rev 9948)
@@ -77,7 +77,7 @@
break;
else
{
- ros::Duration d(0.25);
+ ros::Duration d = ros::Duration().fromSec(0.25);
d.sleep();
}
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|