|
From: <tf...@us...> - 2008-10-20 05:46:10
|
Revision: 5554
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=5554&view=rev
Author: tfoote
Date: 2008-10-20 05:45:56 +0000 (Mon, 20 Oct 2008)
Log Message:
-----------
converting tf::Stamped<T> to inherit instead of have a member data_
Modified Paths:
--------------
pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/util/tf/include/tf/transform_broadcaster.h
pkg/trunk/util/tf/include/tf/transform_datatypes.h
pkg/trunk/util/tf/src/cache.cpp
pkg/trunk/util/tf/src/tf.cpp
pkg/trunk/util/tf/test/cache_unittest.cpp
pkg/trunk/util/tf/test/tf_unittest.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/marker_visualizer.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/planning_visualizer.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/point_cloud_visualizer.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/robot_base2d_pose_visualizer.cpp
Modified: pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -84,7 +84,7 @@
// Get the robot's pose
tf::Stamped<tf::Pose> ident;
tf::Stamped<btTransform> odom_pose;
- ident.data_.setIdentity();
+ ident.setIdentity();
ident.frame_id_ = "base";
ident.stamp_ = t;
try
@@ -97,11 +97,11 @@
return false;
}
double yaw,pitch,roll;
- btMatrix3x3 mat = odom_pose.data_.getBasis();
+ btMatrix3x3 mat = odom_pose.getBasis();
mat.getEulerZYX(yaw, pitch, roll);
- gmap_pose = GMapping::OrientedPoint(odom_pose.data_.getOrigin().x(),
- odom_pose.data_.getOrigin().y(),
+ gmap_pose = GMapping::OrientedPoint(odom_pose.getOrigin().x(),
+ odom_pose.getOrigin().y(),
yaw);
return true;
}
@@ -112,7 +112,7 @@
// @todo Get the laser's pose, relative to base.
tf::Stamped<tf::Pose> ident;
tf::Stamped<btTransform> laser_pose;
- ident.data_.setIdentity();
+ ident.setIdentity();
ident.frame_id_ = "base_laser";
ident.stamp_ = scan.header.stamp;
try
@@ -126,15 +126,15 @@
return false;
}
double yaw,pitch,roll;
- btMatrix3x3 mat = laser_pose.data_.getBasis();
+ btMatrix3x3 mat = laser_pose.getBasis();
mat.getEulerZYX(yaw, pitch, roll);
- GMapping::OrientedPoint gmap_pose(laser_pose.data_.getOrigin().x(),
- laser_pose.data_.getOrigin().y(),
+ GMapping::OrientedPoint gmap_pose(laser_pose.getOrigin().x(),
+ laser_pose.getOrigin().y(),
yaw);
ROS_DEBUG("laser's pose wrt base: %.3f %.3f %.3f",
- laser_pose.data_.getOrigin().x(),
- laser_pose.data_.getOrigin().y(),
+ laser_pose.getOrigin().x(),
+ laser_pose.getOrigin().y(),
yaw);
// The laser must be called "FLASER"
@@ -248,8 +248,8 @@
/*
ROS_DEBUG("scan pose (%.3f): %.3f %.3f %.3f",
scan.header.stamp.toSec(),
- odom_pose.data_.getOrigin().x(),
- odom_pose.data_.getOrigin().y(),
+ odom_pose.getOrigin().x(),
+ odom_pose.getOrigin().y(),
yaw);
*/
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-10-20 05:45:56 UTC (rev 5554)
@@ -426,12 +426,12 @@
}
double yaw,pitch,roll;
- btMatrix3x3 mat = global_pose.data_.getBasis();
+ btMatrix3x3 mat = global_pose.getBasis();
mat.getEulerZYX(yaw, pitch, roll);
// Fill out and publish response
- this->pstate.pos.x = global_pose.data_.getOrigin().x();
- this->pstate.pos.y = global_pose.data_.getOrigin().y();
+ this->pstate.pos.x = global_pose.getOrigin().x();
+ this->pstate.pos.y = global_pose.getOrigin().y();
this->pstate.pos.th = yaw;
this->pstate.goal.x = this->goal[0];
this->pstate.goal.y = this->goal[1];
@@ -609,7 +609,7 @@
//convert!
tf::Stamped<tf::Pose> robotPose;
- robotPose.data_.setIdentity();
+ robotPose.setIdentity();
robotPose.frame_id_ = "base";
robotPose.stamp_ = 0; // request most recent pose
//robotPose.time = laserMsg.header.stamp.sec * 1000000000ULL +
@@ -663,12 +663,12 @@
{
double yaw,pitch,roll; //fixme make cleaner namespace
- btMatrix3x3 mat = global_pose.data_.getBasis();
+ btMatrix3x3 mat = global_pose.getBasis();
mat.getEulerZYX(yaw, pitch, roll);
// Are we done?
if(plan_check_done(this->plan,
- global_pose.data_.getOrigin().x(), global_pose.data_.getOrigin().y(), yaw,
+ global_pose.getOrigin().x(), global_pose.getOrigin().y(), yaw,
this->goal[0], this->goal[1], this->goal[2],
this->dist_eps, this->ang_eps))
{
@@ -688,11 +688,11 @@
// Try a local plan
if((this->planner_state == NEW_GOAL) ||
- (plan_do_local(this->plan, global_pose.data_.getOrigin().x(), global_pose.data_.getOrigin().y(),
+ (plan_do_local(this->plan, global_pose.getOrigin().x(), global_pose.getOrigin().y(),
this->plan_halfwidth) < 0))
{
// Fallback on global plan
- if(plan_do_global(this->plan, global_pose.data_.getOrigin().x(), global_pose.data_.getOrigin().y(),
+ if(plan_do_global(this->plan, global_pose.getOrigin().x(), global_pose.getOrigin().y(),
this->goal[0], this->goal[1]) < 0)
{
// no global plan
@@ -722,7 +722,7 @@
{
// global plan succeeded; now try the local plan again
this->printed_warning = false;
- if(plan_do_local(this->plan, global_pose.data_.getOrigin().x(), global_pose.data_.getOrigin().y(),
+ if(plan_do_local(this->plan, global_pose.getOrigin().x(), global_pose.getOrigin().y(),
this->plan_halfwidth) < 0)
{
// no local plan; better luck next time through
@@ -743,12 +743,12 @@
// double yaw,pitch,roll; //used temporarily earlier fixme make cleaner
//btMatrix3x3
- mat = global_pose.data_.getBasis();
+ mat = global_pose.getBasis();
mat.getEulerZYX(yaw, pitch, roll);
if(plan_compute_diffdrive_cmds(this->plan, &vx, &va,
&this->rotate_dir,
- global_pose.data_.getOrigin().x(), global_pose.data_.getOrigin().y(),
+ global_pose.getOrigin().x(), global_pose.getOrigin().y(),
yaw,
this->goal[0], this->goal[1],
this->goal[2],
@@ -789,15 +789,15 @@
assert(0);
}
double yaw,pitch,roll;
- btMatrix3x3 mat = global_pose.data_.getBasis();
+ btMatrix3x3 mat = global_pose.getBasis();
mat.getEuler(yaw, pitch, roll);
this->pstate.active = (this->enable &&
(this->planner_state == PURSUING_GOAL)) ? 1 : 0;
this->pstate.valid = (this->plan->path_count > 0) ? 1 : 0;
this->pstate.done = (this->planner_state == REACHED_GOAL) ? 1 : 0;
- this->pstate.pos.x = global_pose.data_.getOrigin().x();
- this->pstate.pos.y = global_pose.data_.getOrigin().y();
+ this->pstate.pos.x = global_pose.getOrigin().x();
+ this->pstate.pos.y = global_pose.getOrigin().y();
this->pstate.pos.th = yaw;
this->pstate.goal.x = this->goal[0];
this->pstate.goal.y = this->goal[1];
Modified: pkg/trunk/util/tf/include/tf/transform_broadcaster.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_broadcaster.h 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/util/tf/include/tf/transform_broadcaster.h 2008-10-20 05:45:56 UTC (rev 5554)
@@ -72,10 +72,10 @@
tfArray.quaternions[0].header.frame_id = transform.frame_id_;
tfArray.quaternions[0].parent = transform.parent_id_;
- Quaternion q = transform.data_.getRotation();
- tfArray.quaternions[0].xt = transform.data_.getOrigin().x();
- tfArray.quaternions[0].yt = transform.data_.getOrigin().y();
- tfArray.quaternions[0].zt = transform.data_.getOrigin().z();
+ Quaternion q = transform.getRotation();
+ tfArray.quaternions[0].xt = transform.getOrigin().x();
+ tfArray.quaternions[0].yt = transform.getOrigin().y();
+ tfArray.quaternions[0].zt = transform.getOrigin().z();
tfArray.quaternions[0].xr = q.x();
tfArray.quaternions[0].yr = q.y();
tfArray.quaternions[0].zr = q.z();
Modified: pkg/trunk/util/tf/include/tf/transform_datatypes.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_datatypes.h 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/util/tf/include/tf/transform_datatypes.h 2008-10-20 05:45:56 UTC (rev 5554)
@@ -60,9 +60,8 @@
/** \brief The data type which will be cross compatable with std_msgs
* this will require the associated rosTF package to convert */
template <typename T>
-class Stamped{
+class Stamped : public T{
public:
- T data_;
ros::Time stamp_;
std::string frame_id_;
std::string parent_id_; ///only used for transform
@@ -70,14 +69,15 @@
Stamped() :stamp_ (0),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"):
- data_ (input), stamp_ ( timestamp ), frame_id_ (frame_id), parent_id_(parent_id){ };
+ T (input), stamp_ ( timestamp ), frame_id_ (frame_id), parent_id_(parent_id){ };
//Stamped(const Stamped<T>& input):data_(input.data_), stamp_(input.stamp_), frame_id_(input.frame_id_), parent_id_(input.parent_id_){};
//Stamped& operator=(const Stamped<T>& input){data_ = input.data_; stamp_ = input.stamp_; frame_id_ = input.frame_id_;
// parent_id_ = input.parent_id_; return *this;};
- void stripStamp(T & output) { output = data_;};
+ void setData(const T& input){*static_cast<T*>(this) = input;};
+ // void stripStamp(T & output) { output = data_;}; //just down cast it
};
@@ -88,10 +88,10 @@
/** \brief convert QuaternionStamped msg to Stamped<Quaternion> */
static inline void QuaternionStampedMsgToTF(const std_msgs::QuaternionStamped & msg, Stamped<Quaternion>& bt)
-{QuaternionMsgToTF(msg.quaternion, bt.data_); bt.stamp_ = msg.header.stamp.to_ull(); bt.frame_id_ = msg.header.frame_id;};
+{QuaternionMsgToTF(msg.quaternion, bt); bt.stamp_ = msg.header.stamp.to_ull(); 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.data_, msg.quaternion); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+{QuaternionTFToMsg(bt, msg.quaternion); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Vector3 msg to Vector3 */
static inline void Vector3MsgToTF(const std_msgs::Vector3& msg_v, Vector3& bt_v) {bt_v = Vector3(msg_v.x, msg_v.y, msg_v.z);};
@@ -100,10 +100,10 @@
/** \brief convert Vector3Stamped msg to Stamped<Vector3> */
static inline void Vector3StampedMsgToTF(const std_msgs::Vector3Stamped & msg, Stamped<Vector3>& bt)
-{Vector3MsgToTF(msg.vector, bt.data_); bt.stamp_ = msg.header.stamp.to_ull(); bt.frame_id_ = msg.header.frame_id;};
+{Vector3MsgToTF(msg.vector, bt); bt.stamp_ = msg.header.stamp.to_ull(); 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.data_, msg.vector); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+{Vector3TFToMsg(bt, msg.vector); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Point msg to Point */
@@ -113,10 +113,10 @@
/** \brief convert PointStamped msg to Stamped<Point> */
static inline void PointStampedMsgToTF(const std_msgs::PointStamped & msg, Stamped<Point>& bt)
-{PointMsgToTF(msg.point, bt.data_); bt.stamp_ = msg.header.stamp.to_ull(); bt.frame_id_ = msg.header.frame_id;};
+{PointMsgToTF(msg.point, bt); bt.stamp_ = msg.header.stamp.to_ull(); 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.data_, msg.point); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+{PointTFToMsg(bt, msg.point); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Transform msg to Transform */
@@ -128,10 +128,10 @@
/** \brief convert TransformStamped msg to Stamped<Transform> */
static inline void TransformStampedMsgToTF(const std_msgs::TransformStamped & msg, Stamped<Transform>& bt)
-{TransformMsgToTF(msg.transform, bt.data_); 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.to_ull(); 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.data_, 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.frame_id_; msg.parent_id = bt.parent_id_;};
/** \brief convert Pose msg to Pose */
static inline void PoseMsgToTF(const std_msgs::Pose& msg, Pose& bt)
@@ -142,10 +142,10 @@
/** \brief convert PoseStamped msg to Stamped<Pose> */
static inline void PoseStampedMsgToTF(const std_msgs::PoseStamped & msg, Stamped<Pose>& bt)
-{PoseMsgToTF(msg.pose, bt.data_); bt.stamp_ = msg.header.stamp.to_ull(); bt.frame_id_ = msg.header.frame_id;};
+{PoseMsgToTF(msg.pose, bt); bt.stamp_ = msg.header.stamp.to_ull(); 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.data_, msg.pose); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+{PoseTFToMsg(bt, msg.pose); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief Convert the transform to a Homogeneous matrix for large operations */
Modified: pkg/trunk/util/tf/src/cache.cpp
===================================================================
--- pkg/trunk/util/tf/src/cache.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/util/tf/src/cache.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -160,14 +160,14 @@
//Interpolate translation
btVector3 v;
- v.setInterpolate3(one.data_.getOrigin(), two.data_.getOrigin(), ratio);
- output.data_.setOrigin(v);
+ v.setInterpolate3(one.getOrigin(), two.getOrigin(), ratio);
+ output.setOrigin(v);
//Interpolate rotation
btQuaternion q1,q2;
- one.data_.getBasis().getRotation(q1);
- two.data_.getBasis().getRotation(q2);
- output.data_.setRotation(slerp( q1, q2 , ratio));
+ one.getBasis().getRotation(q1);
+ two.getBasis().getRotation(q2);
+ output.setRotation(slerp( q1, q2 , ratio));
output.frame_id_ = one.frame_id_;
output.parent_id_ = one.parent_id_;
output.parent_frame_id = one.parent_frame_id;
Modified: pkg/trunk/util/tf/src/tf.cpp
===================================================================
--- pkg/trunk/util/tf/src/tf.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/util/tf/src/tf.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -83,7 +83,7 @@
{
TransformLists t_list = lookupLists(lookupFrameNumber( target_frame), time, lookupFrameNumber( source_frame));
- transform.data_ = computeTransformFromList(t_list);
+ transform.setData( computeTransformFromList(t_list));
transform.stamp_ = time;
transform.frame_id_ = target_frame;
@@ -94,14 +94,14 @@
{
//calculate first leg
TransformLists t_list = lookupLists(lookupFrameNumber( fixed_frame), source_time, lookupFrameNumber( source_frame));
- transform.data_ = computeTransformFromList(t_list);
+ btTransform temp1 = computeTransformFromList(t_list);
TransformLists t_list2 = lookupLists(lookupFrameNumber( target_frame), target_time, lookupFrameNumber( fixed_frame));
btTransform temp = computeTransformFromList(t_list2);
- transform.data_*= temp; ///\todo check order here
+ transform.setData( temp1 * temp); ///\todo check order here
transform.stamp_ = target_time;
transform.frame_id_ = target_frame;
@@ -278,7 +278,7 @@
for (unsigned int i = 0; i < lists.inverseTransforms.size(); i++)
{
try {
- retTrans *= (lists.inverseTransforms[lists.inverseTransforms.size() -1 - i]).data_; //Reverse to get left multiply
+ retTrans *= (lists.inverseTransforms[lists.inverseTransforms.size() -1 - i]); //Reverse to get left multiply
}
catch (tf::ExtrapolationException &ex)
{
@@ -290,7 +290,7 @@
for (unsigned int i = 0; i < lists.forwardTransforms.size(); i++)
{
try {
- retTrans = (lists.forwardTransforms[lists.forwardTransforms.size() -1 - i]).data_.inverse() * retTrans; //Do this list backwards(from backwards) for it was generated traveling the wrong way
+ retTrans = (lists.forwardTransforms[lists.forwardTransforms.size() -1 - i]).inverse() * retTrans; //Do this list backwards(from backwards) for it was generated traveling the wrong way
}
catch (tf::ExtrapolationException &ex)
{
@@ -390,7 +390,7 @@
btTransform transform = computeTransformFromList(t_list);
- stamped_out.data_ = transform * stamped_in.data_;
+ stamped_out.setData( transform * stamped_in);
stamped_out.stamp_ = stamped_in.stamp_;
stamped_out.frame_id_ = target_frame;
};
@@ -404,10 +404,10 @@
btTransform transform = computeTransformFromList(t_list);
/** \todo may not be most efficient */
- btVector3 end = stamped_in.data_;
+ btVector3 end = stamped_in;
btVector3 origin = btVector3(0,0,0);
btVector3 output = (transform * end) - (transform * origin);
- stamped_out.data_ = output;
+ stamped_out.setData( output);
stamped_out.stamp_ = stamped_in.stamp_;
stamped_out.frame_id_ = target_frame;
@@ -420,7 +420,7 @@
btTransform transform = computeTransformFromList(t_list);
- stamped_out.data_ = transform * stamped_in.data_;
+ stamped_out.setData(transform * stamped_in);
stamped_out.stamp_ = stamped_in.stamp_;
stamped_out.frame_id_ = target_frame;
stamped_out.parent_id_ = stamped_in.parent_id_;//only useful for transforms
@@ -432,7 +432,7 @@
btTransform transform = computeTransformFromList(t_list);
- stamped_out.data_ = transform * stamped_in.data_;
+ stamped_out.setData(transform * stamped_in);
stamped_out.stamp_ = stamped_in.stamp_;
stamped_out.frame_id_ = target_frame;
// stamped_out.parent_id_ = stamped_in.parent_id_;//only useful for transforms
Modified: pkg/trunk/util/tf/test/cache_unittest.cpp
===================================================================
--- pkg/trunk/util/tf/test/cache_unittest.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/util/tf/test/cache_unittest.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -55,7 +55,7 @@
std::vector<double> values(runs);
TransformStorage stor;
- stor.data_.setIdentity();
+ stor.setIdentity();
for ( unsigned int i = 1; i < runs ; i++ )
{
@@ -92,7 +92,7 @@
std::vector<double> values(runs);
TransformStorage stor;
- stor.data_.setIdentity();
+ stor.setIdentity();
for ( int i = runs -1; i >= 0 ; i-- )
{
@@ -129,7 +129,7 @@
unsigned int runs = values.size();
TransformStorage stor;
- stor.data_.setIdentity();
+ stor.setIdentity();
for ( unsigned int i = 0; i <runs ; i++ )
{
values[i] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
@@ -164,7 +164,7 @@
std::vector<double> values(runs);
TransformStorage stor;
- stor.data_.setIdentity();
+ stor.setIdentity();
for ( unsigned int i = 1; i < runs ; i++ )
{
@@ -229,7 +229,7 @@
unsigned int offset = 200;
TransformStorage stor;
- stor.data_.setIdentity();
+ stor.setIdentity();
for ( unsigned int i = 1; i < runs ; i++ )
{
@@ -240,7 +240,7 @@
yvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
zvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
- stor.data_.setOrigin(btVector3(xvalues[step], yvalues[step], zvalues[step]));
+ stor.setOrigin(btVector3(xvalues[step], yvalues[step], zvalues[step]));
stor.frame_id_ = "NO_NEED";
stor.parent_frame_id = 2;
stor.stamp_ = step * 100 + offset;
@@ -250,9 +250,9 @@
for (int pos = 0; pos < 100 ; pos ++)
{
cache.getData(offset + pos, stor);
- double x_out = stor.data_.getOrigin().x();
- double y_out = stor.data_.getOrigin().y();
- double z_out = stor.data_.getOrigin().z();
+ double x_out = stor.getOrigin().x();
+ double y_out = stor.getOrigin().y();
+ double z_out = stor.getOrigin().z();
EXPECT_NEAR(xvalues[0] + (xvalues[1] - xvalues[0]) * (double)pos/100.0, x_out, epsilon);
EXPECT_NEAR(yvalues[0] + (yvalues[1] - yvalues[0]) * (double)pos/100.0, y_out, epsilon);
EXPECT_NEAR(zvalues[0] + (zvalues[1] - zvalues[0]) * (double)pos/100.0, z_out, epsilon);
@@ -277,7 +277,7 @@
std::vector<double> zvalues(2);
TransformStorage stor;
- stor.data_.setIdentity();
+ stor.setIdentity();
for (unsigned int step = 0; step < 2 ; step++)
{
@@ -285,7 +285,7 @@
yvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
zvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
- stor.data_.setOrigin(btVector3(xvalues[step], yvalues[step], zvalues[step]));
+ stor.setOrigin(btVector3(xvalues[step], yvalues[step], zvalues[step]));
stor.frame_id_ = "NO_NEED";
stor.parent_frame_id = step + 4;
stor.stamp_ = step * 100 + offset;
@@ -295,9 +295,9 @@
for (int pos = 0; pos < 100 ; pos ++)
{
cache.getData(offset + pos, stor);
- double x_out = stor.data_.getOrigin().x();
- double y_out = stor.data_.getOrigin().y();
- double z_out = stor.data_.getOrigin().z();
+ double x_out = stor.getOrigin().x();
+ double y_out = stor.getOrigin().y();
+ double z_out = stor.getOrigin().z();
EXPECT_NEAR(xvalues[0], x_out, epsilon);
EXPECT_NEAR(yvalues[0], y_out, epsilon);
EXPECT_NEAR(zvalues[0], z_out, epsilon);
@@ -306,9 +306,9 @@
for (int pos = 100; pos < 120 ; pos ++)
{
cache.getData(offset + pos, stor);
- double x_out = stor.data_.getOrigin().x();
- double y_out = stor.data_.getOrigin().y();
- double z_out = stor.data_.getOrigin().z();
+ double x_out = stor.getOrigin().x();
+ double y_out = stor.getOrigin().y();
+ double z_out = stor.getOrigin().z();
EXPECT_NEAR(xvalues[1], x_out, epsilon);
EXPECT_NEAR(yvalues[1], y_out, epsilon);
EXPECT_NEAR(zvalues[1], z_out, epsilon);
@@ -331,7 +331,7 @@
unsigned int offset = 555;
TransformStorage stor;
- stor.data_.setIdentity();
+ stor.setIdentity();
for ( unsigned int i = 1; i < runs ; i++ )
{
@@ -342,7 +342,7 @@
yvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
zvalues[step] = 10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
- stor.data_.setOrigin(btVector3(xvalues[step], yvalues[step], zvalues[step]));
+ stor.setOrigin(btVector3(xvalues[step], yvalues[step], zvalues[step]));
stor.frame_id_ = "NO_NEED";
stor.parent_frame_id = 2;
stor.stamp_ = step * 100 + offset;
@@ -352,9 +352,9 @@
for (int pos = -200; pos < 300 ; pos ++)
{
cache.getData(offset + pos, stor);
- double x_out = stor.data_.getOrigin().x();
- double y_out = stor.data_.getOrigin().y();
- double z_out = stor.data_.getOrigin().z();
+ double x_out = stor.getOrigin().x();
+ double y_out = stor.getOrigin().y();
+ double z_out = stor.getOrigin().z();
EXPECT_NEAR(xvalues[0] + (xvalues[1] - xvalues[0]) * (double)pos/100.0, x_out, epsilon);
EXPECT_NEAR(yvalues[0] + (yvalues[1] - yvalues[0]) * (double)pos/100.0, y_out, epsilon);
EXPECT_NEAR(zvalues[0] + (zvalues[1] - zvalues[0]) * (double)pos/100.0, z_out, epsilon);
@@ -406,7 +406,7 @@
std::vector<btQuaternion> quats(2);
TransformStorage stor;
- stor.data_.setIdentity();
+ stor.setIdentity();
for ( unsigned int i = 1; i < runs ; i++ )
{
@@ -417,7 +417,7 @@
pitchvalues[step] = 0;//10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
rollvalues[step] = 0;//10.0 * ((double) rand() - (double)RAND_MAX /2.0) /(double)RAND_MAX;
quats[step] = btQuaternion(yawvalues[step], pitchvalues[step], rollvalues[step]);
- stor.data_.setRotation(quats[step]);
+ stor.setRotation(quats[step]);
stor.frame_id_ = "NO_NEED";
stor.parent_frame_id = 3;
stor.stamp_ = offset + (step * 100); //step = 0 or 1
@@ -427,7 +427,7 @@
for (int pos = -100; pos < 200 ; pos ++)
{
cache.getData(offset + pos, stor); //get the transform for the position
- btQuaternion quat = stor.data_.getRotation(); //get the quaternion out of the transform
+ btQuaternion quat = stor.getRotation(); //get the quaternion out of the transform
//Generate a ground truth quaternion directly calling slerp
btQuaternion ground_truth = quats[0].slerp(quats[1], pos/100.0);
Modified: pkg/trunk/util/tf/test/tf_unittest.cpp
===================================================================
--- pkg/trunk/util/tf/test/tf_unittest.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/util/tf/test/tf_unittest.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -61,13 +61,12 @@
Stamped<btTransform> inpose (btTransform(btQuaternion(0,0,0), btVector3(0,0,0)), 10 + i, "child");
try{
- Stamped<Pose
-> outpose;
- outpose.data_.setIdentity(); //to make sure things are getting mutated
+ Stamped<Pose> outpose;
+ outpose.setIdentity(); //to make sure things are getting mutated
mTR.transformPose("my_parent",inpose, outpose);
- EXPECT_NEAR(outpose.data_.getOrigin().x(), xvalues[i], epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().y(), yvalues[i], epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().z(), zvalues[i], epsilon);
+ EXPECT_NEAR(outpose.getOrigin().x(), xvalues[i], epsilon);
+ EXPECT_NEAR(outpose.getOrigin().y(), yvalues[i], epsilon);
+ EXPECT_NEAR(outpose.getOrigin().z(), zvalues[i], epsilon);
}
catch (tf::TransformException & ex)
{
@@ -79,11 +78,11 @@
Stamped<Pose> inpose (btTransform(btQuaternion(0,0,0), btVector3(0,0,0)), runs, "child");
Stamped<Pose> outpose;
- outpose.data_.setIdentity(); //to make sure things are getting mutated
+ outpose.setIdentity(); //to make sure things are getting mutated
mTR.transformPose("child",inpose, outpose);
- EXPECT_NEAR(outpose.data_.getOrigin().x(), 0, epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().y(), 0, epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().z(), 0, epsilon);
+ EXPECT_NEAR(outpose.getOrigin().x(), 0, epsilon);
+ EXPECT_NEAR(outpose.getOrigin().y(), 0, epsilon);
+ EXPECT_NEAR(outpose.getOrigin().z(), 0, epsilon);
}
@@ -123,12 +122,12 @@
try{
Stamped<Pose> outpose;
- outpose.data_.setIdentity(); //to make sure things are getting mutated
+ outpose.setIdentity(); //to make sure things are getting mutated
mTR.transformPose("child",inpose, outpose);
- EXPECT_NEAR(outpose.data_.getOrigin().x(), 0, epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().y(), 0, epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().z(), 0, epsilon);
- EXPECT_NEAR(outpose.data_.getRotation().w(), 1, epsilon); //Identity is 0,0,0,1
+ EXPECT_NEAR(outpose.getOrigin().x(), 0, epsilon);
+ EXPECT_NEAR(outpose.getOrigin().y(), 0, epsilon);
+ EXPECT_NEAR(outpose.getOrigin().z(), 0, epsilon);
+ EXPECT_NEAR(outpose.getRotation().w(), 1, epsilon); //Identity is 0,0,0,1
}
catch (tf::TransformException & ex)
{
@@ -140,11 +139,11 @@
Stamped<Pose> inpose (btTransform(btQuaternion(0,0,0), btVector3(0,0,0)), runs, "child");
Stamped<Pose> outpose;
- outpose.data_.setIdentity(); //to make sure things are getting mutated
+ outpose.setIdentity(); //to make sure things are getting mutated
mTR.transformPose("child",inpose, outpose);
- EXPECT_NEAR(outpose.data_.getOrigin().x(), 0, epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().y(), 0, epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().z(), 0, epsilon);
+ EXPECT_NEAR(outpose.getOrigin().x(), 0, epsilon);
+ EXPECT_NEAR(outpose.getOrigin().y(), 0, epsilon);
+ EXPECT_NEAR(outpose.getOrigin().z(), 0, epsilon);
}
@@ -184,11 +183,11 @@
try{
Stamped<Point> outvec(btVector3(0,0,0), 10 + i, "child");
- // outpose.data_.setIdentity(); //to make sure things are getting mutated
+ // outpose.setIdentity(); //to make sure things are getting mutated
mTR.transformPoint("my_parent",invec, outvec);
- EXPECT_NEAR(outvec.data_.x(), xvalues[i]+x, epsilon);
- EXPECT_NEAR(outvec.data_.y(), yvalues[i]+y, epsilon);
- EXPECT_NEAR(outvec.data_.z(), zvalues[i]+z, epsilon);
+ EXPECT_NEAR(outvec.x(), xvalues[i]+x, epsilon);
+ EXPECT_NEAR(outvec.y(), yvalues[i]+y, epsilon);
+ EXPECT_NEAR(outvec.z(), zvalues[i]+z, epsilon);
}
catch (tf::TransformException & ex)
{
@@ -235,11 +234,11 @@
try{
Stamped<Vector3> outvec(btVector3(0,0,0), 10 + i, "child");
- // outpose.data_.setIdentity(); //to make sure things are getting mutated
+ // outpose.setIdentity(); //to make sure things are getting mutated
mTR.transformVector("my_parent",invec, outvec);
- EXPECT_NEAR(outvec.data_.x(), x, epsilon);
- EXPECT_NEAR(outvec.data_.y(), y, epsilon);
- EXPECT_NEAR(outvec.data_.z(), z, epsilon);
+ EXPECT_NEAR(outvec.x(), x, epsilon);
+ EXPECT_NEAR(outvec.y(), y, epsilon);
+ EXPECT_NEAR(outvec.z(), z, epsilon);
}
catch (tf::TransformException & ex)
{
@@ -287,7 +286,7 @@
Stamped<btQuaternion> outvec(btQuaternion(xvalues[i],yvalues[i],zvalues[i]), 10 + i, "child");
mTR.transformQuaternion("my_parent",invec, outvec);
- EXPECT_NEAR(outvec.data_.angle(invec.data_) , 0, epsilon);
+ EXPECT_NEAR(outvec.angle(invec) , 0, epsilon);
}
catch (tf::TransformException & ex)
{
@@ -338,9 +337,9 @@
std_msgs::Vector3Stamped msgv;
Vector3StampedTFToMsg(btv, msgv);
Vector3StampedMsgToTF(msgv, btv_out);
- EXPECT_NEAR(btv.data_.x(), btv_out.data_.x(), epsilon);
- EXPECT_NEAR(btv.data_.y(), btv_out.data_.y(), epsilon);
- EXPECT_NEAR(btv.data_.z(), btv_out.data_.z(), epsilon);
+ EXPECT_NEAR(btv.x(), btv_out.x(), epsilon);
+ EXPECT_NEAR(btv.y(), btv_out.y(), epsilon);
+ EXPECT_NEAR(btv.z(), btv_out.z(), epsilon);
EXPECT_STREQ(btv.frame_id_.c_str(), btv_out.frame_id_.c_str());
EXPECT_EQ(btv.stamp_, btv_out.stamp_);
}
@@ -386,10 +385,10 @@
std_msgs::QuaternionStamped msgv;
QuaternionStampedTFToMsg(btv, msgv);
QuaternionStampedMsgToTF(msgv, btv_out);
- EXPECT_NEAR(btv.data_.x(), btv_out.data_.x(), epsilon);
- EXPECT_NEAR(btv.data_.y(), btv_out.data_.y(), epsilon);
- EXPECT_NEAR(btv.data_.z(), btv_out.data_.z(), epsilon);
- EXPECT_NEAR(btv.data_.w(), btv_out.data_.w(), epsilon);
+ EXPECT_NEAR(btv.x(), btv_out.x(), epsilon);
+ EXPECT_NEAR(btv.y(), btv_out.y(), epsilon);
+ EXPECT_NEAR(btv.z(), btv_out.z(), epsilon);
+ EXPECT_NEAR(btv.w(), btv_out.w(), epsilon);
EXPECT_STREQ(btv.frame_id_.c_str(), btv_out.frame_id_.c_str());
EXPECT_EQ(btv.stamp_, btv_out.stamp_);
}
@@ -442,13 +441,13 @@
std_msgs::TransformStamped msgv;
TransformStampedTFToMsg(btv, msgv);
TransformStampedMsgToTF(msgv, btv_out);
- EXPECT_NEAR(btv.data_.getOrigin().x(), btv_out.data_.getOrigin().x(), epsilon);
- EXPECT_NEAR(btv.data_.getOrigin().y(), btv_out.data_.getOrigin().y(), epsilon);
- EXPECT_NEAR(btv.data_.getOrigin().z(), btv_out.data_.getOrigin().z(), epsilon);
- EXPECT_NEAR(btv.data_.getRotation().x(), btv_out.data_.getRotation().x(), epsilon);
- EXPECT_NEAR(btv.data_.getRotation().y(), btv_out.data_.getRotation().y(), epsilon);
- EXPECT_NEAR(btv.data_.getRotation().z(), btv_out.data_.getRotation().z(), epsilon);
- EXPECT_NEAR(btv.data_.getRotation().w(), btv_out.data_.getRotation().w(), epsilon);
+ EXPECT_NEAR(btv.getOrigin().x(), btv_out.getOrigin().x(), epsilon);
+ EXPECT_NEAR(btv.getOrigin().y(), btv_out.getOrigin().y(), epsilon);
+ EXPECT_NEAR(btv.getOrigin().z(), btv_out.getOrigin().z(), epsilon);
+ EXPECT_NEAR(btv.getRotation().x(), btv_out.getRotation().x(), epsilon);
+ EXPECT_NEAR(btv.getRotation().y(), btv_out.getRotation().y(), epsilon);
+ EXPECT_NEAR(btv.getRotation().z(), btv_out.getRotation().z(), epsilon);
+ EXPECT_NEAR(btv.getRotation().w(), btv_out.getRotation().w(), epsilon);
EXPECT_STREQ(btv.frame_id_.c_str(), btv_out.frame_id_.c_str());
EXPECT_EQ(btv.stamp_, btv_out.stamp_);
}
@@ -482,11 +481,11 @@
try{
Stamped<Pose> outpose;
- outpose.data_.setIdentity(); //to make sure things are getting mutated
+ outpose.setIdentity(); //to make sure things are getting mutated
mTR.transformPose("my_parent",inpose, outpose);
- EXPECT_NEAR(outpose.data_.getOrigin().x(), xvalues[i], epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().y(), yvalues[i], epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().z(), zvalues[i], epsilon);
+ EXPECT_NEAR(outpose.getOrigin().x(), xvalues[i], epsilon);
+ EXPECT_NEAR(outpose.getOrigin().y(), yvalues[i], epsilon);
+ EXPECT_NEAR(outpose.getOrigin().z(), zvalues[i], epsilon);
}
catch (tf::TransformException & ex)
{
@@ -527,11 +526,11 @@
try{
Stamped<btTransform> outpose;
- outpose.data_.setIdentity(); //to make sure things are getting mutated
+ outpose.setIdentity(); //to make sure things are getting mutated
mTR.transformPose("child",inpose, outpose);
- EXPECT_NEAR(outpose.data_.getOrigin().x(), -xvalues[i], epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().y(), -yvalues[i], epsilon);
- EXPECT_NEAR(outpose.data_.getOrigin().z(), -zvalues[i], epsilon);
+ EXPECT_NEAR(outpose.getOrigin().x(), -xvalues[i], epsilon);
+ EXPECT_NEAR(outpose.getOrigin().y(), -yvalues[i], epsilon);
+ EXPECT_NEAR(outpose.getOrigin().z(), -zvalues[i], epsilon);
}
catch (tf::TransformException & ex)
{
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -534,11 +534,11 @@
//printf( "Link %s:\npose: %6f %6f %6f,\t%6f %6f %6f\n", name.c_str(), pose.data_.getOrigin().x(), pose.data_.getOrigin().y(), pose.data_.getOrigin().z(), pose.data_.getOrigin().y()aw, pose.pitch, pose.roll );
- Ogre::Vector3 position( pose.data_.getOrigin().x(), pose.data_.getOrigin().y(), pose.data_.getOrigin().z() );
+ Ogre::Vector3 position( pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z() );
robotToOgre( position );
btScalar yaw, pitch, roll;
- pose.data_.getBasis().getEulerZYX( yaw, pitch, roll );
+ pose.getBasis().getEulerZYX( yaw, pitch, roll );
Ogre::Matrix3 orientation( ogreMatrixFromRobotEulers( yaw, pitch, roll ) );
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/marker_visualizer.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/marker_visualizer.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/marker_visualizer.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -272,11 +272,11 @@
ROS_ERROR( "Error transforming marker '%d' from frame '%s' to frame '%s'\n", message.id, frame_id.c_str(), target_frame_.c_str() );
}
- Ogre::Vector3 position( pose.data_.getOrigin().x(), pose.data_.getOrigin().y(), pose.data_.getOrigin().z() );
+ Ogre::Vector3 position( pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z() );
robotToOgre( position );
btScalar yaw, pitch, roll;
- pose.data_.getBasis().getEulerZYX( yaw, pitch, roll );
+ pose.getBasis().getEulerZYX( yaw, pitch, roll );
Ogre::Matrix3 orientation;
orientation.FromEulerAnglesZXY( Ogre::Radian( roll ), Ogre::Radian( pitch ), Ogre::Radian( -yaw) );
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/planning_visualizer.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/planning_visualizer.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/planning_visualizer.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -268,11 +268,11 @@
ROS_ERROR( "Error transforming from frame '%s' to frame '%s'\n", pose.frame_id_.c_str(), target_frame_.c_str() );
}
- Ogre::Vector3 position( pose.data_.getOrigin().x(), pose.data_.getOrigin().y(), pose.data_.getOrigin().z() );
+ Ogre::Vector3 position( pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z() );
robotToOgre( position );
btScalar yaw, pitch, roll;
- pose.data_.getBasis().getEulerZYX( yaw, pitch, roll );
+ pose.getBasis().getEulerZYX( yaw, pitch, roll );
Ogre::Matrix3 orientation;
orientation.FromEulerAnglesYXZ( Ogre::Radian( yaw ), Ogre::Radian( pitch ), Ogre::Radian( roll ) );
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/point_cloud_visualizer.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/point_cloud_visualizer.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/point_cloud_visualizer.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -193,11 +193,11 @@
ROS_ERROR( "Error transforming point cloud '%s' from frame '%s' to frame '%s'\n", name_.c_str(), message_.header.frame_id.c_str(), target_frame_.c_str() );
}
- Ogre::Vector3 position( pose.data_.getOrigin().x(), pose.data_.getOrigin().y(), pose.data_.getOrigin().z() );
+ Ogre::Vector3 position( pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z() );
robotToOgre( position );
btScalar yaw, pitch, roll;
- pose.data_.getBasis().getEulerZYX( yaw, pitch, roll );
+ pose.getBasis().getEulerZYX( yaw, pitch, roll );
Ogre::Matrix3 orientation( ogreMatrixFromRobotEulers( yaw, pitch, roll ) );
scene_node_->setPosition( position );
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/robot_base2d_pose_visualizer.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/robot_base2d_pose_visualizer.cpp 2008-10-20 05:32:58 UTC (rev 5553)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/robot_base2d_pose_visualizer.cpp 2008-10-20 05:45:56 UTC (rev 5554)
@@ -226,12 +226,12 @@
}
btScalar yaw, pitch, roll;
- pose.data_.getBasis().getEulerZYX( yaw, pitch, roll );
+ pose.getBasis().getEulerZYX( yaw, pitch, roll );
Ogre::Matrix3 orient;
orient.FromEulerAnglesZXY( Ogre::Radian( roll ), Ogre::Radian( pitch ), Ogre::Radian( yaw ) );
arrow->setOrientation( orient );
- Ogre::Vector3 pos( pose.data_.getOrigin().x(), pose.data_.getOrigin().y(), pose.data_.getOrigin().z() );
+ Ogre::Vector3 pos( pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z() );
robotToOgre( pos );
arrow->setPosition( pos );
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|