|
From: <tf...@us...> - 2008-12-07 00:41:02
|
Revision: 7737
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7737&view=rev
Author: tfoote
Date: 2008-12-07 00:40:54 +0000 (Sun, 07 Dec 2008)
Log Message:
-----------
disambiguating all time and duration constructors
Modified Paths:
--------------
pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.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/robot_mechanism_controllers/src/cartesian_position_controller.cpp
pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp
pkg/trunk/drivers/imu/imu_node/imu_node.cc
pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp
pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation.cpp
pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp
pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp
pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
pkg/trunk/highlevel/highlevel_controllers/src/VelocityControllers.cpp
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/nav/nav_view_sdl/nav_view.cpp
pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
pkg/trunk/nav/slam_gmapping/src/tftest.cpp
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/trajectory_rollout/src/governor_node.cpp
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/time_cache.h
pkg/trunk/util/tf/include/tf/transform_datatypes.h
pkg/trunk/util/tf/include/tf/transform_listener.h
pkg/trunk/util/tf/src/cache.cpp
pkg/trunk/util/tf/src/tf.cpp
pkg/trunk/util/tf/test/testBroadcaster.cpp
pkg/trunk/vision/calib_converter/src/calib_converter.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/particle_cloud_2d_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/planning_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/tf_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/tools/pose_tool.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp
pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp
pkg/trunk/visualization/scene_labeler/include/scene_labeler.h
pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp
pkg/trunk/world_models/costmap_2d/src/basic_observation_buffer.cc
Modified: pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -105,7 +105,7 @@
string output_topic_ ; // Topic name for publishing our SensorKinematics metapacket
SensorKinematicsGrabber() : ros::node("sensor_kinematics_grabber"),
- dcam_sync_(this, &SensorKinematicsGrabber::dcamCallback, ros::Duration(0.05), &SensorKinematicsGrabber::dcamCallbackTimeout)
+ dcam_sync_(this, &SensorKinematicsGrabber::dcamCallback, ros::Duration().fromSec(0.05), &SensorKinematicsGrabber::dcamCallbackTimeout)
{
param("~subscribe_color", subscribe_color_, false);
param("~output_topic", output_topic_, string("sensor_kinematics"));
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 23:11:03 UTC (rev 7736)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -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) ; // Transform using the latest transform
+ cmd.header.stamp = ros::Time() ; // 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 23:11:03 UTC (rev 7736)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -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;
+ point.stamp_ = ros::Time();
point.frame_id_ = head_track_point_.header.frame_id;
std::string pan_parent;
- TF.getParent("head_pan_link", 0, pan_parent);
+ TF.getParent("head_pan_link", ros::Time(), 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;//get the latest transform
+ point.stamp_ = ros::Time();//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),frame);
+ TF.lookupTransform(point.frame_id_,"head_pan_link",ros::Time(),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 23:11:03 UTC (rev 7736)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -304,7 +304,7 @@
try
{
- TF.lookupTransform(point.frame_id_,"head_pan",ros::Time(0),frame);
+ TF.lookupTransform(point.frame_id_,"head_pan",ros::Time(),frame);
}
catch(tf::TransformException& ex)
{
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 23:11:03 UTC (rev 7736)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -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(10000000));
+ TF.setExtrapolationLimit(ros::Duration().fromNSec(10000000));
}
CartesianPositionControllerNode::~CartesianPositionControllerNode()
Modified: pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp
===================================================================
--- pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -287,7 +287,7 @@
"mono", "uint16",
stcam->stIm->imDisp );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish("~disparity", img_);
stereo_info_.has_disparity = true;
@@ -297,7 +297,7 @@
if (do_calc_points_)
{
- cloud_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ cloud_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
cloud_.header.frame_id = "stereo";
cloud_.pts.resize(stcam->stIm->numPts);
cloud_.chan.resize(1);
@@ -323,7 +323,7 @@
publish("~cloud", cloud_);
}
- stereo_info_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ stereo_info_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
stereo_info_.height = stcam->stIm->imHeight;
stereo_info_.width = stcam->stIm->imWidth;
@@ -360,7 +360,7 @@
"mono", "byte",
img_data->imRaw );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_raw"), img_);
cam_info_.has_image = true;
} else {
@@ -373,7 +373,7 @@
img_data->imHeight, img_data->imWidth, 1,
"mono", "byte",
img_data->im );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image"), img_);
cam_info_.has_image = true;
} else {
@@ -387,7 +387,7 @@
"rgba", "byte",
img_data->imColor );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_color"), img_);
cam_info_.has_image_color = true;
} else {
@@ -400,7 +400,7 @@
img_data->imHeight, img_data->imWidth, 1,
"mono", "byte",
img_data->imRect );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_rect"), img_);
cam_info_.has_image_rect = true;
} else {
@@ -413,7 +413,7 @@
img_data->imHeight, img_data->imWidth, 3,
"rgb", "byte",
img_data->imRectColor );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_rect_color"), img_);
cam_info_.has_image_rect_color = true;
} else {
@@ -426,14 +426,14 @@
img_data->imHeight, img_data->imWidth, 4,
"rgba", "byte",
img_data->imRectColor );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_rect_color"), img_);
cam_info_.has_image_rect_color = true;
} else {
cam_info_.has_image_rect_color = false;
}
- cam_info_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ cam_info_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
cam_info_.height = img_data->imHeight;
cam_info_.width = img_data->imWidth;
Modified: pkg/trunk/drivers/imu/imu_node/imu_node.cc
===================================================================
--- pkg/trunk/drivers/imu/imu_node/imu_node.cc 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/drivers/imu/imu_node/imu_node.cc 2008-12-07 00:40:54 UTC (rev 7737)
@@ -225,7 +225,7 @@
tf::PoseTFToMsg(pose, reading.pos);
- reading.header.stamp = ros::Time(time);
+ reading.header.stamp = ros::Time().fromNSec(time);
reading.header.frame_id = frameid_;
publish("imu_data", reading);
Modified: pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp
===================================================================
--- pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -307,7 +307,7 @@
scan_msg_.range_max = scan_.config.max_range;
scan_msg_.ranges = scan_.ranges;
scan_msg_.intensities = scan_.intensities;
- scan_msg_.header.stamp = ros::Time((uint64_t)scan_.system_time_stamp);
+ scan_msg_.header.stamp = ros::Time().fromNSec((uint64_t)scan_.system_time_stamp);
scan_msg_.header.frame_id = frameid_;
publish("scan", scan_msg_);
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -149,7 +149,7 @@
std_msgs::PoseStamped pose_msg ;
- pose_msg.header.stamp = ros::Time(0.0) ;
+ pose_msg.header.stamp = ros::Time() ;
pose_msg.header.frame_id = frame_id_ ;
tf::PointTFToMsg(pose_result.getOrigin(), pose_msg.pose.position) ;
Modified: pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation.cpp
===================================================================
--- pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -288,7 +288,7 @@
{
// pose
Stamped<Transform> tmp;
- transformer_.lookupTransform("base_footprint","odom", 0.0, tmp);
+ transformer_.lookupTransform("base_footprint","odom", ros::Time(), tmp);
PoseTFToMsg(tmp, estimate.pose);
// header
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 23:11:03 UTC (rev 7736)
+++ pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -296,7 +296,7 @@
// broadcast most recent estimate to TransformArray
Stamped<Transform> tmp;
- my_filter_.getEstimate(0, tmp);
+ my_filter_.getEstimate(ros::Time(), 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 23:11:03 UTC (rev 7736)
+++ pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -68,7 +68,7 @@
virtual void processData() = 0;
virtual bool loadData(std::string filename) {
- if (!mLp.open(filename, ros::Time(0))) return false;
+ if (!mLp.open(filename, ros::Time())) return false;
mLp.addHandler<OctreeLearningMsg>(std::string("grasp_learning_bus"),
©Msg<OctreeLearningMsg>, (void*)this, true);
mNewMsg = false;
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -21,7 +21,7 @@
tf::Stamped<tf::Pose> robotPose, globalPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time((uint64_t)0ULL);
+ robotPose.stamp_ = ros::Time();
try {
this->tf.transformPose("map", robotPose, globalPose);
} catch(tf::LookupException& ex) {
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -221,7 +221,7 @@
tf::Stamped<tf::Pose> robotPose, globalPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time((uint64_t)0ULL);
+ robotPose.stamp_ = ros::Time();
try{
tf_.transformPose("map", robotPose, globalPose);
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -264,7 +264,7 @@
tf::Stamped<tf::Pose> robotPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time((uint64_t)0ULL);
+ robotPose.stamp_ = ros::Time();
try{
tf_.transformPose("map", robotPose, global_pose_);
@@ -302,7 +302,7 @@
qt.setEulerZYX(goalMsg.goal.th, 0, 0);
goalPose.setData(btTransform(qt, btVector3(goalMsg.goal.x, goalMsg.goal.y, 0)));
goalPose.frame_id_ = goalMsg.header.frame_id;
- goalPose.stamp_ = ros::Time((uint64_t)0ULL);
+ goalPose.stamp_ = ros::Time();
try{
tf_.transformPose("map", goalPose, transformedGoalPose);
@@ -382,8 +382,8 @@
try
{
- tf::Stamped<btVector3> v_in(btVector3(odomMsg_.vel.x, odomMsg_.vel.y, 0), ros::Time((uint64_t)0ULL), odomMsg_.header.frame_id), v_out;
- tf_.transformVector("base_link", ros::Time((uint64_t)0ULL), v_in, odomMsg_.header.frame_id, v_out);
+ tf::Stamped<btVector3> v_in(btVector3(odomMsg_.vel.x, odomMsg_.vel.y, 0), ros::Time(), odomMsg_.header.frame_id), v_out;
+ tf_.transformVector("base_link", ros::Time(), v_in, odomMsg_.header.frame_id, v_out);
base_odom_.vel.x = v_in.x();
base_odom_.vel.y = v_in.y();
base_odom_.vel.th = odomMsg_.vel.th;
@@ -823,7 +823,8 @@
*/
void MoveBase::mapUpdateLoop()
{
- ros::Duration *d = new ros::Duration(1.0/map_update_frequency_);
+ ros::Duration *d = new ros::Duration();
+ d->fromSec(1.0/map_update_frequency_);
while (active_){
//Avoids laser race conditions.
Modified: pkg/trunk/highlevel/highlevel_controllers/src/VelocityControllers.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/VelocityControllers.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/highlevel/highlevel_controllers/src/VelocityControllers.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -30,7 +30,7 @@
btQuaternion qt(currentVel.vw, 0, 0);
robot_vel.setData(btTransform(qt, btVector3(currentVel.vx, currentVel.vy, 0)));
robot_vel.frame_id_ = "base_link";
- robot_vel.stamp_ = ros::Time((uint64_t)0ULL);
+ robot_vel.stamp_ = ros::Time();
//do we need to resize our map?
double origin_x, origin_y;
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2008-12-07 00:40:54 UTC (rev 7737)
@@ -749,7 +749,7 @@
{
tf::Stamped<tf::Pose> ident (btTransform(btQuaternion(0,0,0),
btVector3(0,0,0)),
- ros::Time((uint64_t)0ull), laserMsg.header.frame_id);
+ ros::Time(), laserMsg.header.frame_id);
tf::Stamped<btTransform> laser_pose;
try
{
@@ -792,7 +792,7 @@
laser_scans.pop_front();
- double timestamp = scan.header.stamp.to_double();
+ double timestamp = scan.header.stamp.toSec();
//printf("I: %.6f %.3f %.3f %.3f\n",
//timestamp, x, y, yaw);
@@ -875,7 +875,7 @@
pdata.vel.pa = this->odomMsg.vel.th;
pdata.stall = this->odomMsg.stall;
- double timestamp = this->odomMsg.header.stamp.to_double();
+ double timestamp = this->odomMsg.header.stamp.toSec();
this->Driver::Publish(this->position2d_addr,
PLAYER_MSGTYPE_DATA,
Modified: pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
===================================================================
--- pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -431,7 +431,7 @@
{
try
{
- tf::Stamped<tf::Pose> robot_pose(btTransform(btQuaternion(0,0,0), btVector3(0,0,0)), ros::Time((uint64_t)0ULL), "base_link");
+ tf::Stamped<tf::Pose> robot_pose(btTransform(btQuaternion(0,0,0), btVector3(0,0,0)), ros::Time(), "base_link");
tf::Stamped<tf::Pose> map_pose;
tf_client_->transformPose("map", robot_pose, map_pose);
Modified: pkg/trunk/nav/nav_view_sdl/nav_view.cpp
===================================================================
--- pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -355,7 +355,7 @@
tf::Stamped<tf::Pose> robotPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time(0);
+ robotPose.stamp_ = ros::Time();
tf::Stamped<tf::Pose> mapPose ;
tf.transformPose("map", robotPose, mapPose );
Modified: pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -57,7 +57,7 @@
/// not urgent for a robot like the PR2, where odometry is being
/// published several times faster than laser scans.
tf_ = new tf::TransformListener(*node_, true, 10000000000ULL);
- tf_->setExtrapolationLimit((int64_t) 200000000ULL );
+ tf_->setExtrapolationLimit( ros::Duration().fromSec(0.2));
ROS_ASSERT(tf_);
gsp_laser_ = NULL;
Modified: pkg/trunk/nav/slam_gmapping/src/tftest.cpp
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/tftest.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/slam_gmapping/src/tftest.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -10,7 +10,7 @@
node_ = new ros::node("test");
tf_ = new tf::TransformListener(*node_, true,
10000000000ULL);
- tf_->setExtrapolationLimit( ros::Duration((int64_t)200000000ULL));
+ tf_->setExtrapolationLimit( ros::Duration().fromSec(0.2));
node_->subscribe("base_scan", scan_, &Test::laser_cb, this, -1);
}
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-07 00:40:54 UTC (rev 7737)
@@ -279,7 +279,7 @@
ang_eps(DTOR(4.0)),
cycletime(0.1),
laser_maxrange(4.0),
- laser_buffer_time(3000000000LL),
+ laser_buffer_time(ros::Duration().fromSec(3)),
lookahead_maxdist(2.0),
lookahead_distweight(5.0),
tvmin(0.2),
@@ -571,7 +571,7 @@
tf::Stamped<tf::Pose> robotPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time((uint64_t)0ULL); // request most recent pose
+ robotPose.stamp_ = ros::Time(); // request most recent pose
//robotPose.time = laserMsg.header.stamp.sec * (uint64_t)1000000000ULL +
// laserMsg.header.stamp.nsec; ///HACKE FIXME we should be able to get time somewhere else
try
Modified: pkg/trunk/trajectory_rollout/src/governor_node.cpp
===================================================================
--- pkg/trunk/trajectory_rollout/src/governor_node.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/trajectory_rollout/src/governor_node.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -48,7 +48,7 @@
{
robot_vel_.setIdentity();
robot_vel_.frame_id_ = "base_link";
- robot_vel_.stamp_ = ros::Time(uint64_t(0ULL));
+ robot_vel_.stamp_ = ros::Time();
//so we can draw the local path
advertise<std_msgs::Polyline2D>("local_path", 10);
@@ -68,7 +68,7 @@
btQuaternion qt(odom_msg_.vel.th, 0, 0);
robot_vel_.setData(btTransform(qt, btVector3(odom_msg_.vel.x, odom_msg_.vel.y, 0)));
robot_vel_.frame_id_ = "base_link";
- robot_vel_.stamp_ = ros::Time((uint64_t)0ULL);
+ robot_vel_.stamp_ = ros::Time();
//give robot_vel_ back
vel_lock.unlock();
@@ -99,7 +99,7 @@
tf::Stamped<tf::Pose> robot_pose, global_pose;
robot_pose.setIdentity();
robot_pose.frame_id_ = "base_link";
- robot_pose.stamp_ = ros::Time((uint64_t)0ULL);
+ robot_pose.stamp_ = ros::Time();
try
{
Modified: pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
===================================================================
--- pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -125,7 +125,7 @@
for (int i = 1; i < argc; i++)
files.push_back(argv[i]);
- player.open(files, ros::Time(0));
+ player.open(files, ros::Time());
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 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/logsetta/imu/imu_extract.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -57,7 +57,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0));
+ player.open(std::string(argv[1]), ros::Time());
int count;
Modified: pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -57,7 +57,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0));
+ player.open(std::string(argv[1]), ros::Time());
int count;
Modified: pkg/trunk/util/logsetta/odom/odom_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/odom/odom_extract.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/logsetta/odom/odom_extract.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -62,7 +62,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0));
+ player.open(std::string(argv[1]), ros::Time());
int count;
Modified: pkg/trunk/util/tf/include/tf/time_cache.h
===================================================================
--- pkg/trunk/util/tf/include/tf/time_cache.h 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/tf/include/tf/time_cache.h 2008-12-07 00:40:54 UTC (rev 7737)
@@ -69,8 +69,8 @@
static const int64_t DEFAULT_MAX_EXTRAPOLATION_TIME = 0LL; //!< default max extrapolation of 0 nanoseconds \todo remove and make not optional??
- TimeCache(bool interpolating = true, ros::Duration max_storage_time = ros::Duration(DEFAULT_MAX_STORAGE_TIME),
- ros::Duration max_extrapolation_time = ros::Duration(DEFAULT_MAX_EXTRAPOLATION_TIME)):
+ TimeCache(bool interpolating = true, ros::Duration max_storage_time = ros::Duration().fromNSec(DEFAULT_MAX_STORAGE_TIME),
+ ros::Duration max_extrapolation_time = ros::Duration().fromNSec(DEFAULT_MAX_EXTRAPOLATION_TIME)):
interpolating_(interpolating),
max_storage_time_(max_storage_time),
max_extrapolation_time_(max_extrapolation_time)
Modified: pkg/trunk/util/tf/include/tf/transform_datatypes.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_datatypes.h 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/tf/include/tf/transform_datatypes.h 2008-12-07 00:40:54 UTC (rev 7737)
@@ -66,7 +66,7 @@
std::string frame_id_;
std::string parent_id_; ///only used for transform
- Stamped() :stamp_ ((uint64_t)0ULL),frame_id_ ("NO_ID"), parent_id_("NOT A TRANSFORM"){}; //Default constructor used only for preallocation
+ Stamped() :frame_id_ ("NO_ID"), parent_id_("NOT A TRANSFORM"){}; //Default constructor used only for preallocation
Stamped(const T& input, const ros::Time& timestamp, const std::string & frame_id, const std::string & parent_id = "NOT A TRANSFORM"):
T (input), stamp_ ( timestamp ), frame_id_ (frame_id), parent_id_(parent_id){ };
@@ -88,7 +88,7 @@
/** \brief convert QuaternionStamped msg to Stamped<Quaternion> */
static inline void QuaternionStampedMsgToTF(const std_msgs::QuaternionStamped & msg, Stamped<Quaternion>& bt)
-{QuaternionMsgToTF(msg.quaternion, bt); bt.stamp_ = msg.header.stamp.to_ull(); bt.frame_id_ = msg.header.frame_id;};
+{QuaternionMsgToTF(msg.quaternion, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Quaternion> to QuaternionStamped msg*/
static inline void QuaternionStampedTFToMsg(const Stamped<Quaternion>& bt, std_msgs::QuaternionStamped & msg)
{QuaternionTFToMsg(bt, msg.quaternion); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
@@ -100,7 +100,7 @@
/** \brief convert Vector3Stamped msg to Stamped<Vector3> */
static inline void Vector3StampedMsgToTF(const std_msgs::Vector3Stamped & msg, Stamped<Vector3>& bt)
-{Vector3MsgToTF(msg.vector, bt); bt.stamp_ = msg.header.stamp.to_ull(); bt.frame_id_ = msg.header.frame_id;};
+{Vector3MsgToTF(msg.vector, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Vector3> to Vector3Stamped msg*/
static inline void Vector3StampedTFToMsg(const Stamped<Vector3>& bt, std_msgs::Vector3Stamped & msg)
{Vector3TFToMsg(bt, msg.vector); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
@@ -113,7 +113,7 @@
/** \brief convert PointStamped msg to Stamped<Point> */
static inline void PointStampedMsgToTF(const std_msgs::PointStamped & msg, Stamped<Point>& bt)
-{PointMsgToTF(msg.point, bt); bt.stamp_ = msg.header.stamp.to_ull(); bt.frame_id_ = msg.header.frame_id;};
+{PointMsgToTF(msg.point, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Point> to PointStamped msg*/
static inline void PointStampedTFToMsg(const Stamped<Point>& bt, std_msgs::PointStamped & msg)
{PointTFToMsg(bt, msg.point); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
@@ -128,7 +128,7 @@
/** \brief convert TransformStamped msg to Stamped<Transform> */
static inline void TransformStampedMsgToTF(const std_msgs::TransformStamped & msg, Stamped<Transform>& bt)
-{TransformMsgToTF(msg.transform, bt); bt.stamp_ = msg.header.stamp.to_ull(); bt.frame_id_ = msg.header.frame_id; bt.parent_id_ = msg.parent_id;};
+{TransformMsgToTF(msg.transform, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id; bt.parent_id_ = msg.parent_id;};
/** \brief convert Stamped<Transform> to TransformStamped msg*/
static inline void TransformStampedTFToMsg(const Stamped<Transform>& bt, std_msgs::TransformStamped & msg)
{TransformTFToMsg(bt, msg.transform); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_; msg.parent_id = bt.parent_id_;};
@@ -142,7 +142,7 @@
/** \brief convert PoseStamped msg to Stamped<Pose> */
static inline void PoseStampedMsgToTF(const std_msgs::PoseStamped & msg, Stamped<Pose>& bt)
-{PoseMsgToTF(msg.pose, bt); bt.stamp_ = msg.header.stamp.to_ull(); bt.frame_id_ = msg.header.frame_id;};
+{PoseMsgToTF(msg.pose, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Pose> to PoseStamped msg*/
static inline void PoseStampedTFToMsg(const Stamped<Pose>& bt, std_msgs::PoseStamped & msg)
{PoseTFToMsg(bt, msg.pose); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
Modified: pkg/trunk/util/tf/include/tf/transform_listener.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-07 00:40:54 UTC (rev 7737)
@@ -63,7 +63,7 @@
bool interpolating = true,
int64_t max_cache_time = DEFAULT_CACHE_TIME):
Transformer(interpolating,
- max_cache_time),
+ ros::Duration().fromNSec(max_cache_time)),
node_(rosnode)
{
// printf("Constructed rosTF\n");
@@ -154,7 +154,7 @@
// setWithEulers(tfArrayIn.eulers[i].header.frame_id, tfArrayIn.eulers[i].parent, tfArrayIn.eulers[i].x, tfArrayIn.eulers[i].y, tfArrayIn.eulers[i].z, tfArrayIn.eulers[i].yaw, tfArrayIn.eulers[i].pitch, tfArrayIn.eulers[i].roll, tfArrayIn.eulers[i].header.stamp.sec * 1000000000ULL + tfArrayIn.eulers[i].header.stamp.nsec);
setTransform(Stamped<Transform>(Transform(Quaternion(tfArrayIn.eulers[i].yaw, tfArrayIn.eulers[i].pitch, tfArrayIn.eulers[i].roll),
Vector3(tfArrayIn.eulers[i].x, tfArrayIn.eulers[i].y, tfArrayIn.eulers[i].z)),
- tfArrayIn.eulers[i].header.stamp.sec * (uint64_t)1000000000ULL + tfArrayIn.eulers[i].header.stamp.nsec,
+ tfArrayIn.eulers[i].header.stamp,
tfArrayIn.eulers[i].header.frame_id , tfArrayIn.eulers[i].parent) );
}
catch (tf::TransformException &ex)
@@ -174,9 +174,9 @@
try{
// setWithQuaternion(tfArrayIn.quaternions[i].header.frame_id, tfArrayIn.quaternions[i].parent, tfArrayIn.quaternions[i].xt, tfArrayIn.quaternions[i].yt, tfArrayIn.quaternions[i].zt, tfArrayIn.quaternions[i].xr, tfArrayIn.quaternions[i].yr, tfArrayIn.quaternions[i].zr, tfArrayIn.quaternions[i].w, tfArrayIn.quaternions[i].header.stamp.sec * 1000000000ULL + tfArrayIn.quaternions[i].header.stamp.nsec);
setTransform(Stamped<Transform>(Transform(Quaternion(tfArrayIn.quaternions[i].xr, tfArrayIn.quaternions[i].yr, tfArrayIn.quaternions[i].zr, tfArrayIn.quaternions[i].w),
- Vector3(tfArrayIn.quaternions[i].xt, tfArrayIn.quaternions[i].yt, tfArrayIn.quaternions[i].zt)),
- tfArrayIn.quaternions[i].header.stamp.sec * (uint64_t)1000000000ULL + tfArrayIn.quaternions[i].header.stamp.nsec,
- tfArrayIn.quaternions[i].header.frame_id , tfArrayIn.quaternions[i].parent)
+ Vector3(tfArrayIn.quaternions[i].xt, tfArrayIn.quaternions[i].yt, tfArrayIn.quaternions[i].zt)),
+ tfArrayIn.quaternions[i].header.stamp,
+ tfArrayIn.quaternions[i].header.frame_id , tfArrayIn.quaternions[i].parent)
);
}
catch (tf::TransformException &ex)
Modified: pkg/trunk/util/tf/src/cache.cpp
===================================================================
--- pkg/trunk/util/tf/src/cache.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/tf/src/cache.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -88,7 +88,7 @@
}
//If time == 0 return the latest
- if (target_time == ros::Time(0))
+ if (target_time == ros::Time())
{
one = storage_.front();
mode = ONE_VALUE;
Modified: pkg/trunk/util/tf/src/tf.cpp
===================================================================
--- pkg/trunk/util/tf/src/tf.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/tf/src/tf.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -36,9 +36,9 @@
Transformer::Transformer(bool interpolating,
ros::Duration cache_time):
cache_time(cache_time),
- interpolating (interpolating),
- max_extrapolation_distance_(DEFAULT_MAX_EXTRAPOLATION_DISTANCE)
+ interpolating (interpolating)
{
+ max_extrapolation_distance_.fromNSec(DEFAULT_MAX_EXTRAPOLATION_DISTANCE);
frameIDs_["NO_PARENT"] = 0;
frames_.push_back(NULL);// new TimeCache(interpolating, cache_time, max_extrapolation_distance));//unused but needed for iteration over all elements
frameIDs_reverse.push_back("NO_PARENT");
@@ -85,7 +85,7 @@
int retval = NO_ERROR;
ros::Time temp_time;
//If getting the latest get the latest common time
- if (time == ros::Time(0ULL))
+ if (time == ros::Time())
retval = getLatestCommonTime(target_frame, source_frame, temp_time);
else
temp_time = time;
@@ -121,13 +121,13 @@
int retval = NO_ERROR;
ros::Time temp_target_time, temp_source_time;
//If getting the latest get the latest common time
- if (target_time == ros::Time(0ULL))
+ if (target_time == ros::Time())
retval = getLatestCommonTime(target_frame, fixed_frame, temp_target_time);
else
temp_target_time = target_time;
//If getting the latest get the latest common time
- if (source_time == ros::Time(0ULL) && retval == NO_ERROR)
+ if (source_time == ros::Time() && retval == NO_ERROR)
retval = getLatestCommonTime(fixed_frame, source_frame, temp_source_time);
else
temp_source_time = source_time;
@@ -198,7 +198,7 @@
}
}
- if (time != ros::Time((uint64_t)0ULL) && test_extrapolation(time, t_list, NULL))
+ if (time != ros::Time() && test_extrapolation(time, t_list, NULL))
{
return false;
}
@@ -222,7 +222,7 @@
return false;
}
- if (target_time != ros::Time((uint64_t)0ULL) && test_extrapolation(target_time, t_list, NULL))
+ if (target_time != ros::Time() && test_extrapolation(target_time, t_list, NULL))
return false;
@@ -241,7 +241,7 @@
return false;
}
- if (source_time != ros::Time((uint64_t)0ULL) && test_extrapolation(target_time, t_list, NULL))
+ if (source_time != ros::Time() && test_extrapolation(target_time, t_list, NULL))
return false;
return true;
@@ -269,7 +269,7 @@
time = ros::Time::now();///\todo hack fixme
int retval;
TransformLists lists;
- retval = lookupLists(lookupFrameNumber(dest), ros::Time(0ULL), lookupFrameNumber(source), lists, NULL);
+ retval = lookupLists(lookupFrameNumber(dest), ros::Time(), lookupFrameNumber(source), lists, NULL);
if (retval == NO_ERROR)
{
for (unsigned int i = 0; i < lists.inverseTransforms.size(); i++)
@@ -650,7 +650,7 @@
for (unsigned int counter = 1; counter < frames_.size(); counter ++)
{
unsigned int parent_id;
- if( getFrame(counter)->getData((uint64_t)0ULL, temp))
+ if( getFrame(counter)->getData(ros::Time(), temp))
parent_id = temp.parent_frame_id;
else
{
@@ -673,14 +673,6 @@
// for (std::vector< TimeCache*>::iterator it = frames_.begin(); it != frames_.end(); ++it)
for (unsigned int counter = 1; counter < frames_.size(); counter ++)
{
- ///\todo why did I do this and then catch??
- /* try{
- getFrame(counter)->getData((uint64_t)0ULL, temp);
- }
- catch (tf::LookupException& ex)
- {
- }
- */
vec.push_back(frameIDs_reverse[counter]);
}
frame_mutex_.unlock();
Modified: pkg/trunk/util/tf/test/testBroadcaster.cpp
===================================================================
--- pkg/trunk/util/tf/test/testBroadcaster.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/tf/test/testBroadcaster.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -49,7 +49,7 @@
<< 0 << 0 << 1 << 3
<< 0 << 0 << 0 << 1;
- broadcaster.sendTransform(btTransform(btQuaternion(0,0,0), btVector3(1,2,3)), (uint64_t)1000000000ULL, "frame1", "frame2");
+ broadcaster.sendTransform(btTransform(btQuaternion(0,0,0), btVector3(1,2,3)), ros::Time().fromSec(1), "frame1", "frame2");
/* pTFServer->sendEuler("count","count++",1,1,1,1,1,1,ros::Time(100000,100000));
pTFServer->sendInverseEuler("count","count++",1,1,1,1,1,1,ros::Time(100000,100000));
pTFServer->sendDH("count","count++",1,1,1,1,ros::Time(100000,100000));
Modified: pkg/trunk/vision/calib_converter/src/calib_converter.cpp
===================================================================
--- pkg/trunk/vision/calib_converter/src/calib_converter.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/vision/calib_converter/src/calib_converter.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -81,7 +81,7 @@
// -- Load the messages.
- lp.open(fullname, ros::Time(0));
+ lp.open(fullname, ros::Time());
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/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -60,7 +60,7 @@
, height_( 0.0f )
, load_timer_( 2.0f )
, new_metadata_( false )
-, last_loaded_map_time_( 0.0 )
+, last_loaded_map_time_( ros::Time() )
, service_property_( NULL )
, resolution_property_( NULL )
, width_property_( NULL )
@@ -324,9 +324,9 @@
void MapDisplay::transformMap()
{
- tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time((uint64_t)0ULL), "map" );
+ tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time(), "map" );
- if ( tf_->canTransform(fixed_frame_, "map", ros::Time((uint64_t)0ULL)))
+ if ( tf_->canTransform(fixed_frame_, "map", ros::Time()))
{
try
{
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/particle_cloud_2d_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/particle_cloud_2d_display.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/particle_cloud_2d_display.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -205,9 +205,9 @@
clear();
tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0.0f, 0.0f, 0.0f ), btVector3( 0.0f, 0.0f, 0.0f ) ),
- ros::Time((uint64_t)0ULL), "map" );
+ ros::Time(), "map" );
- if (tf_->canTransform(fixed_frame_, "map", ros::Time((uint64_t)0ULL)))
+ if (tf_->canTransform(fixed_frame_, "map", ros::Time()))
{
try
{
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/planning_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/planning_display.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/planning_display.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -254,9 +254,9 @@
void PlanningDisplay::calculateRobotPosition()
{
- tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time((uint64_t)0ULL), displaying_kinematic_path_message_.frame_id );
+ tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time(), displaying_kinematic_path_message_.frame_id );
- if (tf_->canTransform(target_frame_, displaying_kinematic_path_message_.frame_id, ros::Time((uint64_t)0ULL)))
+ if (tf_->canTransform(target_frame_, displaying_kinematic_path_message_.frame_id, ros::Time()))
{
try
{
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -276,9 +276,9 @@
clear();
tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0.0f, 0.0f, 0.0f ), btVector3( 0.0f, 0.0f, z_position_ ) ),
- ros::Time((uint64_t)0ULL), "map" );
+ ros::Time(), "map" );
- if (tf_->canTransform(fixed_frame_, "map", ros::Time((uint64_t)0ULL)))
+ if (tf_->canTransform(fixed_frame_, "map", ros::Time()))
{
try
{
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/tf_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/tf_display.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/tf_display.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -287,9 +287,9 @@
void TFDisplay::updateFrame(FrameInfo* frame)
{
- tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time((uint64_t)0ULL), frame->name_ );
+ tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time(), frame->name_ );
- if (tf_->canTransform(fixed_frame_, frame->name_, ros::Time((uint64_t)0ULL)))
+ if (tf_->canTransform(fixed_frame_, frame->name_, ros::Time()))
{
try
{
@@ -321,7 +321,7 @@
std::string old_parent = frame->parent_;
frame->parent_.clear();
- bool has_parent = tf_->getParent( frame->name_, ros::Time((uint64_t)0ULL), frame->parent_ );
+ bool has_parent = tf_->getParent( frame->name_, ros::Time(), frame->parent_ );
if ( has_parent )
{
if ( !frame->tree_property_ || old_parent != frame->parent_ )
@@ -342,9 +342,9 @@
if ( show_arrows_ )
{
- tf::Stamped<tf::Pose> parent_pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time((uint64_t)0ULL), frame->parent_ );
+ tf::Stamped<tf::Pose> parent_pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time(), frame->parent_ );
- if (tf_->canTransform(fixed_frame_, frame->parent_, ros::Time((uint64_t)0ULL)))
+ if (tf_->canTransform(fixed_frame_, frame->parent_, ros::Time()))
{
try
{
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -621,9 +621,9 @@
continue;
}
- tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time((uint64_t)0ULL), name );
+ tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0, 0, 0 ), btVector3( 0, 0, 0 ) ), ros::Time(), name );
- if (tf->canTransform(target_frame, name, ros::Time((uint64_t)0ULL)))
+ if (tf->canTransform(target_frame, name, ros::Time()))
{
try
{
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/tools/pose_tool.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/tools/pose_tool.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/tools/pose_tool.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -144,8 +144,8 @@
ogreToRobot( robot_pos );
const std::string& fixed_frame = manager_->getFixedFrame();
- tf::Stamped<tf::Point> cur_pos_transformed( tf::Point(cur_pos.x, cur_pos.y, cur_pos.z), ros::Time((uint64_t)0ULL), fixed_frame );
- tf::Stamped<tf::Point> robot_pos_transformed( tf::Point(robot_pos.x, robot_pos.y, robot_pos.z), ros::Time((uint64_t)0ULL), fixed_frame );
+ tf::Stamped<tf::Point> cur_pos_transformed( tf::Point(cur_pos.x, cur_pos.y, cur_pos.z), ros::Time(), fixed_frame );
+ tf::Stamped<tf::Point> robot_pos_transformed( tf::Point(robot_pos.x, robot_pos.y, robot_pos.z), ros::Time(), fixed_frame );
tf::TransformListener* tf = manager_->getTFClient();
try
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 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -69,8 +69,8 @@
, vis_panel_( panel )
, needs_reset_( false )
, new_ros_time_( false )
-, wall_clock_begin_( 0 )
-, ros_time_begin_( 0 )
+, wall_clock_begin_( ros::Time() )
+, ros_time_begin_( ros::Time() )
{
initializeCommon();
registerFactories( this );
@@ -234,8 +234,8 @@
resetDisplays();
tf_->clear();
- ros_time_begin_ = ros::Time( 0 );
- wall_clock_begin_ = ros::Time( 0 );
+ ros_time_begin_ = ros::Time();
+ wall_clock_begin_ = ros::Time();
}
static float time_update_timer = 0.0f;
@@ -659,9 +659,9 @@
void VisualizationManager::updateRelativeNode()
{
tf::Stamped<tf::Pose> pose( btTransform( btQuaternion( 0.0f, 0.0f, 0.0f ), btVector3( 0.0f, 0.0f, 0.0f ) ),
- ros::Time((uint64_t)0ULL), target_frame_ );
+ ros::Time(), target_frame_ );
- if (tf_->canTransform(fixed_frame_, target_frame_, ros::Time((uint64_t)0ULL)))
+ if (tf_->canTransform(fixed_frame_, target_frame_, ros::Time()))
{
try
{
@@ -709,7 +709,7 @@
void VisualizationManager::incomingROSTime()
{
- static ros::Time last_time = ros::Time((uint64_t)0ULL);
+ static ros::Time last_time = ros::Time();
if ( time_message_.rostime < last_time )
{
Modified: pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -21,7 +21,7 @@
{
std_msgs::VisualizationMarker marker;
marker.header.frame_id = "map";
- marker.header.stamp = ros::Time((uint64_t)0ULL);
+ marker.header.stamp = ros::Time();
marker.id = i;
marker.type = std_msgs::VisualizationMarker::CUBE;
marker.action = 0;
@@ -43,7 +43,7 @@
std_msgs::VisualizationMarker line_marker;
line_marker.header.frame_id = "map";
- line_marker.header.stamp = ros::Time((uint64_t)0ULL);
+ line_marker.header.stamp = ros::Time();
line_marker.id = 1000;
line_marker.type = std_msgs::VisualizationMarker::LINE_STRIP;
line_marker.action = 0;
Modified: pkg/trunk/visualization/scene_labeler/include/scene_labeler.h
===================================================================
--- pkg/trunk/visualization/scene_labeler/include/scene_labeler.h 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/scene_labeler/include/scene_labeler.h 2008-12-07 00:40:54 UTC (rev 7737)
@@ -11,7 +11,6 @@
#include <ros/node.h>
#include <std_msgs/Empty.h>
#include <std_msgs/VisualizationMarker.h>
-#include "logging/LogPlayer.h"
#include <rosTF/rosTF.h>
#include <newmat10/newmat.h>
#include <newmat10/newmatio.h>
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 23:11:03 UTC (rev 7736)
+++ pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -13,7 +13,7 @@
cout << "Loading messages... "; flush(cout);
- lp.open(file, ros::Time(0));
+ lp.open(file, ros::Time());
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/costmap_2d/src/basic_observation_buffer.cc
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/basic_observation_buffer.cc 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/world_models/costmap_2d/src/basic_observation_buffer.cc 2008-12-07 00:40:54 UTC (rev 7737)
@@ -32,7 +32,7 @@
try
{
// First we want the origin for the sensor
- tf::Stamped<btVector3> local_origin(btVector3(0, 0, 0), point_cloud.header.stamp.toNSec(), frame_id_);
+ tf::Stamped<btVector3> local_origin(btVector3(0, 0, 0), point_cloud.header.stamp, frame_id_);
tf_.transformPoint("map", local_origin, map_origin);
tf_.transformPointCloud("base_link", point_cloud, base_cloud);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|