|
From: <hsu...@us...> - 2008-09-18 16:30:04
|
Revision: 4450
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4450&view=rev
Author: hsujohnhsu
Date: 2008-09-18 23:30:14 +0000 (Thu, 18 Sep 2008)
Log Message:
-----------
renamed
FRAMEID_ROBOT --> base
FRAMEID_ODOM --> odom
FRAMEID_MAP --> map
FRAMEID_LASER --> base_laser
as stated in personalrobots ticket 323
https://prdev.willowgarage.com/trac/personalrobots/ticket/323
Modified Paths:
--------------
pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/fake_localization/fake_localization.cpp
pkg/trunk/nav/laser_pose_interpolator/laser_pose_interpolator.cpp
pkg/trunk/nav/nav_view/nav_view.cpp
pkg/trunk/nav/sbpl_2dnav/src/sbpl_2dnav.cpp
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/simulators/rosstage/rosstage.cc
Modified: pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp 2008-09-18 23:28:16 UTC (rev 4449)
+++ pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp 2008-09-18 23:30:14 UTC (rev 4450)
@@ -442,7 +442,7 @@
void BaseController::setOdomMessage(std_msgs::RobotBase2DOdom &odom_msg_)
{
- odom_msg_.header.frame_id = "FRAMEID_ODOM";
+ odom_msg_.header.frame_id = "odom";
odom_msg_.header.stamp.sec = (unsigned long)floor(robot_state_->hw_->current_time_);
odom_msg_.header.stamp.nsec = (unsigned long)floor( 1e9 * ( robot_state_->hw_->current_time_ - odom_msg_.header.stamp.sec) );
@@ -497,23 +497,12 @@
double x=0,y=0,yaw=0,vx,vy,vyaw;
this->getOdometry(x,y,yaw,vx,vy,vyaw);
this->tfs->sendInverseEuler(
- "FRAMEID_ODOM",
- "FRAMEID_ROBOT",
+ "odom",
+ "base",
x, y, 0,
yaw, 0, 0,
odom_msg_.header.stamp);
- /***************************************************************/
- /* */
- /* FRAMEID_ROBOT is the base frame */
- /* */
- /***************************************************************/
- this->tfs->sendInverseEuler(
- "FRAMEID_ROBOT",
- "base",
- 0, 0, 0, 0, 0, 0,
- odom_msg_.header.stamp);
-
}
odom_publish_counter_++;
@@ -577,7 +566,7 @@
// receive messages from 2dnav stack
node->subscribe("cmd_vel", baseVelMsg, &BaseControllerNode::CmdBaseVelReceived, this);
- // for publishing odometry frame transforms FRAMEID_ODOM
+ // for publishing odometry frame transforms odom
this->tfs = new rosTFServer(*node); //, true, 1 * 1000000000ULL, 0ULL);
return true;
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2008-09-18 23:28:16 UTC (rev 4449)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2008-09-18 23:30:14 UTC (rev 4450)
@@ -366,8 +366,8 @@
// publish new transform robot->map
- this->tf->sendEuler("FRAMEID_ROBOT",
- "FRAMEID_MAP",
+ this->tf->sendEuler("base",
+ "map",
pdata->pos.px,
pdata->pos.py,
0.0,
@@ -393,7 +393,7 @@
localizedOdomMsg.header.stamp.from_double(hdr->timestamp);
try
{
- localizedOdomMsg.header.frame_id = "FRAMEID_MAP";
+ localizedOdomMsg.header.frame_id = "map";
}
catch(...)
{
Modified: pkg/trunk/nav/fake_localization/fake_localization.cpp
===================================================================
--- pkg/trunk/nav/fake_localization/fake_localization.cpp 2008-09-18 23:28:16 UTC (rev 4449)
+++ pkg/trunk/nav/fake_localization/fake_localization.cpp 2008-09-18 23:30:14 UTC (rev 4450)
@@ -151,10 +151,10 @@
m_currentPos.pos.x += m_iniPos.x;
m_currentPos.pos.y += m_iniPos.y;
m_currentPos.pos.th = math_utils::normalize_angle(m_currentPos.pos.th + m_iniPos.th);
- m_currentPos.header.frame_id = "FRAMEID_MAP";
+ m_currentPos.header.frame_id = "map";
- m_tfServer->sendEuler("FRAMEID_ROBOT",
- "FRAMEID_MAP",
+ m_tfServer->sendEuler("base",
+ "map",
m_currentPos.pos.x,
m_currentPos.pos.y,
0.0,
Modified: pkg/trunk/nav/laser_pose_interpolator/laser_pose_interpolator.cpp
===================================================================
--- pkg/trunk/nav/laser_pose_interpolator/laser_pose_interpolator.cpp 2008-09-18 23:28:16 UTC (rev 4449)
+++ pkg/trunk/nav/laser_pose_interpolator/laser_pose_interpolator.cpp 2008-09-18 23:30:14 UTC (rev 4450)
@@ -30,36 +30,36 @@
robotPose.yaw = 0;
robotPose.time = laserMsg.header.stamp.sec * 1000000000ULL + laserMsg.header.stamp.nsec;
try {
- robotPose.frame = "FRAMEID_ROBOT";
+ robotPose.frame = "base";
} catch(libTF::TransformReference::LookupException& ex) {
- std::cerr << "LookupException in lookup(\"FRAMEID_ROBOT\"): " << ex.what() << "\n";
- std::cout << "LookupException in lookup(\"FRAMEID_ROBOT\"): " << ex.what() << "\n";
+ std::cerr << "LookupException in lookup(\"base\"): " << ex.what() << "\n";
+ std::cout << "LookupException in lookup(\"base\"): " << ex.what() << "\n";
return;
} catch(libTF::TransformReference::ExtrapolateException& ex) {
- std::cerr << "ExtrapolateException in lookup(\"FRAMEID_ROBOT\"): " << ex.what() << "\n";
- std::cout << "ExtrapolateException in lookup(\"FRAMEID_ROBOT\"): " << ex.what() << "\n";
+ std::cerr << "ExtrapolateException in lookup(\"base\"): " << ex.what() << "\n";
+ std::cout << "ExtrapolateException in lookup(\"base\"): " << ex.what() << "\n";
return;
} catch(libTF::TransformReference::ConnectivityException& ex) {
- std::cerr << "ConnectivityException in lookup(\"FRAMEID_ROBOT\"): " << ex.what() << "\n";
- std::cout << "ConnectivityException in lookup(\"FRAMEID_ROBOT\"): " << ex.what() << "\n";
+ std::cerr << "ConnectivityException in lookup(\"base\"): " << ex.what() << "\n";
+ std::cout << "ConnectivityException in lookup(\"base\"): " << ex.what() << "\n";
return;
}
try {
- global_pose = this->tf.transformPose2D("FRAMEID_ODOM", robotPose);
+ global_pose = this->tf.transformPose2D("odom", robotPose);
} catch(libTF::TransformReference::LookupException& ex) {
std::cerr << tf.viewFrames();
- std::cerr << "LookupException in transformPose2D(\"FRAMEID_ODOM\", robotPose): " << ex.what() << "\n";
- std::cout << "LookupException in transformPose2D(\"FRAMEID_ODOM\", robotPose): " << ex.what() << "\n";
+ std::cerr << "LookupException in transformPose2D(\"odom\", robotPose): " << ex.what() << "\n";
+ std::cout << "LookupException in transformPose2D(\"odom\", robotPose): " << ex.what() << "\n";
return;
} catch(libTF::TransformReference::ExtrapolateException& ex) {
- std::cerr << "ExtrapolateException in transformPose2D(\"FRAMEID_ODOM\", robotPose): " << ex.what() << "\n";
- std::cout << "ExtrapolateException in transformPose2D(\"FRAMEID_ODOM\", robotPose): " << ex.what() << "\n";
+ std::cerr << "ExtrapolateException in transformPose2D(\"odom\", robotPose): " << ex.what() << "\n";
+ std::cout << "ExtrapolateException in transformPose2D(\"odom\", robotPose): " << ex.what() << "\n";
return;
} catch(libTF::TransformReference::ConnectivityException& ex) {
- std::cerr << "ConnectivityException in transformPose2D(\"FRAMEID_ODOM\", robotPose): " << ex.what() << "\n";
- std::cout << "ConnectivityException in transformPose2D(\"FRAMEID_ODOM\", robotPose): " << ex.what() << "\n";
+ std::cerr << "ConnectivityException in transformPose2D(\"odom\", robotPose): " << ex.what() << "\n";
+ std::cout << "ConnectivityException in transformPose2D(\"odom\", robotPose): " << ex.what() << "\n";
return;
}
msg.scan = laserMsg;
Modified: pkg/trunk/nav/nav_view/nav_view.cpp
===================================================================
--- pkg/trunk/nav/nav_view/nav_view.cpp 2008-09-18 23:28:16 UTC (rev 4449)
+++ pkg/trunk/nav/nav_view/nav_view.cpp 2008-09-18 23:30:14 UTC (rev 4450)
@@ -351,10 +351,10 @@
robotPose.x = 0;
robotPose.y = 0;
robotPose.yaw = 0;
- robotPose.frame = "FRAMEID_ROBOT";
+ robotPose.frame = "base";
robotPose.time = 0;
- libTF::TFPose2D mapPose = tf.transformPose2D("FRAMEID_MAP", robotPose);
+ libTF::TFPose2D mapPose = tf.transformPose2D("map", robotPose);
glPushMatrix();
glTranslatef(mapPose.x, mapPose.y, 0);
Modified: pkg/trunk/nav/sbpl_2dnav/src/sbpl_2dnav.cpp
===================================================================
--- pkg/trunk/nav/sbpl_2dnav/src/sbpl_2dnav.cpp 2008-09-18 23:28:16 UTC (rev 4449)
+++ pkg/trunk/nav/sbpl_2dnav/src/sbpl_2dnav.cpp 2008-09-18 23:30:14 UTC (rev 4450)
@@ -273,13 +273,13 @@
robot_pose.x = 0;
robot_pose.y = 0;
robot_pose.yaw = 0;
- robot_pose.frame = "FRAMEID_ROBOT";
+ robot_pose.frame = "base";
robot_pose.time = 0; // request most recent pose
//robot_pose_.time = laserMsg.header.stamp.sec * 1000000000ULL +
// laserMsg.header.stamp.nsec; ///HACKE FIXME we should be able to get time somewhere else
try
{
- global_pose = tf_.transformPose2D("FRAMEID_MAP", robot_pose);
+ global_pose = tf_.transformPose2D("map", robot_pose);
}
catch(libTF::TransformReference::LookupException& ex)
{
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-09-18 23:28:16 UTC (rev 4449)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-09-18 23:30:14 UTC (rev 4450)
@@ -373,8 +373,8 @@
// Static robot->laser transform
double laser_x_offset;
param("laser_x_offset", laser_x_offset, 0.05);
- this->tf.setWithEulers("FRAMEID_LASER",
- "FRAMEID_ROBOT",
+ this->tf.setWithEulers("base_laser",
+ "base",
laser_x_offset, 0.0, 0.0, 0.0, 0.0, 0.0, 0);
advertise<std_msgs::Planner2DState>("state");
@@ -468,7 +468,7 @@
try
{
- global_cloud = this->tf.transformPointCloud("FRAMEID_MAP", local_cloud);
+ global_cloud = this->tf.transformPointCloud("map", local_cloud);
}
catch(libTF::TransformReference::LookupException& ex)
{
@@ -603,13 +603,13 @@
robotPose.x = 0;
robotPose.y = 0;
robotPose.yaw = 0;
- robotPose.frame = "FRAMEID_ROBOT";
+ robotPose.frame = "base";
robotPose.time = 0; // request most recent pose
//robotPose.time = laserMsg.header.stamp.sec * 1000000000ULL +
// laserMsg.header.stamp.nsec; ///HACKE FIXME we should be able to get time somewhere else
try
{
- global_pose = this->tf.transformPose2D("FRAMEID_MAP", robotPose);
+ global_pose = this->tf.transformPose2D("map", robotPose);
}
catch(libTF::TransformReference::LookupException& ex)
{
Modified: pkg/trunk/simulators/rosstage/rosstage.cc
===================================================================
--- pkg/trunk/simulators/rosstage/rosstage.cc 2008-09-18 23:28:16 UTC (rev 4449)
+++ pkg/trunk/simulators/rosstage/rosstage.cc 2008-09-18 23:30:14 UTC (rev 4450)
@@ -244,7 +244,7 @@
}
// TODO: get the frame ID from somewhere
- this->laserMsg.header.frame_id = "FRAMEID_LASER";
+ this->laserMsg.header.frame_id = "base_laser";
this->laserMsg.header.stamp.from_double(world->SimTimeNow() / 1e6);
//this->laserMsg.header.stamp.sec =
//(unsigned long)floor(world->SimTimeNow() / 1e6);
@@ -265,7 +265,7 @@
this->odomMsg.vel.th = v.a;
this->odomMsg.stall = this->positionmodel->Stall();
// TODO: get the frame ID from somewhere
- this->odomMsg.header.frame_id = "FRAMEID_ODOM";
+ this->odomMsg.header.frame_id = "odom";
this->odomMsg.header.stamp.from_double(world->SimTimeNow() / 1e6);
//this->odomMsg.header.stamp.sec =
@@ -276,8 +276,8 @@
// printf("%u \n",world->SimTimeNow());
//printf("time: %u, %u \n",odomMsg.header.stamp.sec, odomMsg.header.stamp.nsec);
- tf.sendInverseEuler("FRAMEID_ODOM",
- "FRAMEID_ROBOT",
+ tf.sendInverseEuler("odom",
+ "base",
odomMsg.pos.x,
odomMsg.pos.y,
0.0,
@@ -296,7 +296,7 @@
pose.setFromEuler(gpose.y, -gpose.x, 0.0,
Stg::normalize(gpose.a-M_PI/2.0), 0.0, 0.0);
this->groundTruthMsg.pose3D = pose.getMessage();
- this->groundTruthMsg.header.frame_id = "FRAMEID_ODOM";
+ this->groundTruthMsg.header.frame_id = "odom";
this->groundTruthMsg.header.stamp.from_double(world->SimTimeNow() / 1e6);
publish("base_pose_ground_truth", this->groundTruthMsg);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|