|
From: <tf...@us...> - 2008-12-06 02:36:40
|
Revision: 7719
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7719&view=rev
Author: tfoote
Date: 2008-12-06 02:36:34 +0000 (Sat, 06 Dec 2008)
Log Message:
-----------
results from changing ros::Time constructor and all uses of it I can find
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_position_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp
pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp
pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h
pkg/trunk/hardware_test/self_test/include/self_test/self_test.h
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
pkg/trunk/nav/amcl_player/cli.cpp
pkg/trunk/nav/nav_view_sdl/nav_view.cpp
pkg/trunk/nav/wavefront_player/cli.cpp
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
pkg/trunk/util/logsetta/imu/imu_extract.cpp
pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp
pkg/trunk/util/logsetta/odom/odom_extract.cpp
pkg/trunk/util/tf/include/tf/tf.h
pkg/trunk/util/tf/src/cache.cpp
pkg/trunk/util/tf/src/transform_listener.cpp
pkg/trunk/vision/calib_converter/src/calib_converter.cpp
pkg/trunk/vision/stereo_view/stereo_view.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp
pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_position_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_position_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -311,7 +311,7 @@
int ticks=0;
static const double interval=1e-2;
const int max_ticks = int(cmd.timeout/interval);
- ros::Duration d=ros::Duration(interval);
+ ros::Duration d=ros::Duration().fromSec(interval);
while(!(c_->goalAchieved() || ticks >= max_ticks))
{
d.sleep();
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -160,7 +160,7 @@
void BasePositionControllerNode::setPoseCommand(std_msgs::PoseStamped cmd)
{
std_msgs::PoseStamped pose_odom ; // Stores the pose in the odometric frame
- cmd.header.stamp = ros::Time(0.0) ; // Transform using the latest transform
+ cmd.header.stamp = ros::Time(0) ; // Transform using the latest transform
tf_.transformPose(odom_frame_name_, cmd, pose_odom) ;
tf::Quaternion orientation_odom ; // Orientation in the odometric frame
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -222,11 +222,11 @@
point.setX(head_track_point_.point.x);
point.setY(head_track_point_.point.y);
point.setZ(head_track_point_.point.z);
- point.stamp_ =0.0;
+ point.stamp_ =0;
point.frame_id_ = head_track_point_.header.frame_id;
std::string pan_parent;
- TF.getParent("head_pan_link", 0.0, pan_parent);
+ TF.getParent("head_pan_link", 0, pan_parent);
std::string tilt_parent("head_pan_link");
// Pan angle
@@ -282,12 +282,12 @@
point.setX(frame_track_point_.point.x);
point.setY(frame_track_point_.point.y);
point.setZ(frame_track_point_.point.z);
- point.stamp_ = 0.0;//get the latest transform
+ point.stamp_ = 0;//get the latest transform
point.frame_id_ = frame_track_point_.header.frame_id;
try
{
- TF.lookupTransform(point.frame_id_,"head_pan_link",ros::Time(0.0),frame);
+ TF.lookupTransform(point.frame_id_,"head_pan_link",ros::Time(0),frame);
}
catch(tf::TransformException& ex)
{
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -304,7 +304,7 @@
try
{
- TF.lookupTransform(point.frame_id_,"head_pan",ros::Time(0.0),frame);
+ TF.lookupTransform(point.frame_id_,"head_pan",ros::Time(0),frame);
}
catch(tf::TransformException& ex)
{
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -85,7 +85,7 @@
sleep(4);
ros::Time start_time = ros::Time::now();
- ros::Duration sleep_time(0.01);
+ ros::Duration sleep_time = ros::Duration().fromSec(0.01);
/* while(!done)
{
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -121,7 +121,7 @@
: robot_(NULL), pos_publisher_(NULL), TF(*ros::node::instance(), false) , loop_count_(0)
{
assert(ros::node::instance());
- TF.setExtrapolationLimit(ros::Duration(10.0e-3));
+ TF.setExtrapolationLimit(ros::Duration().fromSec(10.0e-3));
}
CartesianOrientationControllerNode::~CartesianOrientationControllerNode()
@@ -179,7 +179,7 @@
{
if (pos_publisher_->trylock())
{
- pos_publisher_->msg_.header.stamp = robot_->hw_->current_time_;
+ pos_publisher_->msg_.header.stamp.fromSec(robot_->hw_->current_time_);
pos_publisher_->msg_.header.frame_id = c_.rootFrame();
tf::Quaternion q;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -120,7 +120,7 @@
: robot_(NULL), pos_publisher_(NULL), TF(*ros::node::instance(), false) , loop_count_(0)
{
assert(ros::node::instance());
- TF.setExtrapolationLimit(ros::Duration(10.0e-3));
+ TF.setExtrapolationLimit(ros::Duration(10000000));
}
CartesianPositionControllerNode::~CartesianPositionControllerNode()
@@ -179,7 +179,7 @@
{
if (pos_publisher_->trylock())
{
- pos_publisher_->msg_.header.stamp = robot_->hw_->current_time_;
+ pos_publisher_->msg_.header.stamp.fromSec(robot_->hw_->current_time_);
pos_publisher_->msg_.header.frame_id = c_.rootFrame();
tf::Point p;
Modified: pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp
===================================================================
--- pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -412,7 +412,7 @@
{
dc1394_cam::FrameSet fs = cd.cam->getFrames(DC1394_CAPTURE_POLICY_POLL);
- ros::Time ts = ros::Time::now() + ros::Duration(-.125);
+ ros::Time ts = ros::Time::now() + ros::Duration().fromSec(-.125);
if (fs.size() > 0)
{
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -104,7 +104,7 @@
PointCloudAssembler() : ros::node("point_cloud_assembler"), tf_(*this)
{
- tf_.setExtrapolationLimit(ros::Duration(1.0)) ;
+ tf_.setExtrapolationLimit(ros::Duration().fromSec(1.0)) ;
advertise_service("build_cloud", &PointCloudAssembler::buildCloud, this, 0) ; // Don't spawn threads so that we can avoid dealing with mutexing [for now]
subscribe("scan", scan_, &PointCloudAssembler::scans_callback, 40) ;
Modified: pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
===================================================================
--- pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -296,7 +296,7 @@
// broadcast most recent estimate to TransformArray
Stamped<Transform> tmp;
- my_filter_.getEstimate(0.0, tmp);
+ my_filter_.getEstimate(0, tmp);
odom_broadcaster_.sendTransform(Stamped<Transform>(tmp.inverse(), tmp.stamp_, "odom_combined", "base_footprint"));
#ifdef __EKF_DEBUG_FILE__
Modified: pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp
===================================================================
--- pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -68,7 +68,7 @@
virtual void processData() = 0;
virtual bool loadData(std::string filename) {
- if (!mLp.open(filename, ros::Time(0.0))) return false;
+ if (!mLp.open(filename, ros::Time(0))) return false;
mLp.addHandler<OctreeLearningMsg>(std::string("grasp_learning_bus"),
©Msg<OctreeLearningMsg>, (void*)this, true);
mNewMsg = false;
Modified: pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h
===================================================================
--- pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h 2008-12-06 02:36:34 UTC (rev 7719)
@@ -66,7 +66,7 @@
((ros::node*)(node_))->advertise<robot_msgs::DiagnosticMessage>("/diagnostics", 1);
node_->param("~diagnostic_period", period_, 1.0);
- next_time_ = ros::Time::now() + ros::Duration(period_);
+ next_time_ = ros::Time::now() + ros::Duration().fromSec(period_);
}
void addUpdater(void (T::*f)(robot_msgs::DiagnosticStatus&))
@@ -112,7 +112,7 @@
}
node_->param("~diagnostic_period", period_, 1.0);
- next_time_ = ros::Time::now() + ros::Duration(period_);
+ next_time_ = ros::Time::now() + ros::Duration().fromSec(period_);
}
double getPeriod()
Modified: pkg/trunk/hardware_test/self_test/include/self_test/self_test.h
===================================================================
--- pkg/trunk/hardware_test/self_test/include/self_test/self_test.h 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/hardware_test/self_test/include/self_test/self_test.h 2008-12-06 02:36:34 UTC (rev 7719)
@@ -130,7 +130,7 @@
while (!ready)
{
- if (!testing_condition.timed_wait(ros::Duration(5.0)))
+ if (!testing_condition.timed_wait(ros::Duration().fromSec(5.0)))
{
printf("Timed out waiting to run self test.\n");
waiting = false;
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-12-06 02:36:34 UTC (rev 7719)
@@ -190,7 +190,7 @@
void waitForState(void)
{
while (m_node->ok() && (m_haveState ^ loadedRobot()))
- ros::Duration(0.05).sleep();
+ ros::Duration().fromSec(0.05).sleep();
}
protected:
Modified: pkg/trunk/nav/amcl_player/cli.cpp
===================================================================
--- pkg/trunk/nav/amcl_player/cli.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/nav/amcl_player/cli.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -31,8 +31,8 @@
ros::init(argc, argv);
AmclCLI amcl_cli;
ros::Time t_start(ros::Time::now());
- while (amcl_cli.ok() && ros::Time::now() - t_start < 2.0 && !amcl_cli.done)
- ros::Duration(0.1).sleep();
+ while (amcl_cli.ok() && ros::Time::now() - t_start < ros::Duration().fromSec(2.0) && !amcl_cli.done)
+ ros::Duration().fromSec(0.1).sleep();
if (!amcl_cli.done)
printf("failed\n");
ros::fini();
Modified: pkg/trunk/nav/nav_view_sdl/nav_view.cpp
===================================================================
--- pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -355,7 +355,7 @@
tf::Stamped<tf::Pose> robotPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time(0.0);
+ robotPose.stamp_ = ros::Time(0);
tf::Stamped<tf::Pose> mapPose ;
tf.transformPose("map", robotPose, mapPose );
Modified: pkg/trunk/nav/wavefront_player/cli.cpp
===================================================================
--- pkg/trunk/nav/wavefront_player/cli.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/nav/wavefront_player/cli.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -32,7 +32,7 @@
{
wf_goal.enable = 0;
publish("goal", wf_goal);
- ros::Duration(0.5).sleep(); // hack to try and wait for the message to go
+ ros::Duration().fromSec(0.5).sleep(); // hack to try and wait for the message to go
}
virtual void peer_subscribe(const std::string &topic_name,
ros::pub_sub_conn * const psc)
@@ -57,8 +57,8 @@
WavefrontCLI wf_cli(atof(argv[1]), atof(argv[2]), atof(argv[3]));
ros::Time t_start(ros::Time::now());
while (wf_cli.ok() && wf_cli.state != WavefrontCLI::WF_DONE &&
- ros::Time::now() - t_start < max_secs)
- ros::Duration(0.1).sleep();
+ ros::Time::now() - t_start < ros::Duration().fromSec(max_secs))
+ ros::Duration().fromSec(0.1).sleep();
if (wf_cli.ok() && wf_cli.state != WavefrontCLI::WF_DONE) // didn't get there
{
printf("timeout\n");
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-06 02:36:34 UTC (rev 7719)
@@ -279,7 +279,7 @@
ang_eps(DTOR(4.0)),
cycletime(0.1),
laser_maxrange(4.0),
- laser_buffer_time(3.0),
+ laser_buffer_time(3000000000LL),
lookahead_maxdist(2.0),
lookahead_distweight(5.0),
tvmin(0.2),
@@ -288,8 +288,7 @@
avmax(DTOR(80.0)),
amin(DTOR(10.0)),
amax(DTOR(40.0)),
- tf(*this, true, (uint64_t)10000000000ULL)// cache for 10 sec, no extrapolation
- //tf(*this, true, (uint64_t)200000000ULL, (uint64_t)200000000ULL) //nanoseconds
+ tf(*this, true, 10000000000ULL) // cache for 10 sec, no extrapolation
{
// Initialize global pose. Will be set in control loop based on actual data.
///\todo does this need to be initialized? global_pose.setIdentity();
Modified: pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
===================================================================
--- pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -125,7 +125,7 @@
for (int i = 1; i < argc; i++)
files.push_back(argv[i]);
- player.open(files, ros::Time(0.0));
+ player.open(files, ros::Time(0));
player.addHandler<std_msgs::RobotBase2DOdom>(string("*"), &odom_callback, NULL);
player.addHandler<std_msgs::LaserScan>(string("*"), &scan_callback, NULL);
Modified: pkg/trunk/util/logsetta/imu/imu_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/imu/imu_extract.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/logsetta/imu/imu_extract.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -57,7 +57,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0.0));
+ player.open(std::string(argv[1]), ros::Time(0));
int count;
Modified: pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -57,7 +57,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0.0));
+ player.open(std::string(argv[1]), ros::Time(0));
int count;
Modified: pkg/trunk/util/logsetta/odom/odom_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/odom/odom_extract.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/logsetta/odom/odom_extract.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -62,7 +62,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0.0));
+ player.open(std::string(argv[1]), ros::Time(0));
int count;
Modified: pkg/trunk/util/tf/include/tf/tf.h
===================================================================
--- pkg/trunk/util/tf/include/tf/tf.h 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/tf/include/tf/tf.h 2008-12-06 02:36:34 UTC (rev 7719)
@@ -80,9 +80,9 @@
{
public:
/************* Constants ***********************/
- static const unsigned int MAX_GRAPH_DEPTH = 100; //!< The maximum number of time to recurse before assuming the tree has a loop.
- static const int64_t DEFAULT_CACHE_TIME = 10 * 1000000000ULL; //!< The default amount of time to cache data
- static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0; //!< The default amount of time to extrapolate
+ static const unsigned int MAX_GRAPH_DEPTH = 100UL; //!< The maximum number of time to recurse before assuming the tree has a loop.
+ static const int64_t DEFAULT_CACHE_TIME = 10ULL * 1000000000ULL; //!< The default amount of time to cache data
+ static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL; //!< The default amount of time to extrapolate
/** Constructor
@@ -91,7 +91,7 @@
*
*/
Transformer(bool interpolating = true,
- ros::Duration cache_time_ = ros::Duration(DEFAULT_CACHE_TIME));
+ ros::Duration cache_time_ = ros::Duration().fromNSec(DEFAULT_CACHE_TIME));
virtual ~Transformer(void);
/** \brief Clear all data */
Modified: pkg/trunk/util/tf/src/cache.cpp
===================================================================
--- pkg/trunk/util/tf/src/cache.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/tf/src/cache.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -88,7 +88,7 @@
}
//If time == 0 return the latest
- if (target_time == ros::Time(0.0))
+ if (target_time == ros::Time(0))
{
one = storage_.front();
mode = ONE_VALUE;
Modified: pkg/trunk/util/tf/src/transform_listener.cpp
===================================================================
--- pkg/trunk/util/tf/src/transform_listener.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/tf/src/transform_listener.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -202,7 +202,7 @@
// Extract transforms for the beginning and end of the laser scan
ros::Time start_time = scanIn.header.stamp ;
- ros::Time end_time = scanIn.header.stamp + ros::Duration(scanIn.get_ranges_size()*scanIn.time_increment) ;
+ ros::Time end_time = scanIn.header.stamp + ros::Duration().fromSec(scanIn.get_ranges_size()*scanIn.time_increment) ;
tf::Stamped<tf::Transform> start_transform ;
tf::Stamped<tf::Transform> end_transform ;
Modified: pkg/trunk/vision/calib_converter/src/calib_converter.cpp
===================================================================
--- pkg/trunk/vision/calib_converter/src/calib_converter.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/vision/calib_converter/src/calib_converter.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -81,7 +81,7 @@
// -- Load the messages.
- lp.open(fullname, ros::Time(0.0));
+ lp.open(fullname, ros::Time(0));
lp.addHandler<std_msgs::ImageArray>(string("videre/images"), ©Msg<std_msgs::ImageArray>, (void*)(&image_msg), true);
lp.addHandler<std_msgs::String>(string("videre/cal_params"), ©Msg<std_msgs::String>, (void*)(&calparams), true);
lp.addHandler<std_msgs::PointCloud>(string("full_cloud"), ©Msg<std_msgs::PointCloud>, (void*)(&cloud), true);
Modified: pkg/trunk/vision/stereo_view/stereo_view.cpp
===================================================================
--- pkg/trunk/vision/stereo_view/stereo_view.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/vision/stereo_view/stereo_view.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -78,7 +78,7 @@
StereoView() : ros::node("stereo_view"),
lcal(this), rcal(this), lcalimage(NULL), rcalimage(NULL),
- sync(this, &StereoView::image_cb_all, ros::Duration(0.05), &StereoView::image_cb_timeout),
+ sync(this, &StereoView::image_cb_all, ros::Duration().fromSec(0.05), &StereoView::image_cb_timeout),
subscribe_color_(false), calib_color_(false), recompand_(false)
{
cvNamedWindow("left", CV_WINDOW_AUTOSIZE);
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -69,8 +69,8 @@
, vis_panel_( panel )
, needs_reset_( false )
, new_ros_time_( false )
-, wall_clock_begin_( 0.0 )
-, ros_time_begin_( 0.0 )
+, wall_clock_begin_( 0 )
+, ros_time_begin_( 0 )
{
initializeCommon();
registerFactories( this );
@@ -234,8 +234,8 @@
resetDisplays();
tf_->clear();
- ros_time_begin_ = ros::Time( 0.0 );
- wall_clock_begin_ = ros::Time( 0.0 );
+ ros_time_begin_ = ros::Time( 0 );
+ wall_clock_begin_ = ros::Time( 0 );
}
static float time_update_timer = 0.0f;
Modified: pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp
===================================================================
--- pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -13,7 +13,7 @@
cout << "Loading messages... "; flush(cout);
- lp.open(file, ros::Time(0.0));
+ lp.open(file, ros::Time(0));
lp.addHandler<std_msgs::ImageArray>(string("videre/images"), ©Msg<std_msgs::ImageArray>, (void*)(&images_msg_), true);
lp.addHandler<std_msgs::ImageArray>(string("labeled_images"), ©Msg<std_msgs::ImageArray>, (void*)(&labeled_images_msg_), true);
lp.addHandler<std_msgs::PointCloud>(ptcld_topic_, ©Msg<std_msgs::PointCloud>, (void*)(&cloud_), true);
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -227,7 +227,8 @@
void publishDataThread(void)
{
- ros::Duration *d = new ros::Duration(1.0/m_maxPublishFrequency);
+ ros::Duration *d = new ros::Duration();
+ d->fromSec(1.0/m_maxPublishFrequency);
/* Pump out buffered, filtered point clouds and clear the buffer */
while (m_active)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|