|
From: <jfa...@us...> - 2009-08-08 03:14:02
|
Revision: 21120
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21120&view=rev
Author: jfaustwg
Date: 2009-08-08 03:13:52 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
QuaternionStamped::quaternion -> QuaternionStamped::data (#2278)
Modified Paths:
--------------
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg
pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
pkg/trunk/stacks/geometry/tf/src/tf/listener.py
pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
Modified: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg 2009-08-08 03:11:05 UTC (rev 21119)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg 2009-08-08 03:13:52 UTC (rev 21120)
@@ -1,2 +1,2 @@
Header header
-Quaternion quaternion
+Quaternion data
Modified: pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
===================================================================
--- pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-08 03:11:05 UTC (rev 21119)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-08 03:13:52 UTC (rev 21120)
@@ -135,10 +135,10 @@
/** \brief convert QuaternionStamped msg to Stamped<Quaternion> */
static inline void quaternionStampedMsgToTF(const geometry_msgs::QuaternionStamped & msg, Stamped<Quaternion>& bt)
-{quaternionMsgToTF(msg.quaternion, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
+{quaternionMsgToTF(msg.data, 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, geometry_msgs::QuaternionStamped & msg)
-{quaternionTFToMsg(bt, msg.quaternion); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+{quaternionTFToMsg(bt, msg.data); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Vector3 msg to Vector3 */
static inline void vector3MsgToTF(const geometry_msgs::Vector3& msg_v, Vector3& bt_v) {bt_v = Vector3(msg_v.x, msg_v.y, msg_v.z);};
Modified: pkg/trunk/stacks/geometry/tf/src/tf/listener.py
===================================================================
--- pkg/trunk/stacks/geometry/tf/src/tf/listener.py 2009-08-08 03:11:05 UTC (rev 21119)
+++ pkg/trunk/stacks/geometry/tf/src/tf/listener.py 2009-08-08 03:13:52 UTC (rev 21120)
@@ -104,7 +104,7 @@
r = geometry_msgs.msg.QuaternionStamped()
r.header.stamp = ps.header.stamp
r.header.frame_id = target_frame
- r.quaternion = geometry_msgs.msg.Quaternion(*quat)
+ r.data = geometry_msgs.msg.Quaternion(*quat)
return r
## Transforms a robot_msgs PoseStamped message to frame target_frame, returns the resulting PoseStamped.
Modified: pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
===================================================================
--- pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 03:11:05 UTC (rev 21119)
+++ pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 03:13:52 UTC (rev 21120)
@@ -59,18 +59,18 @@
## Setup the quaternion tests
self.tfquaternion_stamped = tf.QuaternionStamped()
- self.tfquaternion_stamped.quaternion.x = 0
- self.tfquaternion_stamped.quaternion.y = 0
- self.tfquaternion_stamped.quaternion.z = 0
- self.tfquaternion_stamped.quaternion.w = 1
+ self.tfquaternion_stamped.data.x = 0
+ self.tfquaternion_stamped.data.y = 0
+ self.tfquaternion_stamped.data.z = 0
+ self.tfquaternion_stamped.data.w = 1
self.tfquaternion_stamped.frame_id = "frame1"
self.tfquaternion_stamped.stamp = roslib.rostime.Time(10, 0)
self.msgquaternion_stamped = robot_msgs.msg.QuaternionStamped()
- self.msgquaternion_stamped.quaternion.x = 0
- self.msgquaternion_stamped.quaternion.y = 0
- self.msgquaternion_stamped.quaternion.z = 0
- self.msgquaternion_stamped.quaternion.w = 1
+ self.msgquaternion_stamped.data.x = 0
+ self.msgquaternion_stamped.data.y = 0
+ self.msgquaternion_stamped.data.z = 0
+ self.msgquaternion_stamped.data.w = 1
self.msgquaternion_stamped.header.frame_id = "frame1"
self.msgquaternion_stamped.header.stamp = roslib.rostime.Time(10,0)
@@ -159,9 +159,9 @@
self.assertEquals(tf.quaternion_stamped_msg_to_bt(self.msgquaternion_stamped), tf.quaternion_stamped_msg_to_bt(self.msgquaternion_stamped), "quaternion bt test correctness after conversion")
def test_to_msg_quaternion(self):
- self.assertEquals(tf.quaternion_bt_to_msg(self.tfquaternion_stamped.quaternion), self.msgquaternion_stamped.quaternion, "quaternion tf to msg incorrect")
+ self.assertEquals(tf.quaternion_bt_to_msg(self.tfquaternion_stamped.data), self.msgquaternion_stamped.data, "quaternion tf to msg incorrect")
def test_to_tf_quaternion(self):
- self.assertEquals(tf.quaternion_msg_to_bt(self.msgquaternion_stamped.quaternion), self.tfquaternion_stamped.quaternion, "quaternion stamped msg to tf incorrect")
+ self.assertEquals(tf.quaternion_msg_to_bt(self.msgquaternion_stamped.data), self.tfquaternion_stamped.data, "quaternion stamped msg to tf incorrect")
def test_stamped_to_msg_quaternion(self):
self.assertEquals(tf.quaternion_stamped_bt_to_msg(self.tfquaternion_stamped), self.msgquaternion_stamped, "quaternion stamped tf to msg incorrect")
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|