|
From: <tf...@us...> - 2009-08-13 05:42:32
|
Revision: 21780
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21780&view=rev
Author: tfoote
Date: 2009-08-13 05:42:20 +0000 (Thu, 13 Aug 2009)
Log Message:
-----------
switching TransformStamped logic to follow that of all other frame_ids where the frame_id is the operating frame and there is now a child_frame_id which defines the target frame. And the parent frame is gone. This is only changing the message. The API change will come later.
Modified Paths:
--------------
pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/test/test_move_base_local.py
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp
pkg/trunk/demos/plug_in/fake_camera_frame.py
pkg/trunk/demos/plug_in/fake_vision.py
pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/old/scripts/approachtable.py
pkg/trunk/sandbox/tf_node/src/tf_node.cpp
pkg/trunk/sandbox/webteleop/src/server.py
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/TransformStamped.msg
pkg/trunk/stacks/geometry/tf/include/tf/transform_broadcaster.h
pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
pkg/trunk/stacks/geometry/tf/src/pytf.cpp
pkg/trunk/stacks/geometry/tf/src/transform_broadcaster.cpp
pkg/trunk/stacks/geometry/tf/src/transform_listener.cpp
pkg/trunk/stacks/geometry/tf/test/testPython.py
pkg/trunk/stacks/mechanism/robot_state_publisher/src/robot_state_publisher.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/scripts/fake_gripper_frame.py
Modified: pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/test/test_move_base_local.py
===================================================================
--- pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/test/test_move_base_local.py 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/test/test_move_base_local.py 2009-08-13 05:42:20 UTC (rev 21780)
@@ -55,7 +55,7 @@
def tf_cb(self, msg):
if self.active:
for t in msg.transforms:
- if t.parent_id == 'odom_combined':
+ if t.header.frame_id == 'odom_combined':
tx = t.transform
# Convert Transform.msg to bullet
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -157,26 +157,26 @@
msg.transforms[i].header.stamp = mech_state->header.stamp ;
// Laser Chain
- msg.transforms[0].parent_id = "torso_lift_link" ;
- msg.transforms[0].header.frame_id = "laser_tilt_mount_link_cal" ;
+ msg.transforms[0].header.frame_id = "torso_lift_link" ;
+ msg.transforms[0].child_frame_id = "laser_tilt_mount_link_cal" ;
tf::transformTFToMsg(laser_initial_T_*laser_joint_T, msg.transforms[0].transform) ;
- msg.transforms[1].parent_id = "laser_tilt_mount_link_cal" ;
- msg.transforms[1].header.frame_id = "laser_tilt_link_cal" ;
+ msg.transforms[1].header.frame_id = "laser_tilt_mount_link_cal" ;
+ msg.transforms[1].child_frame_id = "laser_tilt_link_cal" ;
tf::transformTFToMsg(laser_final_T_, msg.transforms[1].transform) ;
// Head Chain
- msg.transforms[2].parent_id = "torso_lift_link" ;
- msg.transforms[2].header.frame_id = "head_pan_link_cal" ;
+ msg.transforms[2].header.frame_id = "torso_lift_link" ;
+ msg.transforms[2].child_frame_id = "head_pan_link_cal" ;
tf::transformTFToMsg(head_initial_T_*pan_joint_T, msg.transforms[2].transform) ;
- msg.transforms[3].parent_id = "head_pan_link_cal" ;
- msg.transforms[3].header.frame_id = "head_tilt_link_cal" ;
+ msg.transforms[3].header.frame_id = "head_pan_link_cal" ;
+ msg.transforms[3].child_frame_id = "head_tilt_link_cal" ;
//tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
- msg.transforms[4].parent_id = "head_tilt_link_cal" ;
- msg.transforms[4].header.frame_id = "stereo_optical_frame_cal" ;
+ msg.transforms[4].header.frame_id = "head_tilt_link_cal" ;
+ msg.transforms[4].child_frame_id = "stereo_optical_frame_cal" ;
tf::transformTFToMsg(after_tilt_T_, msg.transforms[4].transform) ;
tf_pub_.publish(msg) ;
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -161,26 +161,26 @@
msg.transforms[i].header.stamp = mech_state->header.stamp ;
// Laser Chain
- msg.transforms[0].parent_id = "torso_lift_link" ;
- msg.transforms[0].header.frame_id = "laser_tilt_mount_link_cal" ;
+ msg.transforms[0].header.frame_id = "torso_lift_link" ;
+ msg.transforms[0].child_frame_id = "laser_tilt_mount_link_cal" ;
tf::transformTFToMsg(laser_initial_T_*laser_joint_T, msg.transforms[0].transform) ;
- msg.transforms[1].parent_id = "laser_tilt_mount_link_cal" ;
- msg.transforms[1].header.frame_id = "laser_tilt_link_cal" ;
+ msg.transforms[1].header.frame_id = "laser_tilt_mount_link_cal" ;
+ msg.transforms[1].child_frame_id = "laser_tilt_link_cal" ;
tf::transformTFToMsg(laser_final_T_, msg.transforms[1].transform) ;
// Head Chain
- msg.transforms[2].parent_id = "torso_lift_link" ;
- msg.transforms[2].header.frame_id = "head_pan_link_cal" ;
+ msg.transforms[2].header.frame_id = "torso_lift_link" ;
+ msg.transforms[2].child_frame_id = "head_pan_link_cal" ;
tf::transformTFToMsg(head_initial_T_*pan_joint_T, msg.transforms[2].transform) ;
- msg.transforms[3].parent_id = "head_pan_link_cal" ;
- msg.transforms[3].header.frame_id = "head_tilt_link_cal" ;
+ msg.transforms[3].header.frame_id = "head_pan_link_cal" ;
+ msg.transforms[3].child_frame_id = "head_tilt_link_cal" ;
//tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
- msg.transforms[4].parent_id = "head_tilt_link_cal" ;
- msg.transforms[4].header.frame_id = "stereo_optical_frame_cal" ;
+ msg.transforms[4].header.frame_id = "head_tilt_link_cal" ;
+ msg.transforms[4].child_frame_id = "stereo_optical_frame_cal" ;
tf::transformTFToMsg(after_tilt_T_, msg.transforms[4].transform) ;
tf_pub_.publish(msg) ;
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -160,26 +160,26 @@
msg.transforms[i].header.stamp = mech_state->header.stamp ;
// Laser Chain
- msg.transforms[0].parent_id = "torso_lift_link" ;
- msg.transforms[0].header.frame_id = "laser_tilt_mount_link_cal" ;
+ msg.transforms[0].header.frame_id = "torso_lift_link" ;
+ msg.transforms[0].child_frame_id = "laser_tilt_mount_link_cal" ;
tf::transformTFToMsg(laser_initial_T_*laser_joint_T, msg.transforms[0].transform) ;
- msg.transforms[1].parent_id = "laser_tilt_mount_link_cal" ;
- msg.transforms[1].header.frame_id = "laser_tilt_link_cal" ;
+ msg.transforms[1].header.frame_id = "laser_tilt_mount_link_cal" ;
+ msg.transforms[1].child_frame_id = "laser_tilt_link_cal" ;
tf::transformTFToMsg(laser_final_T_, msg.transforms[1].transform) ;
// Head Chain
- msg.transforms[2].parent_id = "torso_lift_link" ;
- msg.transforms[2].header.frame_id = "head_pan_link_cal" ;
+ msg.transforms[2].header.frame_id = "torso_lift_link" ;
+ msg.transforms[2].child_frame_id = "head_pan_link_cal" ;
tf::transformTFToMsg(head_initial_T_*pan_joint_T, msg.transforms[2].transform) ;
- msg.transforms[3].parent_id = "head_pan_link_cal" ;
- msg.transforms[3].header.frame_id = "head_tilt_link_cal" ;
+ msg.transforms[3].header.frame_id = "head_pan_link_cal" ;
+ msg.transforms[3].child_frame_id = "head_tilt_link_cal" ;
//tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
- msg.transforms[4].parent_id = "head_tilt_link_cal" ;
- msg.transforms[4].header.frame_id = "stereo_optical_frame_cal" ;
+ msg.transforms[4].header.frame_id = "head_tilt_link_cal" ;
+ msg.transforms[4].child_frame_id = "stereo_optical_frame_cal" ;
tf::transformTFToMsg(after_tilt_T_, msg.transforms[4].transform) ;
tf_pub_.publish(msg) ;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -358,8 +358,8 @@
geometry_msgs::TransformStamped &out = transform_publisher_->msg_.transforms[0];
out.header.stamp.fromSec(current_time_);
- out.header.frame_id = odom_frame_;
- out.parent_id = base_footprint_frame_;
+ out.header.frame_id = base_footprint_frame_;
+ out.child_frame_id = odom_frame_;
out.transform.translation.x = -x * cos(yaw) - y * sin(yaw);
out.transform.translation.y = +x * sin(yaw) - y * cos(yaw);
out.transform.translation.z = 0;
@@ -372,8 +372,8 @@
geometry_msgs::TransformStamped &out2 = transform_publisher_->msg_.transforms[1];
out2.header.stamp.fromSec(current_time_);
- out2.header.frame_id = base_link_frame_;
- out2.parent_id = base_footprint_frame_;
+ out2.header.frame_id = base_footprint_frame_;
+ out2.child_frame_id = base_link_frame_;
out2.transform.translation.x = 0;
out2.transform.translation.y = 0;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -37,6 +37,7 @@
#include <kdl/chainfksolvervel_recursive.hpp>
#include <kdl/chainjnttojacsolver.hpp>
#include <kdl/jacobian.hpp>
+#include "tf/tfMessage.h"
#include "tf_conversions/tf_kdl.h"
#include "realtime_tools/realtime_publisher.h"
#include "control_toolbox/pid.h"
@@ -587,8 +588,8 @@
if (pub_tf_->trylock())
{
//pub_tf_->msg_.transforms[0].header.stamp.fromSec();
- pub_tf_->msg_.transforms[0].header.frame_id = name_ + "/tool_frame";
- pub_tf_->msg_.transforms[0].parent_id = c_.kdl_chain_.getSegment(c_.kdl_chain_.getNrOfSegments()-1).getName();
+ pub_tf_->msg_.transforms[0].header.frame_id = c_.kdl_chain_.getSegment(c_.kdl_chain_.getNrOfSegments()-1).getName();
+ pub_tf_->msg_.transforms[0].child_frame_id = name_ + "/tool_frame";
tf::Transform t;
tf::TransformKDLToTF(c_.tool_frame_offset_, t);
tf::transformTFToMsg(t, pub_tf_->msg_.transforms[0].transform);
Modified: pkg/trunk/demos/plug_in/fake_camera_frame.py
===================================================================
--- pkg/trunk/demos/plug_in/fake_camera_frame.py 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/demos/plug_in/fake_camera_frame.py 2009-08-13 05:42:20 UTC (rev 21780)
@@ -26,6 +26,8 @@
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
+
+#\todo replace this with usage of transform_sender in tf packge
import roslib
roslib.load_manifest('plug_in')
import rospy
@@ -62,9 +64,9 @@
self.msg = msg
t = TransformStamped()
-t.header.frame_id = 'high_def_frame'
+t.header.frame_id = 'base_link'
t.header.seq = 0
-t.parent_id = 'base_link'
+t.child_frame_id = 'high_def_frame'
t.transform.translation = xyz(0, 0, 1.25)
t.transform.rotation = rpy(0, 1.3, 0)
Modified: pkg/trunk/demos/plug_in/fake_vision.py
===================================================================
--- pkg/trunk/demos/plug_in/fake_vision.py 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/demos/plug_in/fake_vision.py 2009-08-13 05:42:20 UTC (rev 21780)
@@ -32,7 +32,6 @@
import rospy
from std_msgs.msg import *
from geometry_msgs.msg import Quaternion, PoseStamped
-from tf.msg import tfMessage
from math import *
from time import sleep
import tf.transformations
Modified: pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/old/scripts/approachtable.py
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/old/scripts/approachtable.py 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/old/scripts/approachtable.py 2009-08-13 05:42:20 UTC (rev 21780)
@@ -66,7 +66,7 @@
# Hack to get around the fact that we don't have pytf
def tfCallback(self,msg):
- if (msg.transforms[0].header.frame_id == self.global_frame and
+ if (msg.transforms[0].child_frame_id == self.global_frame and
self.odom_pose != None):
self.robot_position = Point((self.odom_pose.pose.pose.position.x -
msg.transforms[0].transform.translation.x),
Modified: pkg/trunk/sandbox/tf_node/src/tf_node.cpp
===================================================================
--- pkg/trunk/sandbox/tf_node/src/tf_node.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/sandbox/tf_node/src/tf_node.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -36,9 +36,6 @@
#include "tf/FrameGraph.h"
-#include "tf/tfMessage.h"
-
-
#include "geometry_msgs/PointStamped.h"
#include "sensor_msgs/PointCloud.h"
#include "geometry_msgs/PoseStamped.h"
@@ -163,10 +160,8 @@
******************************************************************************/
void publishTransformCallback(const boost::shared_ptr<const geometry_msgs::TransformStamped> &message) {
- tf::Transform tft;
- tf::transformMsgToTF(message->transform, tft);
- ROS_INFO((std::string("Sending transform from parent ") + message->parent_id + " to " + message->header.frame_id).c_str());
- tb->sendTransform(tft, message->header.stamp, message->header.frame_id, message->parent_id);
+ ROS_INFO((std::string("Sending transform from parent ") + message->header.frame_id + " to " + message->child_frame_id).c_str());
+ tb->sendTransform(*message);
}
class TimedTransform {
Modified: pkg/trunk/sandbox/webteleop/src/server.py
===================================================================
--- pkg/trunk/sandbox/webteleop/src/server.py 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/sandbox/webteleop/src/server.py 2009-08-13 05:42:20 UTC (rev 21780)
@@ -26,7 +26,6 @@
import wg_hardware_roslaunch.roslaunch_caller as roslaunch_caller
-from tf.msg import tfMessage
from nav_msgs import *
from nav_msgs.msg import *
from std_msgs.msg import *
Modified: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/TransformStamped.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/TransformStamped.msg 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/TransformStamped.msg 2009-08-13 05:42:20 UTC (rev 21780)
@@ -1,6 +1,6 @@
-# This expresses a transform between coordinate frames labeled by parent_id
-# and the frame_id field of the header.
+# This expresses a transform from coordinate frame header.frame_id
+# to the coordinate frame child_frame_id
Header header
-string parent_id # the frame id of the parent frame
+string child_frame_id # the frame id of the child frame
Transform transform
Modified: pkg/trunk/stacks/geometry/tf/include/tf/transform_broadcaster.h
===================================================================
--- pkg/trunk/stacks/geometry/tf/include/tf/transform_broadcaster.h 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_broadcaster.h 2009-08-13 05:42:20 UTC (rev 21780)
@@ -61,6 +61,10 @@
* The stamped data structure includes frame_id, and time, and parent_id already. */
void sendTransform(const Stamped<Transform> & transform);
+ /** \brief Send a TransformStamped
+ * The stamped data structure includes frame_id, and time, and parent_id already. */
+ void sendTransform(const geometry_msgs::TransformStamped & transform);
+
/** \brief Send a Transform, stamped with time, frame_id and parent_id */
void sendTransform(const Transform & transform, const ros::Time& time, const std::string& frame_id, const std::string& parent_id);
Modified: pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
===================================================================
--- pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-13 05:42:20 UTC (rev 21780)
@@ -175,10 +175,10 @@
/** \brief convert TransformStamped msg to Stamped<Transform> */
static inline void transformStampedMsgToTF(const geometry_msgs::TransformStamped & msg, Stamped<Transform>& bt)
-{transformMsgToTF(msg.transform, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id; bt.parent_id_ = msg.parent_id;};
+{transformMsgToTF(msg.transform, bt); bt.stamp_ = msg.header.stamp; bt.parent_id_ = msg.header.frame_id; bt.frame_id_ = msg.child_frame_id;};
/** \brief convert Stamped<Transform> to TransformStamped msg*/
static inline void transformStampedTFToMsg(const Stamped<Transform>& bt, geometry_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_;};
+{transformTFToMsg(bt, msg.transform); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.parent_id_; msg.child_frame_id = bt.frame_id_;};
/** \brief convert Pose msg to Pose */
static inline void poseMsgToTF(const geometry_msgs::Pose& msg, Pose& bt)
Modified: pkg/trunk/stacks/geometry/tf/src/pytf.cpp
===================================================================
--- pkg/trunk/stacks/geometry/tf/src/pytf.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/stacks/geometry/tf/src/pytf.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -233,8 +233,8 @@
return NULL;
tf::Stamped< btTransform > transform;
PyObject *header = PyObject_BorrowAttrString(py_transform, "header");
- transform.frame_id_ = PyString_AsString(PyObject_BorrowAttrString(header, "frame_id"));
- transform.parent_id_ = PyString_AsString(PyObject_BorrowAttrString(py_transform, "parent_id"));
+ transform.frame_id_ = PyString_AsString(PyObject_BorrowAttrString(py_transform, "child_frame_id"));
+ transform.parent_id_ = PyString_AsString(PyObject_BorrowAttrString(header, "frame_id"));
if (rostime_converter(PyObject_BorrowAttrString(header, "stamp"), &transform.stamp_) != 1)
return NULL;
Modified: pkg/trunk/stacks/geometry/tf/src/transform_broadcaster.cpp
===================================================================
--- pkg/trunk/stacks/geometry/tf/src/transform_broadcaster.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/stacks/geometry/tf/src/transform_broadcaster.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -42,15 +42,20 @@
node_.param(std::string("~tf_prefix"),tf_prefix_, std::string(""));
};
+void TransformBroadcaster::sendTransform(const geometry_msgs::TransformStamped & msgtf)
+{
+ tfMessage message;
+ message.transforms.push_back(msgtf);
+ publisher_.publish(message);
+}
+
void TransformBroadcaster::sendTransform(const Stamped<Transform> & transform)
{
- tfMessage message;
geometry_msgs::TransformStamped msgtf;
transformStampedTFToMsg(transform, msgtf);
msgtf.header.frame_id = tf::remap(tf_prefix_, msgtf.header.frame_id);
- msgtf.parent_id = tf::remap(tf_prefix_, msgtf.parent_id);
- message.transforms.push_back(msgtf);
- publisher_.publish(message);
+ msgtf.child_frame_id = tf::remap(tf_prefix_, msgtf.child_frame_id);
+ sendTransform(msgtf);
}
@@ -59,9 +64,8 @@
tfMessage message;
geometry_msgs::TransformStamped msgtf;
msgtf.header.stamp = time;
- msgtf.header.frame_id = frame_id;
- msgtf.header.frame_id = tf::remap(tf_prefix_, msgtf.header.frame_id);
- msgtf.parent_id = remap(tf_prefix_, parent_id);
+ msgtf.header.frame_id = tf::remap(tf_prefix_, parent_id);
+ msgtf.child_frame_id = tf::remap(tf_prefix_, frame_id);
transformTFToMsg(transform, msgtf.transform);
message.transforms.push_back(msgtf);
publisher_.publish(message);
Modified: pkg/trunk/stacks/geometry/tf/src/transform_listener.cpp
===================================================================
--- pkg/trunk/stacks/geometry/tf/src/transform_listener.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/stacks/geometry/tf/src/transform_listener.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -318,7 +318,7 @@
{
///\todo Use error reporting
std::string temp = ex.what();
- ROS_ERROR("Failure to set recieved transform %s to %s with error: %s\n", msg_in.transforms[i].header.frame_id.c_str(), msg_in.transforms[i].parent_id.c_str(), temp.c_str());
+ ROS_ERROR("Failure to set recieved transform from %s to %s with error: %s\n", msg_in.transforms[i].child_frame_id.c_str(), msg_in.transforms[i].header.frame_id.c_str(), temp.c_str());
}
}
};
Modified: pkg/trunk/stacks/geometry/tf/test/testPython.py
===================================================================
--- pkg/trunk/stacks/geometry/tf/test/testPython.py 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/stacks/geometry/tf/test/testPython.py 2009-08-13 05:42:20 UTC (rev 21780)
@@ -51,8 +51,8 @@
def common(self, t):
m = geometry_msgs.msg.TransformStamped()
- m.header.frame_id = "THISFRAME"
- m.parent_id = "PARENT"
+ m.header.frame_id = "PARENT"
+ m.child_frame_id = "THISFRAME"
m.transform.translation.y = 5.0
m.transform.rotation = geometry_msgs.msg.Quaternion(*tf.transformations.quaternion_from_euler(0, 0, 0))
t.setTransform(m)
Modified: pkg/trunk/stacks/mechanism/robot_state_publisher/src/robot_state_publisher.cpp
===================================================================
--- pkg/trunk/stacks/mechanism/robot_state_publisher/src/robot_state_publisher.cpp 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/stacks/mechanism/robot_state_publisher/src/robot_state_publisher.cpp 2009-08-13 05:42:20 UTC (rev 21780)
@@ -93,8 +93,8 @@
tf::Transform tf_frame;
tf::TransformKDLToTF(frame, tf_frame);
trans.header.stamp = time;
- trans.header.frame_id = tf::remap(tf_prefix_, f->first);
- trans.parent_id = tf::remap(tf_prefix_, root->first);
+ trans.header.frame_id = tf::remap(tf_prefix_, root->first);
+ trans.child_frame_id = tf::remap(tf_prefix_, f->first);
tf::transformTFToMsg(tf_frame, trans.transform);
tf_msg_.transforms[i++] = trans;
}
Modified: pkg/trunk/stacks/visual_feature_detectors/outlet_detection/scripts/fake_gripper_frame.py
===================================================================
--- pkg/trunk/stacks/visual_feature_detectors/outlet_detection/scripts/fake_gripper_frame.py 2009-08-13 05:38:40 UTC (rev 21779)
+++ pkg/trunk/stacks/visual_feature_detectors/outlet_detection/scripts/fake_gripper_frame.py 2009-08-13 05:42:20 UTC (rev 21780)
@@ -54,13 +54,13 @@
return q
t = TransformStamped()
-t.header.frame_id = 'r_gripper_tool_frame'
+t.child_frame_id = 'r_gripper_tool_frame'
t.header.seq = 0
#t.parent_id = 'base_link'
#t.transform.translation = xyz(0.506305, -0.194843, 0.284381)
#t.transform.rotation = rpy(0, 1.13, 0)
#t.transform.rotation = Quaternion(0.050555, 0.245594, -0.051239, 0.966697)
-t.parent_id = 'high_def_frame'
+t.header.frame_id = 'high_def_frame'
t.transform.translation = xyz(1.013218, -0.019657, -0.044208)
t.transform.rotation = Quaternion(-0.092009, -0.482387, 0.139255, 0.859910)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|