|
From: <tf...@us...> - 2009-08-08 04:11:04
|
Revision: 21130
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21130&view=rev
Author: tfoote
Date: 2009-08-08 04:10:57 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
deprecating VOPose allowing #1941 to slip milestones
Modified Paths:
--------------
pkg/trunk/deprecated/deprecated_msgs/manifest.xml
pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation_node.h
pkg/trunk/stacks/estimation/robot_pose_ekf/manifest.xml
pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/vision/visual_odometry/nodes/diff.py
pkg/trunk/vision/visual_odometry/nodes/vo.py
Added Paths:
-----------
pkg/trunk/deprecated/deprecated_msgs/msg/VOPose.msg
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_msgs/msg/VOPose.msg
Modified: pkg/trunk/deprecated/deprecated_msgs/manifest.xml
===================================================================
--- pkg/trunk/deprecated/deprecated_msgs/manifest.xml 2009-08-08 04:06:22 UTC (rev 21129)
+++ pkg/trunk/deprecated/deprecated_msgs/manifest.xml 2009-08-08 04:10:57 UTC (rev 21130)
@@ -11,6 +11,7 @@
<logo>http://www.willowgarage.com/files/willowgarage/robot10.jpg</logo>
<depend package="roslib"/>
<depend package="std_msgs"/>
+ <depend package="geometry_msgs"/>
<export>
<cpp cflags="-I${prefix}/msg/cpp"/>
</export>
Copied: pkg/trunk/deprecated/deprecated_msgs/msg/VOPose.msg (from rev 20633, pkg/trunk/stacks/common_msgs/robot_msgs/msg/VOPose.msg)
===================================================================
--- pkg/trunk/deprecated/deprecated_msgs/msg/VOPose.msg (rev 0)
+++ pkg/trunk/deprecated/deprecated_msgs/msg/VOPose.msg 2009-08-08 04:10:57 UTC (rev 21130)
@@ -0,0 +1,3 @@
+Header header
+geometry_msgs/Pose pose
+int32 inliers
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/VOPose.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/VOPose.msg 2009-08-08 04:06:22 UTC (rev 21129)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/VOPose.msg 2009-08-08 04:10:57 UTC (rev 21130)
@@ -1,3 +0,0 @@
-Header header
-geometry_msgs/Pose pose
-int32 inliers
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation_node.h
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation_node.h 2009-08-08 04:06:22 UTC (rev 21129)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation_node.h 2009-08-08 04:10:57 UTC (rev 21130)
@@ -49,7 +49,7 @@
#include "geometry_msgs/Twist.h"
#include "geometry_msgs/PoseWithRatesStamped.h"
#include "geometry_msgs/PoseStamped.h"
-#include "robot_msgs/VOPose.h"
+#include "deprecated_msgs/VOPose.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include <boost/thread/mutex.hpp>
@@ -96,7 +96,7 @@
void imuCallback(const ImuConstPtr& imu);
/// callback function for vo data
- void voCallback(const tf::MessageNotifier<robot_msgs::VOPose>::MessagePtr& vo);
+ void voCallback(const tf::MessageNotifier<deprecated_msgs::VOPose>::MessagePtr& vo);
ros::NodeHandle node_;
@@ -115,7 +115,7 @@
tf::TransformBroadcaster odom_broadcaster_;
// message notifier for vo
- tf::MessageNotifier<robot_msgs::VOPose>* vo_notifier_;
+ tf::MessageNotifier<deprecated_msgs::VOPose>* vo_notifier_;
// vectors
MatrixWrapper::ColumnVector vel_desi_;
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/manifest.xml
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/manifest.xml 2009-08-08 04:06:22 UTC (rev 21129)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/manifest.xml 2009-08-08 04:10:57 UTC (rev 21130)
@@ -11,6 +11,7 @@
<depend package="std_msgs" />
<depend package="robot_msgs" />
<depend package="geometry_msgs" />
+<depend package="deprecated_msgs" />
<depend package="nav_msgs" />
<depend package="tf" />
<depend package="gtest"/>
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2009-08-08 04:06:22 UTC (rev 21129)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2009-08-08 04:10:57 UTC (rev 21130)
@@ -102,7 +102,7 @@
// subscribe to vo messages
if (vo_used_){
ROS_INFO("VO sensor can be used");
- vo_notifier_ = new MessageNotifier<robot_msgs::VOPose>(robot_state_, boost::bind(&OdomEstimationNode::voCallback, this, _1), "vo", "base_link", 10);
+ vo_notifier_ = new MessageNotifier<deprecated_msgs::VOPose>(robot_state_, boost::bind(&OdomEstimationNode::voCallback, this, _1), "vo", "base_link", 10);
}
else ROS_INFO("VO sensor will NOT be used");
@@ -240,7 +240,7 @@
// callback function for VO data
- void OdomEstimationNode::voCallback(const MessageNotifier<robot_msgs::VOPose>::MessagePtr& vo)
+ void OdomEstimationNode::voCallback(const MessageNotifier<deprecated_msgs::VOPose>::MessagePtr& vo)
{
assert(vo_used_);
Modified: pkg/trunk/vision/visual_odometry/nodes/diff.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/diff.py 2009-08-08 04:06:22 UTC (rev 21129)
+++ pkg/trunk/vision/visual_odometry/nodes/diff.py 2009-08-08 04:10:57 UTC (rev 21130)
@@ -50,7 +50,7 @@
self.prev_a = 0
self.prev_b = 0
rospy.Subscriber('/stereo/raw_stereo', sensor_msgs.msg.RawStereo, self.handle_a, queue_size=2, buff_size=7000000)
- rospy.Subscriber('/vo', robot_msgs.msg.VOPose, self.handle_b, queue_size=2, buff_size=7000000)
+ rospy.Subscriber('/vo', deprecated_msgs.msg.VOPose, self.handle_b, queue_size=2, buff_size=7000000)
def handle_a(self, msg):
self.prev_a = msg.header.stamp.to_seconds()
Modified: pkg/trunk/vision/visual_odometry/nodes/vo.py
===================================================================
--- pkg/trunk/vision/visual_odometry/nodes/vo.py 2009-08-08 04:06:22 UTC (rev 21129)
+++ pkg/trunk/vision/visual_odometry/nodes/vo.py 2009-08-08 04:10:57 UTC (rev 21130)
@@ -75,7 +75,7 @@
def __init__(self):
rospy.Subscriber('/stereo/raw_stereo', sensor_msgs.msg.RawStereo, self.handle_raw_stereo, queue_size=2, buff_size=7000000)
- self.pub_vo = rospy.Publisher("/vo", robot_msgs.msg.VOPose)
+ self.pub_vo = rospy.Publisher("/vo", deprecated_msgs.msg.VOPose)
self.vo = None
self.modulo = 0
@@ -93,7 +93,7 @@
pair = [imgAdapted(i, size) for i in [ msg.left_image, msg.right_image ]]
af = SparseStereoFrame(pair[0], pair[1], feature_detector = self.fd, descriptor_scheme = self.ds)
pose = self.vo.handle_frame(af)
- p = robot_msgs.msg.VOPose()
+ p = deprecated_msgs.msg.VOPose()
p.inliers = self.vo.inl
# XXX - remove after camera sets frame_id
p.header = roslib.msg.Header(0, msg.header.stamp, "stereo_link")
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|