|
From: <sf...@us...> - 2009-08-08 04:59:27
|
Revision: 21137
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21137&view=rev
Author: sfkwc
Date: 2009-08-08 04:59:15 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
#2271 Vector3Stamped uses new standarization
Modified Paths:
--------------
pkg/trunk/demos/plug_in/fake_camera_frame.py
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_bumper.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_f3d.cpp
pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp
pkg/trunk/stacks/common_msgs/geometry_msgs/migration_rules/migration_rules.py
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/Vector3Stamped.msg
pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
Modified: pkg/trunk/demos/plug_in/fake_camera_frame.py
===================================================================
--- pkg/trunk/demos/plug_in/fake_camera_frame.py 2009-08-08 04:58:08 UTC (rev 21136)
+++ pkg/trunk/demos/plug_in/fake_camera_frame.py 2009-08-08 04:59:15 UTC (rev 21137)
@@ -65,8 +65,8 @@
t.header.frame_id = 'high_def_frame'
t.header.seq = 0
t.parent_id = 'base_link'
-t.transform.translation = xyz(0, 0, 1.25)
-t.transform.rotation = rpy(0, 1.3, 0)
+t.data.translation = xyz(0, 0, 1.25)
+t.data.rotation = rpy(0, 1.3, 0)
rospy.init_node('fake_camera')
pub_tf = rospy.Publisher('/tf_message', tfMessage)
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_bumper.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_bumper.cpp 2009-08-08 04:58:08 UTC (rev 21136)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_bumper.cpp 2009-08-08 04:59:15 UTC (rev 21137)
@@ -87,9 +87,9 @@
// Initialize the controller
void RosBumper::InitChild()
{
- this->forceMsg.vector.x = 0;
- this->forceMsg.vector.y = 0;
- this->forceMsg.vector.z = 0;
+ this->forceMsg.data.x = 0;
+ this->forceMsg.data.y = 0;
+ this->forceMsg.data.z = 0;
}
////////////////////////////////////////////////////////////////////////////////
@@ -136,9 +136,9 @@
this->forceMsg.header.stamp.nsec = (unsigned long)floor( 1e9 * ( cur_time - this->forceMsg.header.stamp.sec) );
double eps = 0.10; // very crude low pass filter
- this->forceMsg.vector.x = (1.0-eps)*this->forceMsg.vector.x + eps*contact_forces.f1[0];
- this->forceMsg.vector.y = (1.0-eps)*this->forceMsg.vector.y + eps*contact_forces.f1[1];
- this->forceMsg.vector.z = (1.0-eps)*this->forceMsg.vector.z + eps*contact_forces.f1[2];
+ this->forceMsg.data.x = (1.0-eps)*this->forceMsg.data.x + eps*contact_forces.f1[0];
+ this->forceMsg.data.y = (1.0-eps)*this->forceMsg.data.y + eps*contact_forces.f1[1];
+ this->forceMsg.data.z = (1.0-eps)*this->forceMsg.data.z + eps*contact_forces.f1[2];
this->info_pub_.publish(this->bumperMsg);
this->force_pub_.publish(this->forceMsg);
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_f3d.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_f3d.cpp 2009-08-08 04:58:08 UTC (rev 21136)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_f3d.cpp 2009-08-08 04:59:15 UTC (rev 21137)
@@ -109,9 +109,9 @@
this->vector3Msg.header.stamp.sec = (unsigned long)floor(Simulator::Instance()->GetSimTime());
this->vector3Msg.header.stamp.nsec = (unsigned long)floor( 1e9 * ( Simulator::Instance()->GetSimTime() - this->vector3Msg.header.stamp.sec) );
- this->vector3Msg.vector.x = force.x;
- this->vector3Msg.vector.y = force.y;
- this->vector3Msg.vector.z = force.z;
+ this->vector3Msg.data.x = force.x;
+ this->vector3Msg.data.y = force.y;
+ this->vector3Msg.data.z = force.z;
//std::cout << "RosF3D: " << this->topicName
// << " f: " << force
Modified: pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp
===================================================================
--- pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp 2009-08-08 04:58:08 UTC (rev 21136)
+++ pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp 2009-08-08 04:59:15 UTC (rev 21137)
@@ -88,7 +88,6 @@
#include <sys/time.h>
using namespace std;
-using namespace robot_msgs;
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Comparison operator for a vector of vectors
@@ -301,18 +300,18 @@
geometry_msgs::Vector3Stamped axis_original;
ROS_INFO("Original axis: %f %f %f",axis_.x,axis_.y,axis_.z);
- axis_original.vector.x = axis_.x;
- axis_original.vector.y = axis_.y;
- axis_original.vector.z = axis_.z;
+ axis_original.data.x = axis_.x;
+ axis_original.data.y = axis_.y;
+ axis_original.data.z = axis_.z;
axis_original.header.frame_id = "base_link";
axis_original.header.stamp = ros::Time(0.0);
tf_->transformVector("stereo_link",axis_original,axis_transformed);
geometry_msgs::Point32 axis_point_32;
- axis_point_32.x = axis_transformed.vector.x;
- axis_point_32.y = axis_transformed.vector.y;
- axis_point_32.z = axis_transformed.vector.z;
+ axis_point_32.x = axis_transformed.data.x;
+ axis_point_32.y = axis_transformed.data.y;
+ axis_point_32.z = axis_transformed.data.z;
ROS_INFO("Transformed axis: %f %f %f",axis_point_32.x,axis_point_32.y,axis_point_32.z);
Modified: pkg/trunk/stacks/common_msgs/geometry_msgs/migration_rules/migration_rules.py
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/migration_rules/migration_rules.py 2009-08-08 04:58:08 UTC (rev 21136)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/migration_rules/migration_rules.py 2009-08-08 04:59:15 UTC (rev 21137)
@@ -155,7 +155,7 @@
new_type = "geometry_msgs/Vector3Stamped"
new_full_text = """
Header header
-Vector3 vector
+Vector3 data
================================================================================
MSG: roslib/Header
@@ -188,7 +188,7 @@
def update(self, old_msg, new_msg):
self.migrate(old_msg.header, new_msg.header)
- self.migrate(old_msg.vector, new_msg.vector)
+ self.migrate(old_msg.vector, new_msg.data)
class update_robot_msgs_Point_4a842b65f413084dc2b10fb484ea7f17(MessageUpdateRule):
old_type = "robot_msgs/Point"
Modified: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/Vector3Stamped.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/Vector3Stamped.msg 2009-08-08 04:58:08 UTC (rev 21136)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/Vector3Stamped.msg 2009-08-08 04:59:15 UTC (rev 21137)
@@ -1,2 +1,2 @@
Header header
-Vector3 vector
+Vector3 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 04:58:08 UTC (rev 21136)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-08 04:59:15 UTC (rev 21137)
@@ -147,10 +147,10 @@
/** \brief convert Vector3Stamped msg to Stamped<Vector3> */
static inline void vector3StampedMsgToTF(const geometry_msgs::Vector3Stamped & msg, Stamped<Vector3>& bt)
-{vector3MsgToTF(msg.vector, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
+{vector3MsgToTF(msg.data, 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, geometry_msgs::Vector3Stamped & msg)
-{vector3TFToMsg(bt, msg.vector); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+{vector3TFToMsg(bt, msg.data); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Point msg to Point */
Modified: pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
===================================================================
--- pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 04:58:08 UTC (rev 21136)
+++ pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 04:59:15 UTC (rev 21137)
@@ -51,9 +51,9 @@
self.tfvector_stamped.stamp = roslib.rostime.Time(10, 0)
self.msgvector_stamped = robot_msgs.msg.Vector3Stamped()
- self.msgvector_stamped.vector.x = 0
- self.msgvector_stamped.vector.y = 0
- self.msgvector_stamped.vector.z = 0
+ self.msgvector_stamped.data.x = 0
+ self.msgvector_stamped.data.y = 0
+ self.msgvector_stamped.data.z = 0
self.msgvector_stamped.header.frame_id = "frame1"
self.msgvector_stamped.header.stamp = roslib.rostime.Time(10,0)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|