|
From: <tf...@us...> - 2009-08-08 01:21:04
|
Revision: 21107
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21107&view=rev
Author: tfoote
Date: 2009-08-08 01:20:58 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
moving mapping messages outside of common_msgs for 0.1 release
Added Paths:
-----------
pkg/trunk/sandbox/mapping_msgs/
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/mapping_msgs/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jfa...@us...> - 2009-08-08 01:30:31
|
Revision: 21110
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21110&view=rev
Author: jfaustwg
Date: 2009-08-08 01:30:20 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
PoseWithCovariance->PoseWithCovarianceStamped
PoseWithCovarianceStamped::pose_with_covariance -> PoseWithCovarianceStamped::data
Modified Paths:
--------------
pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py
pkg/trunk/demos/test_2dnav_gazebo/set_goal.py
pkg/trunk/sandbox/labeled_object_detector/test/test_nearest_action2.cpp
pkg/trunk/sandbox/webteleop/src/server.py
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithCovarianceStamped.msg
pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation.h
pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation_node.h
pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp
pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp
pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp
pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h
pkg/trunk/stacks/navigation/nav_view/src/nav_view/tools.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/tools/pose_tool.cpp
pkg/trunk/vision/vslam/nodes/picmap.py
pkg/trunk/vision/vslam/nodes/roadmap.py
Modified: pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py
===================================================================
--- pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py 2009-08-08 01:30:20 UTC (rev 21110)
@@ -49,7 +49,7 @@
from std_msgs.msg import String
from nav_robot_actions.msg import MoveBaseState
-from geometry_msgs.msg import Pose,Quaternion,Point, PoseWithRatesStamped, PoseStamped, PoseWithCovariance
+from geometry_msgs.msg import Pose,Quaternion,Point, PoseWithRatesStamped, PoseStamped, PoseWithCovarianceStamped
from geometry_msgs.msg import Twist
from nav_msgs.msg import Odometry
import tf.transformations as tft
@@ -222,13 +222,13 @@
#pub_base = rospy.Publisher("cmd_vel", BaseVel)
pub_goal = rospy.Publisher("/move_base/activate", PoseStamped)
- pub_pose = rospy.Publisher("initialpose", PoseWithCovariance)
+ pub_pose = rospy.Publisher("initialpose", PoseWithCovarianceStamped)
rospy.Subscriber("base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
rospy.Subscriber("odom" , Odometry , self.odomInput)
rospy.Subscriber("base_bumper/info" , String , self.bumpedInput)
rospy.Subscriber("torso_lift_bumper/info", String , self.bumpedInput)
rospy.Subscriber("/move_base/feedback" , MoveBaseState , self.stateInput)
- rospy.Subscriber("/amcl_pose" , PoseWithCovariance , self.amclInput)
+ rospy.Subscriber("/amcl_pose" , PoseWithCovarianceStamped , self.amclInput)
# below only for debugging build 303, base not moving
rospy.Subscriber("cmd_vel" , Twist , self.cmd_velInput)
@@ -312,7 +312,7 @@
q = Quaternion(tmpq[0],tmpq[1],tmpq[2],tmpq[3])
pose = Pose(p,q)
print "publishing initialpose",h,p,COV[0]
- pub_pose.publish(PoseWithCovariance(h, pose,COV))
+ pub_pose.publish(PoseWithCovarianceStamped(h, PoseWithCovariance(pose,COV)))
else:
# send goal until state /move_base/feedback indicates goal is received
p = Point(self.target_x, self.target_y, 0)
Modified: pkg/trunk/demos/test_2dnav_gazebo/set_goal.py
===================================================================
--- pkg/trunk/demos/test_2dnav_gazebo/set_goal.py 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/demos/test_2dnav_gazebo/set_goal.py 2009-08-08 01:30:20 UTC (rev 21110)
@@ -48,7 +48,7 @@
import rospy, rostest
from std_msgs.msg import String
from nav_robot_actions.msg import MoveBaseState
-from geometry_msgs.msg import Pose,Quaternion,Point, PoseWithRatesStamped, PoseStamped, PoseWithCovariance
+from geometry_msgs.msg import Pose,Quaternion,Point, PoseWithRatesStamped, PoseStamped, PoseWithCovarianceStamped
from robot_msgs.msg import PoseDot
from nav_msgs.msg import Odometry
import tf.transformations as tft
@@ -223,13 +223,13 @@
#pub_base = rospy.Publisher("cmd_vel", BaseVel)
pub_goal = rospy.Publisher("/move_base/activate", PoseStamped)
- pub_pose = rospy.Publisher("initialpose", PoseWithCovariance)
+ pub_pose = rospy.Publisher("initialpose", PoseWithCovarianceStamped)
rospy.Subscriber("base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
rospy.Subscriber("odom" , Odometry , self.odomInput)
rospy.Subscriber("base_bumper/info" , String , self.bumpedInput)
rospy.Subscriber("torso_lift_bumper/info", String , self.bumpedInput)
rospy.Subscriber("/move_base/feedback" , MoveBaseState , self.stateInput)
- rospy.Subscriber("/amcl_pose" , PoseWithCovariance , self.amclInput)
+ rospy.Subscriber("/amcl_pose" , PoseWithCovarianceStamped , self.amclInput)
# below only for debugging build 303, base not moving
rospy.Subscriber("cmd_vel" , PoseDot , self.cmd_velInput)
@@ -313,7 +313,7 @@
q = Quaternion(tmpq[0],tmpq[1],tmpq[2],tmpq[3])
pose = Pose(p,q)
print "publishing initialpose",h,p,COV[0]
- pub_pose.publish(PoseWithCovariance(h, pose,COV))
+ pub_pose.publish(PoseWithCovarianceStamped(h, PoseWithCovariance(pose,COV)))
else:
# send goal until state /move_base/feedback indicates goal is received
p = Point(self.target_x, self.target_y, 0)
Modified: pkg/trunk/sandbox/labeled_object_detector/test/test_nearest_action2.cpp
===================================================================
--- pkg/trunk/sandbox/labeled_object_detector/test/test_nearest_action2.cpp 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/sandbox/labeled_object_detector/test/test_nearest_action2.cpp 2009-08-08 01:30:20 UTC (rev 21110)
@@ -40,7 +40,7 @@
#include <ros/ros.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PoseStamped.h>
-#include <geometry_msgs/PoseWithCovariance.h>
+#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <gtest/gtest.h>
using namespace robot_msgs;
@@ -48,12 +48,12 @@
int count=0;
-void on_pose(robot_actions::ActionClient<PoseStamped, PoseStampedState, PoseStamped> &client,PoseWithCovarianceConstPtr pose)
+void on_pose(robot_actions::ActionClient<PoseStamped, PoseStampedState, PoseStamped> &client,PoseWithCovarianceStampedConstPtr pose)
{
ROS_INFO_STREAM("pose "<<count <<","<<pose);
PoseStamped goal;
- goal.pose=pose->pose;
+ goal.pose=pose->data.pose;
goal.header=pose->header;
PoseStamped feedback;
robot_actions::ResultStatus result = client.execute(goal, feedback, ros::Duration(5));
@@ -71,7 +71,7 @@
//duration.sleep();
ros::NodeHandle n_;
- ros::Subscriber s=n_.subscribe<PoseWithCovariance>("amcl_pose",1,boost::bind(&on_pose,client,_1));
+ ros::Subscriber s=n_.subscribe<PoseWithCovarianceStamped>("amcl_pose",1,boost::bind(&on_pose,client,_1));
ros::spin();
Modified: pkg/trunk/sandbox/webteleop/src/server.py
===================================================================
--- pkg/trunk/sandbox/webteleop/src/server.py 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/sandbox/webteleop/src/server.py 2009-08-08 01:30:20 UTC (rev 21110)
@@ -41,7 +41,7 @@
rosCoreUp = False
launchers = {}
-msgClasses = { '/initialpose' : geometry_msgs.msg.PoseWithCovariance,
+msgClasses = { '/initialpose' : geometry_msgs.msg.PoseWithCovarianceStamped,
'/move_base/activate' : geometry_msgs.msg.PoseStamped
}
Modified: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithCovarianceStamped.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithCovarianceStamped.msg 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithCovarianceStamped.msg 2009-08-08 01:30:20 UTC (rev 21110)
@@ -1,2 +1,2 @@
Header header
-PoseWithCovariance pose_with_covariance
+PoseWithCovariance data
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation.h
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation.h 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation.h 2009-08-08 01:30:20 UTC (rev 21110)
@@ -48,7 +48,7 @@
#include <tf/tf.h>
// msgs
-#include <geometry_msgs/PoseWithCovariance.h>
+#include <geometry_msgs/PoseWithCovarianceStamped.h>
// log files
#include <fstream>
@@ -106,7 +106,7 @@
/** get the filter posterior
* \param estimate the filter posterior as a pose with covariance
*/
- void getEstimate(geometry_msgs::PoseWithCovariance& estimate);
+ void getEstimate(geometry_msgs::PoseWithCovarianceStamped& estimate);
/** Add a sensor measurement to the measurement buffer
* \param meas the measurement to add
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 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation_node.h 2009-08-08 01:30:20 UTC (rev 21110)
@@ -50,7 +50,7 @@
#include "geometry_msgs/PoseWithRatesStamped.h"
#include "geometry_msgs/PoseStamped.h"
#include "robot_msgs/VOPose.h"
-#include "geometry_msgs/PoseWithCovariance.h"
+#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include <boost/thread/mutex.hpp>
@@ -108,7 +108,7 @@
OdomEstimation my_filter_;
// estimated robot pose message to send
- geometry_msgs::PoseWithCovariance output_;
+ geometry_msgs::PoseWithCovarianceStamped output_;
// robot state
tf::TransformListener robot_state_;
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp 2009-08-08 01:30:20 UTC (rev 21110)
@@ -334,8 +334,8 @@
transformer_.lookupTransform("base_footprint","odom", time, estimate);
};
- // get most recent filter posterior as PoseWithCovariance
- void OdomEstimation::getEstimate(geometry_msgs::PoseWithCovariance& estimate)
+ // get most recent filter posterior as PoseWithCovarianceStamped
+ void OdomEstimation::getEstimate(geometry_msgs::PoseWithCovarianceStamped& estimate)
{
// pose
Stamped<Transform> tmp;
@@ -344,7 +344,7 @@
return;
}
transformer_.lookupTransform("base_footprint","odom", ros::Time(), tmp);
- poseTFToMsg(tmp, estimate.pose);
+ poseTFToMsg(tmp, estimate.data.pose);
// header
estimate.header.stamp = tmp.stamp_;
@@ -354,7 +354,7 @@
SymmetricMatrix covar = filter_->PostGet()->CovarianceGet();
for (unsigned int i=0; i<6; i++)
for (unsigned int j=0; j<6; j++)
- estimate.covariance[6*i+j] = covar(i+1,j+1);
+ estimate.data.covariance[6*i+j] = covar(i+1,j+1);
};
// correct for angle overflow
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 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2009-08-08 01:30:20 UTC (rev 21110)
@@ -74,7 +74,7 @@
timer_ = node_.createTimer(ros::Duration(1.0/max(freq,1.0)), &OdomEstimationNode::spin, this);
// advertise our estimation
- pose_pub_ = node_.advertise<geometry_msgs::PoseWithCovariance>("~"+publish_name, 10);
+ pose_pub_ = node_.advertise<geometry_msgs::PoseWithCovarianceStamped>("~"+publish_name, 10);
// initialize
filter_stamp_ = Time::now();
@@ -303,7 +303,7 @@
{
// receive data
boost::mutex::scoped_lock lock(vel_mutex_);
- vel_desi_(1) = vel->vel.vx; vel_desi_(2) = vel->ang_vel.vz;
+ vel_desi_(1) = vel->linear.x; vel_desi_(2) = vel->angular.z;
// active
//if (!vel_active_) vel_active_ = true;
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp 2009-08-08 01:30:20 UTC (rev 21110)
@@ -37,7 +37,7 @@
#include <string>
#include <gtest/gtest.h>
#include "ros/node.h"
-#include "geometry_msgs/PoseWithCovariance.h"
+#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include "geometry_msgs/PoseWithRatesStamped.h"
@@ -56,7 +56,7 @@
class TestEKF : public testing::Test
{
public:
- geometry_msgs::PoseWithCovariance ekf_msg_, ekf_begin_;
+ geometry_msgs::PoseWithCovarianceStamped ekf_msg_, ekf_begin_;
geometry_msgs::PoseWithRatesStamped odom_msg_;
double ekf_counter_, odom_counter_;
Time ekf_time_begin_, odom_time_begin_;
@@ -142,20 +142,20 @@
EXPECT_GT(Duration(ekf_msg_.header.stamp - odom_msg_.header.stamp).toSec(), -1.0);
// check filter result
- EXPECT_GT(ekf_begin_.pose.position.x, 0.038043 - EPS_trans);
- EXPECT_LT(ekf_begin_.pose.position.x, 0.038043 + EPS_trans);
- EXPECT_GT(ekf_begin_.pose.position.y, -0.001618 - EPS_trans);
- EXPECT_LT(ekf_begin_.pose.position.y, -0.001618 + EPS_trans);
- EXPECT_GT(ekf_begin_.pose.position.z, 0.000000 - EPS_trans);
- EXPECT_LT(ekf_begin_.pose.position.z, 0.000000 + EPS_trans);
- EXPECT_GT(ekf_begin_.pose.orientation.x, 0.000000 - EPS_rot);
- EXPECT_LT(ekf_begin_.pose.orientation.x, 0.000000 + EPS_rot);
- EXPECT_GT(ekf_begin_.pose.orientation.y, 0.000000 - EPS_rot);
- EXPECT_LT(ekf_begin_.pose.orientation.y, 0.000000 + EPS_rot);
- EXPECT_GT(ekf_begin_.pose.orientation.z, 0.088400 - EPS_rot);
- EXPECT_LT(ekf_begin_.pose.orientation.z, 0.088400 + EPS_rot);
- EXPECT_GT(ekf_begin_.pose.orientation.w, 0.996085 - EPS_rot);
- EXPECT_LT(ekf_begin_.pose.orientation.w, 0.996085 + EPS_rot);
+ EXPECT_GT(ekf_begin_.data.pose.position.x, 0.038043 - EPS_trans);
+ EXPECT_LT(ekf_begin_.data.pose.position.x, 0.038043 + EPS_trans);
+ EXPECT_GT(ekf_begin_.data.pose.position.y, -0.001618 - EPS_trans);
+ EXPECT_LT(ekf_begin_.data.pose.position.y, -0.001618 + EPS_trans);
+ EXPECT_GT(ekf_begin_.data.pose.position.z, 0.000000 - EPS_trans);
+ EXPECT_LT(ekf_begin_.data.pose.position.z, 0.000000 + EPS_trans);
+ EXPECT_GT(ekf_begin_.data.pose.orientation.x, 0.000000 - EPS_rot);
+ EXPECT_LT(ekf_begin_.data.pose.orientation.x, 0.000000 + EPS_rot);
+ EXPECT_GT(ekf_begin_.data.pose.orientation.y, 0.000000 - EPS_rot);
+ EXPECT_LT(ekf_begin_.data.pose.orientation.y, 0.000000 + EPS_rot);
+ EXPECT_GT(ekf_begin_.data.pose.orientation.z, 0.088400 - EPS_rot);
+ EXPECT_LT(ekf_begin_.data.pose.orientation.z, 0.088400 + EPS_rot);
+ EXPECT_GT(ekf_begin_.data.pose.orientation.w, 0.996085 - EPS_rot);
+ EXPECT_LT(ekf_begin_.data.pose.orientation.w, 0.996085 + EPS_rot);
SUCCEED();
}
Modified: pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp 2009-08-08 01:30:20 UTC (rev 21110)
@@ -37,7 +37,7 @@
// Messages that I need
#include "sensor_msgs/LaserScan.h"
-#include "geometry_msgs/PoseWithCovariance.h"
+#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include "geometry_msgs/PoseArray.h"
#include "geometry_msgs/Pose.h"
#include "nav_msgs/GetMap.h"
@@ -106,7 +106,7 @@
static pf_vector_t uniformPoseGenerator(void* arg);
// incoming messages
- geometry_msgs::PoseWithCovariance initial_pose_;
+ geometry_msgs::PoseWithCovarianceStamped initial_pose_;
// Message callbacks
bool globalLocalizationCallback(std_srvs::Empty::Request& req,
@@ -126,7 +126,7 @@
ros::Time save_pose_last_time;
ros::Duration save_pose_period;
- geometry_msgs::PoseWithCovariance last_published_pose;
+ geometry_msgs::PoseWithCovarianceStamped last_published_pose;
map_t* map_;
char* mapdata;
@@ -319,7 +319,7 @@
laser_->SetModelLikelihoodField(z_hit, z_rand, sigma_hit,
laser_likelihood_max_dist);
- ros::Node::instance()->advertise<geometry_msgs::PoseWithCovariance>("amcl_pose",2);
+ ros::Node::instance()->advertise<geometry_msgs::PoseWithCovarianceStamped>("amcl_pose",2);
ros::Node::instance()->advertise<geometry_msgs::PoseArray>("particlecloud",2);
ros::Node::instance()->advertise<visualization_msgs::Polyline>("gui_laser",2);
ros::Node::instance()->advertiseService("global_localization",
@@ -664,15 +664,15 @@
puts("");
*/
- geometry_msgs::PoseWithCovariance p;
+ geometry_msgs::PoseWithCovarianceStamped p;
// Fill in the header
p.header.frame_id = "map";
p.header.stamp = laser_scan->header.stamp;
// Copy in the pose
- p.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
- p.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
+ p.data.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
+ p.data.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
tf::quaternionTFToMsg(tf::Quaternion(hyps[max_weight_hyp].pf_pose_mean.v[2], 0.0, 0.0),
- p.pose.orientation);
+ p.data.pose.orientation);
// Copy in the covariance, converting from 3-D to 6-D
pf_sample_set_t* set = pf_->sets + pf_->current_set;
for(int i=0; i<2; i++)
@@ -682,13 +682,13 @@
// Report the overall filter covariance, rather than the
// covariance for the highest-weight cluster
//p.covariance[6*i+j] = hyps[max_weight_hyp].pf_pose_cov.m[i][j];
- p.covariance[6*i+j] = set->cov.m[i][j];
+ p.data.covariance[6*i+j] = set->cov.m[i][j];
}
}
// Report the overall filter covariance, rather than the
// covariance for the highest-weight cluster
//p.covariance[6*3+3] = hyps[max_weight_hyp].pf_pose_cov.m[2][2];
- p.covariance[6*3+3] = set->cov.m[2][2];
+ p.data.covariance[6*3+3] = set->cov.m[2][2];
/*
printf("cov:\n");
@@ -821,11 +821,11 @@
ros::Node::instance()->setParam("~initial_pose_y", map_pose.getOrigin().y());
ros::Node::instance()->setParam("~initial_pose_a", yaw);
ros::Node::instance()->setParam("~initial_cov_xx",
- last_published_pose.covariance[6*0+0]);
+ last_published_pose.data.covariance[6*0+0]);
ros::Node::instance()->setParam("~initial_cov_yy",
- last_published_pose.covariance[6*1+1]);
+ last_published_pose.data.covariance[6*1+1]);
ros::Node::instance()->setParam("~initial_cov_aa",
- last_published_pose.covariance[6*3+3]);
+ last_published_pose.data.covariance[6*3+3]);
save_pose_last_time = now;
}
}
@@ -861,7 +861,7 @@
}
tf::Pose pose_old, pose_new;
- tf::poseMsgToTF(initial_pose_.pose, pose_old);
+ tf::poseMsgToTF(initial_pose_.data.pose, pose_old);
pose_new = tx_odom.inverse() * pose_old;
ROS_INFO("Setting pose (%.6f): %.3f %.3f %.3f",
@@ -880,10 +880,10 @@
{
for(int j=0; j<2; j++)
{
- pf_init_pose_cov.m[i][j] = initial_pose_.covariance[6*i+j];
+ pf_init_pose_cov.m[i][j] = initial_pose_.data.covariance[6*i+j];
}
}
- pf_init_pose_cov.m[2][2] = initial_pose_.covariance[6*3+3];
+ pf_init_pose_cov.m[2][2] = initial_pose_.data.covariance[6*3+3];
pf_mutex_.lock();
pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
Modified: pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
===================================================================
--- pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-08 01:30:20 UTC (rev 21110)
@@ -59,7 +59,7 @@
- @b "base_pose_ground_truth" geometry_msgs/PoseWithRatesStamped : robot's odometric pose. Only the position information is used (velocity is ignored).
Publishes to (name / type):
-- @b "amcl_pose" geometry_msgs/PoseWithCovariance : robot's estimated pose in the map, with covariance
+- @b "amcl_pose" geometry_msgs/PoseWithCovarianceStamped : robot's estimated pose in the map, with covariance
- @b "particlecloud" geometry_msgs/PoseArray : fake set of poses being maintained by the filter (one paricle only).
<hr>
@@ -75,7 +75,7 @@
#include <geometry_msgs/PoseWithRatesStamped.h>
#include <geometry_msgs/PoseArray.h>
-#include <geometry_msgs/PoseWithCovariance.h>
+#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <angles/angles.h>
@@ -91,7 +91,7 @@
public:
FakeOdomNode(void) : ros::Node("fake_localization")
{
- advertise<geometry_msgs::PoseWithCovariance>("amcl_pose",1);
+ advertise<geometry_msgs::PoseWithCovarianceStamped>("amcl_pose",1);
advertise<geometry_msgs::PoseArray>("particlecloud",1);
m_tfServer = new tf::TransformBroadcaster();
m_tfListener = new tf::TransformListener(*this);
@@ -141,7 +141,7 @@
geometry_msgs::PoseWithRatesStamped m_basePosMsg;
geometry_msgs::PoseArray m_particleCloud;
- geometry_msgs::PoseWithCovariance m_currentPos;
+ geometry_msgs::PoseWithCovarianceStamped m_currentPos;
//parameter for what odom to use
std::string odom_frame_id_;
@@ -205,16 +205,16 @@
// Publish localized pose
m_currentPos.header = message->header;
m_currentPos.header.frame_id = "/map"; ///\todo fixme hack
- m_currentPos.pose.position.x = x;
- m_currentPos.pose.position.y = y;
+ m_currentPos.data.pose.position.x = x;
+ m_currentPos.data.pose.position.y = y;
// Leave z as zero
tf::quaternionTFToMsg(tf::Quaternion(yaw, 0.0, 0.0),
- m_currentPos.pose.orientation);
+ m_currentPos.data.pose.orientation);
// Leave covariance as zero
publish("amcl_pose", m_currentPos);
// The particle cloud is the current position. Quite convenient.
- m_particleCloud.poses[0] = m_currentPos.pose;
+ m_particleCloud.poses[0] = m_currentPos.data.pose;
publish("particlecloud", m_particleCloud);
}
};
Modified: pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h
===================================================================
--- pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h 2009-08-08 01:30:20 UTC (rev 21110)
@@ -35,7 +35,7 @@
#include "geometry_msgs/PoseArray.h"
#include "geometry_msgs/PoseStamped.h"
#include "visualization_msgs/Polyline.h"
-#include "geometry_msgs/PoseWithCovariance.h"
+#include "geometry_msgs/PoseWithCovarianceStamped.h"
#include <OGRE/OgreTexture.h>
#include <OGRE/OgreMaterial.h>
Modified: pkg/trunk/stacks/navigation/nav_view/src/nav_view/tools.cpp
===================================================================
--- pkg/trunk/stacks/navigation/nav_view/src/nav_view/tools.cpp 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/navigation/nav_view/src/nav_view/tools.cpp 2009-08-08 01:30:20 UTC (rev 21110)
@@ -88,7 +88,7 @@
, is_goal_( goal )
{
goal_pub_ = nh_.advertise<geometry_msgs::PoseStamped>("goal", 1);
- pose_pub_ = nh_.advertise<geometry_msgs::PoseWithCovariance>("initialpose", 1);
+ pose_pub_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 1);
}
PoseTool::~PoseTool()
@@ -171,14 +171,14 @@
}
else
{
- geometry_msgs::PoseWithCovariance pose;
- pose.pose.position.x = pos_.x;
- pose.pose.position.y = pos_.y;
+ geometry_msgs::PoseWithCovarianceStamped pose;
+ pose.data.pose.position.x = pos_.x;
+ pose.data.pose.position.y = pos_.y;
tf::quaternionTFToMsg(tf::Quaternion(angle, 0.0, 0.0),
- pose.pose.orientation);
- pose.covariance[6*0+0] = 0.5 * 0.5;
- pose.covariance[6*1+1] = 0.5 * 0.5;
- pose.covariance[6*3+3] = M_PI/12.0 * M_PI/12.0;
+ pose.data.pose.orientation);
+ pose.data.covariance[6*0+0] = 0.5 * 0.5;
+ pose.data.covariance[6*1+1] = 0.5 * 0.5;
+ pose.data.covariance[6*3+3] = M_PI/12.0 * M_PI/12.0;
ROS_INFO( "setting pose: %.3f %.3f %.3f\n", pos_.x, pos_.y, angle );
pose_pub_.publish( pose );
}
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/tools/pose_tool.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/tools/pose_tool.cpp 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/tools/pose_tool.cpp 2009-08-08 01:30:20 UTC (rev 21110)
@@ -37,7 +37,7 @@
#include "ogre_tools/wx_ogre_render_window.h"
#include <geometry_msgs/PoseStamped.h>
-#include <geometry_msgs/PoseWithCovariance.h>
+#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <OGRE/OgreRay.h>
#include <OGRE/OgrePlane.h>
@@ -61,7 +61,7 @@
arrow_->getSceneNode()->setVisible( false );
goal_pub_ = nh_.advertise<geometry_msgs::PoseStamped>("goal", 1);
- pose_pub_ = nh_.advertise<geometry_msgs::PoseWithCovariance>("initialpose", 1);
+ pose_pub_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 1);
}
PoseTool::~PoseTool()
@@ -159,14 +159,14 @@
}
else
{
- geometry_msgs::PoseWithCovariance pose;
- pose.pose.position.x = robot_pos_transformed.x();
- pose.pose.position.y = robot_pos_transformed.y();
+ geometry_msgs::PoseWithCovarianceStamped pose;
+ pose.data.pose.position.x = robot_pos_transformed.x();
+ pose.data.pose.position.y = robot_pos_transformed.y();
tf::quaternionTFToMsg(tf::Quaternion(angle, 0.0, 0.0),
- pose.pose.orientation);
- pose.covariance[6*0+0] = 0.5 * 0.5;
- pose.covariance[6*1+1] = 0.5 * 0.5;
- pose.covariance[6*3+3] = M_PI/12.0 * M_PI/12.0;
+ pose.data.pose.orientation);
+ pose.data.covariance[6*0+0] = 0.5 * 0.5;
+ pose.data.covariance[6*1+1] = 0.5 * 0.5;
+ pose.data.covariance[6*3+3] = M_PI/12.0 * M_PI/12.0;
ROS_INFO("Setting pose: %.3f %.3f %.3f [frame=%s]",
robot_pos_transformed.x(),
robot_pos_transformed.y(),
Modified: pkg/trunk/vision/vslam/nodes/picmap.py
===================================================================
--- pkg/trunk/vision/vslam/nodes/picmap.py 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/vision/vslam/nodes/picmap.py 2009-08-08 01:30:20 UTC (rev 21110)
@@ -107,7 +107,7 @@
#self.pub = rospy.Publisher("/picmap_pose", vslam.msg.Picmap)
rospy.Subscriber('/stereo/raw_stereo', sensor_msgs.msg.RawStereo, self.handle_raw_stereo_queue, queue_size=2, buff_size=7000000)
- rospy.Subscriber('/amcl_pose', robot_msgs.msg.PoseWithCovariance, self.handle_amcl_pose)
+ rospy.Subscriber('/amcl_pose', robot_msgs.msg.PoseWithCovarianceStamped, self.handle_amcl_pose)
rospy.Subscriber('/tf_message', tf.msg.tfMessage, self.handle_tf_queue)
self.pmlock = threading.Lock()
@@ -191,8 +191,8 @@
def handle_amcl_pose(self, msg):
if self.vo:
print "handle_amcl_pose(", msg, ")"
- happy = max([msg.covariance[0], msg.covariance[7]]) < 0.003
- print "picmap node got amcl", msg.header.stamp.to_seconds(), msg.covariance[0], msg.covariance[7], "happy", happy
+ happy = max([msg.data.covariance[0], msg.data.covariance[7]]) < 0.003
+ print "picmap node got amcl", msg.header.stamp.to_seconds(), msg.data.covariance[0], msg.data.covariance[7], "happy", happy
self.pmlock.acquire()
self.pm.newLocalization(msg.header.stamp.to_seconds(), happy)
self.pmlock.release()
Modified: pkg/trunk/vision/vslam/nodes/roadmap.py
===================================================================
--- pkg/trunk/vision/vslam/nodes/roadmap.py 2009-08-08 01:21:58 UTC (rev 21109)
+++ pkg/trunk/vision/vslam/nodes/roadmap.py 2009-08-08 01:30:20 UTC (rev 21110)
@@ -246,7 +246,7 @@
def __init__(self, args):
rospy.init_node('roadmap_server')
self.pub = rospy.Publisher("roadmap", vslam.msg.Roadmap)
- rospy.Subscriber('amcl_pose', robot_msgs.msg.PoseWithCovariance, self.handle_localizedpose)
+ rospy.Subscriber('amcl_pose', robot_msgs.msg.PoseWithCovarianceStamped, self.handle_localizedpose)
self.updated = None
rospy.Subscriber('time', roslib.msg.Time, self.handle_time)
self.nodes = []
@@ -259,9 +259,9 @@
self.send_map(msg.header.stamp)
def handle_localizedpose(self, msg):
- th = tf.transformations.euler_from_quaternion([msg.pose.o...
[truncated message content] |
|
From: <bla...@us...> - 2009-08-08 01:39:03
|
Revision: 21112
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21112&view=rev
Author: blaisegassend
Date: 2009-08-08 01:38:54 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
Changed DiagnosticValue to KeyValue
Modified Paths:
--------------
pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
pkg/trunk/drivers/ups/apcupsd_node/scripts/monitor
pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
pkg/trunk/pr2/life_test/simple_test/fake_test.py
pkg/trunk/pr2/life_test/src/life_test/life_test.py
pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py
pkg/trunk/stacks/common_msgs/diagnostic_msgs/migration_rules/migration_rules.py
pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticStatus.msg
pkg/trunk/stacks/common_msgs/test_common_msgs/mainpage.dox
pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticMessage.saved
pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticStatus.saved
pkg/trunk/stacks/common_msgs/test_common_msgs/test/test_common_msgs_migration.py
pkg/trunk/stacks/driver_common/dynamic_reconfigure/templates/ConfigReconfigurator.h
pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py
pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/log_runtime_messages
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/monitor
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/test_high_level
pkg/trunk/stacks/hardware_test/runtime_monitor/src/runtime_monitor/monitor_panel.py
pkg/trunk/stacks/hardware_test/runtime_monitor/testmonitor.py
pkg/trunk/stacks/mechanism/mechanism_control/scripts/joints_to_diagnostics.py
pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/wg0x.h
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ek1122.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ethercat_hardware.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg014.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg0x.cpp
pkg/trunk/stacks/pr2_power_drivers/ocean_battery_driver/scripts/monitor
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node.cpp
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node_simulator.cpp
Modified: pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py
===================================================================
--- pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -66,7 +66,7 @@
# Display the time, just so that something is always updating
#timestamp = mech_state.header.stamp.to_seconds()
- #diag.values.append(DiagnosticValue(value=timestamp, label="Time"))
+ #diag.values.append(KeyValue(value=timestamp, label="Time"))
# Display the actuator and joint names for this monitor
diag.strings.append(DiagnosticString(value=self._actuator, label="Actuator"))
@@ -79,7 +79,7 @@
if act_exists :
cal_flag = mech_state.actuator_states[act_names.index(self._actuator)].calibration_reading
- diag.values.append(DiagnosticValue(value=(1 if act_exists else 0),
+ diag.values.append(KeyValue(value=(1 if act_exists else 0),
label="Actuator Exists"))
joint_names = [x.name for x in mech_state.joint_states]
@@ -87,7 +87,7 @@
if joint_exists :
joint_pos = mech_state.joint_states[joint_names.index(self._joint)].position
- diag.values.append(DiagnosticValue(value=(1 if joint_exists else 0),
+ diag.values.append(KeyValue(value=(1 if joint_exists else 0),
label="Joint Exists"))
if not (act_exists and joint_exists) :
@@ -95,10 +95,10 @@
diag.message = "Error finding joint and actuator"
return diag
- diag.values.append(DiagnosticValue(value=cal_flag,
+ diag.values.append(KeyValue(value=cal_flag,
label="Flag State"))
- diag.values.append(DiagnosticValue(value=joint_pos,
+ diag.values.append(KeyValue(value=joint_pos,
label="Joint Position"))
# Call the predicate to see what the result is for this joint
@@ -116,11 +116,11 @@
diag.strings.append(DiagnosticString(value=self._flag_lookup[sample_result],
label="Flag Check Result"))
- diag.values.append(DiagnosticValue(value=flag_oks,
+ diag.values.append(KeyValue(value=flag_oks,
label="Flag OKs"))
- diag.values.append(DiagnosticValue(value=flag_deadbands,
+ diag.values.append(KeyValue(value=flag_deadbands,
label="Flag Deadbands"))
- diag.values.append(DiagnosticValue(value=flag_errors,
+ diag.values.append(KeyValue(value=flag_errors,
label="Flag Errors"))
if flag_errors > 0 :
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -690,10 +690,10 @@
cmd.set_velocity_size(1);
vector<diagnostic_msgs::DiagnosticStatus> statuses;
- vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::KeyValue> values;
vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
status.name = service_prefix_;
status.level = 0;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -281,11 +281,11 @@
diagnostic_msgs::DiagnosticMessage message;
std::vector<diagnostic_msgs::DiagnosticStatus> statuses;
- std::vector<diagnostic_msgs::DiagnosticValue> values;
+ std::vector<diagnostic_msgs::KeyValue> values;
std::vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
status.name = ros_node_.getName();
status.message = control_state_;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -932,10 +932,10 @@
cmd.set_velocity_size(1);
vector<diagnostic_msgs::DiagnosticStatus> statuses;
- vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::KeyValue> values;
vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
status.name = "Whole Body Trajectory Controller";
status.level = 0;
Modified: pkg/trunk/drivers/ups/apcupsd_node/scripts/monitor
===================================================================
--- pkg/trunk/drivers/ups/apcupsd_node/scripts/monitor 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/drivers/ups/apcupsd_node/scripts/monitor 2009-08-08 01:38:54 UTC (rev 21112)
@@ -48,7 +48,7 @@
import rospy
from robot_msgs.msg import BatteryState
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
NAME = 'monitor'
Modified: pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -340,10 +340,10 @@
diagnostic_msgs::DiagnosticStatus DoorReactivePlanner::getDiagnostics()
{
- vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::KeyValue> values;
vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
status.name = "Door Reactive Planner";
status.level = 0;
Modified: pkg/trunk/pr2/life_test/simple_test/fake_test.py
===================================================================
--- pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -39,7 +39,7 @@
import wx
import sys
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
from std_srvs.srv import *
from mechanism_msgs.msg import MechanismState, JointState, ActuatorState
Modified: pkg/trunk/pr2/life_test/src/life_test/life_test.py
===================================================================
--- pkg/trunk/pr2/life_test/src/life_test/life_test.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/life_test/src/life_test/life_test.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -49,7 +49,7 @@
import rospy
from std_srvs.srv import *
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
# Stuff from life_test package
from msg import TestStatus
Modified: pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py
===================================================================
--- pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -101,9 +101,9 @@
diag.strings.append(DiagnosticString(value=self._actuator, label="Actuator"))
diag.strings.append(DiagnosticString(value=str(self._positive), label="Positive Joint"))
diag.strings.append(DiagnosticString(value=str(self._continuous), label="Continuous Joint"))
- diag.values.append(DiagnosticValue(value=float(self._ref_position), label="Reference Position"))
- diag.values.append(DiagnosticValue(value=float(self._deadband), label="Deadband"))
- diag.values.append(DiagnosticValue(value=float(self._rx_count), label="Mech State RX Count"))
+ diag.values.append(KeyValue(value=float(self._ref_position), label="Reference Position"))
+ diag.values.append(KeyValue(value=float(self._deadband), label="Deadband"))
+ diag.values.append(KeyValue(value=float(self._rx_count), label="Mech State RX Count"))
# Check if we can find both the joint and actuator
@@ -150,17 +150,17 @@
diag.strings.insert(0, DiagnosticString(value=diag.message, label='Transmission Status'))
diag.strings.insert(1, DiagnosticString(value=reading_msg, label='Current Reading'))
diag.strings.append(DiagnosticString(value=str(calibrated), label='Is Calibrated'))
- diag.values.append(DiagnosticValue(value=cal_reading, label='Calibration Reading'))
- diag.values.append(DiagnosticValue(value=position, label='Joint Position'))
+ diag.values.append(KeyValue(value=cal_reading, label='Calibration Reading'))
+ diag.values.append(KeyValue(value=position, label='Joint Position'))
- diag.values.append(DiagnosticValue(value=self._num_errors, label='Total Errors'))
- diag.values.append(DiagnosticValue(value=self._num_errors_since_reset, label='Errors Since Reset'))
+ diag.values.append(KeyValue(value=self._num_errors, label='Total Errors'))
+ diag.values.append(KeyValue(value=self._num_errors_since_reset, label='Errors Since Reset'))
self._max_position = max(self._max_position, position)
- diag.values.append(DiagnosticValue(value = self._max_position, label='Max Obs. Position'))
+ diag.values.append(KeyValue(value = self._max_position, label='Max Obs. Position'))
self._min_position = min(self._min_position, position)
- diag.values.append(DiagnosticValue(value = self._min_position, label='Min Obs. Position'))
+ diag.values.append(KeyValue(value = self._min_position, label='Min Obs. Position'))
return diag, self._ok
Modified: pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py
===================================================================
--- pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -95,7 +95,7 @@
tmp = ipmi_val.rstrip(' degrees C').lstrip()
if unicode(tmp).isnumeric():
temperature = float(tmp)
- diag_vals.append(DiagnosticValue(label = name, value = temperature))
+ diag_vals.append(KeyValue(label = name, value = temperature))
cpu_name = name.split()[0]
if temperature >= 80 and temperature < 85:
@@ -121,7 +121,7 @@
tmp = ipmi_val.rstrip(' degrees C').lstrip()
if unicode(tmp).isnumeric():
temperature = float(tmp)
- diag_vals.append(DiagnosticValue(label = name, value = temperature))
+ diag_vals.append(KeyValue(label = name, value = temperature))
dev_name = name.split()[0]
if temperature >= 60 and temperature < 70:
@@ -140,7 +140,7 @@
rpm = ipmi_val.rstrip(' RPM').lstrip()
if unicode(rpm).isnumeric():
rpm = float(rpm)
- diag_vals.append(DiagnosticValue(label = name, value = rpm))
+ diag_vals.append(KeyValue(label = name, value = rpm))
else:
diag_strs.append(DiagnosticString(label = name, value = ipmi_val))
@@ -189,7 +189,7 @@
tmp = stdout.strip()
if unicode(tmp).isnumeric():
temp = float(tmp) / 1000
- diag_vals.append(DiagnosticValue(label = 'Core %d Temp' % index, value = temp))
+ diag_vals.append(KeyValue(label = 'Core %d Temp' % index, value = temp))
if temp >= 85 and temp < 90:
diag_level = max(diag_level, 1)
@@ -233,7 +233,7 @@
speed = words[1].strip().split('.')[0]
if unicode(speed).isnumeric():
mhz = float(speed)
- vals.append(DiagnosticValue(label = 'Core %d Speed' % index, value = mhz))
+ vals.append(KeyValue(label = 'Core %d Speed' % index, value = mhz))
if mhz < 2240 and mhz > 2150:
lvl = max(lvl, 1)
@@ -279,10 +279,10 @@
load15 = float(upvals[-1])
num_users = float(upvals[-7])
- vals.append(DiagnosticValue(label = '1 min Load Average', value = load1))
- vals.append(DiagnosticValue(label = '5 min Load Average', value = load5))
- vals.append(DiagnosticValue(label = '15 min Load Average', value = load15))
- vals.append(DiagnosticValue(label = 'Number of Users', value = num_users))
+ vals.append(KeyValue(label = '1 min Load Average', value = load1))
+ vals.append(KeyValue(label = '5 min Load Average', value = load5))
+ vals.append(KeyValue(label = '15 min Load Average', value = load15))
+ vals.append(KeyValue(label = 'Number of Users', value = num_users))
if load1 > 25 or load5 > 18:
level = 1
@@ -321,9 +321,9 @@
used_mem = float(data[2])
free_mem = float(data[3])
- values.append(DiagnosticValue(label = 'Total Memory', value = total_mem))
- values.append(DiagnosticValue(label = 'Used Memory', value = used_mem))
- values.append(DiagnosticValue(label = 'Free Memory', value = free_mem))
+ values.append(KeyValue(label = 'Total Memory', value = total_mem))
+ values.append(KeyValue(label = 'Used Memory', value = used_mem))
+ values.append(KeyValue(label = 'Free Memory', value = free_mem))
level = 0
if free_mem < 10:
@@ -374,10 +374,10 @@
nice = float(lst[4])
system = float(lst[5])
- vals.append(DiagnosticValue(label = 'CPU %s User' % cpu_name, value = user))
- vals.append(DiagnosticValue(label = 'CPU %s Nice' % cpu_name, value = nice))
- vals.append(DiagnosticValue(label = 'CPU %s System' % cpu_name, value = system))
- vals.append(DiagnosticValue(label = 'CPU %s Idle' % cpu_name, value = idle))
+ vals.append(KeyValue(label = 'CPU %s User' % cpu_name, value = user))
+ vals.append(KeyValue(label = 'CPU %s Nice' % cpu_name, value = nice))
+ vals.append(KeyValue(label = 'CPU %s System' % cpu_name, value = system))
+ vals.append(KeyValue(label = 'CPU %s Idle' % cpu_name, value = idle))
core_level = 0
if user + nice > 75.0:
@@ -432,7 +432,7 @@
stat.strings.pop(0)
stat.values.pop(0)
stat.strings.insert(0, DiagnosticString(label = 'Update Status', value = stale_status))
- stat.values.insert(0, DiagnosticValue(label = 'Time Since Update', value = time_since_update))
+ stat.values.insert(0, KeyValue(label = 'Time Since Update', value = time_since_update))
class CPUMonitor():
def __init__(self, hostname):
@@ -455,7 +455,7 @@
self._temp_stat.hardware_id = hostname
self._temp_stat.message = 'No Data'
self._temp_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._temp_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000 )]
+ self._temp_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
self._usage_stat = DiagnosticStatus()
self._usage_stat.name = '%s CPU Usage' % hostname
@@ -463,7 +463,7 @@
self._usage_stat.hardware_id = hostname
self._usage_stat.message = 'No Data'
self._usage_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._usage_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000 )]
+ self._usage_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
self._nfs_stat = DiagnosticStatus()
self._nfs_stat.name = '%s NFS I/O' % hostname
@@ -471,7 +471,7 @@
self._nfs_stat.hardware_id = hostname
self._nfs_stat.message = 'No Data'
self._nfs_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._nfs_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000 )]
+ self._nfs_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
self._last_temp_time = 0
self._last_usage_time = 0
@@ -510,7 +510,7 @@
nfs_level = 0
msg = 'OK'
strs = [ DiagnosticString(label = 'Update Status', value = 'OK' )]
- vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 )]
+ vals = [ KeyValue(label = 'Time Since Last Update', value = 0 )]
try:
p = subprocess.Popen('iostat -n',
@@ -535,17 +535,17 @@
r_blk_srv = float(lst[5])
w_blk_srv = float(lst[6])
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Read Blks/s' % file_sys, value=read_blk))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Write Blks/s' % file_sys, value=write_blk))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Read Blk dir/s' % file_sys, value=read_blk_dir))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Write Blks dir/s' % file_sys, value=write_blk_dir))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Read Blks srv/s' % file_sys, value=r_blk_srv))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Write Blks srv/s' % file_sys, value=w_blk_srv))
except Exception, e:
@@ -580,7 +580,7 @@
return
diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
- diag_vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 ) ]
+ diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 ) ]
diag_msgs = []
diag_level = 0
@@ -634,7 +634,7 @@
diag_level = 0
diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
- diag_vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 )]
+ diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 )]
# Check mpstat
mp_level, mp_vals, mp_strs = check_mpstat()
Modified: pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py
===================================================================
--- pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -110,7 +110,7 @@
stat.strings.pop(0)
stat.values.pop(0)
stat.strings.insert(0, DiagnosticString(label = 'Update Status', value = stale_status))
- stat.values.insert(0, DiagnosticValue(label = 'Time Since Update', value = time_since_update))
+ stat.values.insert(0, KeyValue(label = 'Time Since Update', value = time_since_update))
class hdMonitor():
def __init__(self, hostname, home_dir = ''):
@@ -130,7 +130,7 @@
self._temp_stat.hardware_id = hostname
self._temp_stat.message = 'No Data'
self._temp_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._temp_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000 )]
+ self._temp_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
if self._home_dir != '':
self._usage_stat = DiagnosticStatus()
@@ -138,7 +138,7 @@
self._usage_stat.hardware_id = hostname
self._usage_stat.name = '%s HD Usage' % hostname
self._usage_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._usage_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000) ]
+ self._usage_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000) ]
self.check_disk_usage()
self._last_temp_time = 0
@@ -170,7 +170,7 @@
return
diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
- diag_vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 ) ]
+ diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 ) ]
diag_level = 0
diag_message = 'OK'
@@ -188,7 +188,7 @@
diag_strs.append(DiagnosticString(label = 'Disk %d Temp Status' % index, value = temp_dict[temp_level]))
diag_strs.append(DiagnosticString(label = 'Disk %d Mount Pt.' % index, value = drives[index]))
diag_strs.append(DiagnosticString(label = 'Disk %d Device ID' % index, value = makes[index]))
- diag_vals.append(DiagnosticValue(label = 'Disk %d Temp' % index, value = temp))
+ diag_vals.append(KeyValue(label = 'Disk %d Temp' % index, value = temp))
if not temp_ok:
diag_level = 2
@@ -229,7 +229,7 @@
return
diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
- diag_vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 ) ]
+ diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 ) ]
diag_level = 0
diag_message = 'OK'
Modified: pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py
===================================================================
--- pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -34,7 +34,7 @@
import roslib
roslib.load_manifest('pr2_computer_monitor')
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
import sys
import rospy
import socket
Modified: pkg/trunk/stacks/common_msgs/diagnostic_msgs/migration_rules/migration_rules.py
===================================================================
--- pkg/trunk/stacks/common_msgs/diagnostic_msgs/migration_rules/migration_rules.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/common_msgs/diagnostic_msgs/migration_rules/migration_rules.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -4,11 +4,11 @@
byte level #(OK=0, WARN=1, ERROR=2)
string name # a description of the test/component reporting
string message # a description of the status
-DiagnosticValue[] values # an array of values associated with the status
+KeyValue[] values # an array of values associated with the status
DiagnosticString[] strings # an array of string associated with the status
================================================================================
-MSG: diagnostic_msgs/DiagnosticValue
+MSG: diagnostic_msgs/KeyValue
float32 value # a value to track over time
string label # what to label this value when viewing
@@ -24,11 +24,11 @@
string name # a description of the test/component reporting
string message # a description of the status
string hardware_id # a hardware unique string
-DiagnosticValue[] values # an array of values associated with the status
+KeyValue[] values # an array of values associated with the status
DiagnosticString[] strings # an array of string associated with the status
================================================================================
-MSG: diagnostic_msgs/DiagnosticValue
+MSG: diagnostic_msgs/KeyValue
float32 value # a value to track over time
string label # what to label this value when viewing
@@ -40,7 +40,7 @@
order = 0
migrated_types = [
- ("DiagnosticValue","DiagnosticValue"),
+ ("KeyValue","DiagnosticValue"),
("DiagnosticString","DiagnosticString"),]
valid = True
@@ -50,6 +50,6 @@
new_msg.name = old_msg.name
new_msg.message = old_msg.message
new_msg.hardware_id = 'NONE'
- self.migrate_array(old_msg.values, new_msg.values, "DiagnosticValue")
+ self.migrate_array(old_msg.values, new_msg.values, "KeyValue")
self.migrate_array(old_msg.strings, new_msg.strings, "DiagnosticString")
Modified: pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticStatus.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticStatus.msg 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticStatus.msg 2009-08-08 01:38:54 UTC (rev 21112)
@@ -2,5 +2,5 @@
string name # a description of the test/component reporting
string message # a description of the status
string hardware_id # a hardware unique string
-DiagnosticValue[] values # an array of values associated with the status
+KeyValue[] values # an array of values associated with the...
[truncated message content] |
|
From: <wa...@us...> - 2009-08-08 03:16:05
|
Revision: 21122
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21122&view=rev
Author: wattsk
Date: 2009-08-08 03:15:54 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
Changed DiagnosticMessage to DiagnosticArray
Modified Paths:
--------------
pkg/trunk/calibration/joint_calibration_monitor/scripts/pr2_calibration_monitor_node.py
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/manifest.xml
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_inverse_dynamics_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_battery.h
pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_battery.cpp
pkg/trunk/drivers/ups/apcupsd_node/scripts/monitor
pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
pkg/trunk/pr2/life_test/caster_life_test/periodic_drive.py
pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py
pkg/trunk/pr2/life_test/src/life_test/life_test.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py
pkg/trunk/stacks/common/robot_actions/include/robot_actions/action.h
pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py
pkg/trunk/stacks/hardware_test/diagnostic_test/test/expected_publisher.py
pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/log_runtime_messages
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/monitor
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/test_high_level
pkg/trunk/stacks/hardware_test/runtime_monitor/src/runtime_monitor/monitor_panel.py
pkg/trunk/stacks/hardware_test/runtime_monitor/testmonitor.py
pkg/trunk/stacks/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
pkg/trunk/stacks/mechanism/mechanism_control/scripts/joints_to_diagnostics.py
pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/ethercat_device.h
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticArray.msg
Removed Paths:
-------------
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/src/backlash_controller.cpp
pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticMessage.msg
Modified: pkg/trunk/calibration/joint_calibration_monitor/scripts/pr2_calibration_monitor_node.py
===================================================================
--- pkg/trunk/calibration/joint_calibration_monitor/scripts/pr2_calibration_monitor_node.py 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/calibration/joint_calibration_monitor/scripts/pr2_calibration_monitor_node.py 2009-08-08 03:15:54 UTC (rev 21122)
@@ -41,7 +41,7 @@
import threading
import math
-from diagnostic_msgs.msg import DiagnosticMessage
+from diagnostic_msgs.msg import DiagnosticArray
from mechanism_msgs.msg import MechanismState
from roslib import rostime
from joint_calibration_monitor.generic_joint_monitor import *
@@ -93,7 +93,7 @@
100) )
- pub = rospy.Publisher("/diagnostics", DiagnosticMessage)
+ pub = rospy.Publisher("/diagnostics", DiagnosticArray)
sub = rospy.Subscriber('mechanism_state', MechanismState,
mech_state_callback, None)
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h 2009-08-08 03:15:54 UTC (rev 21122)
@@ -58,7 +58,7 @@
#include <manipulation_msgs/JointTraj.h>
#include <manipulation_msgs/JointTrajPoint.h>
-#include <diagnostic_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticArray.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
#include <pr2_mechanism_controllers/TrajectoryQuery.h>
@@ -239,7 +239,7 @@
void publishDiagnostics();
- realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage>* diagnostics_publisher_ ; //!< Publishes controller information
+ realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticArray>* diagnostics_publisher_ ; //!< Publishes controller information
/*!
* \brief mutex lock for setting and getting ros messages
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_controller.h 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_controller.h 2009-08-08 03:15:54 UTC (rev 21122)
@@ -38,6 +38,7 @@
<wheel_pid p="4.0" i="0.0" d="0.0" iClamp="0.0" />
</controller>
*/
+
#ifndef CASTER_CONTROLLER_H
#define CASTER_CONTROLLER_H
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h 2009-08-08 03:15:54 UTC (rev 21122)
@@ -43,7 +43,7 @@
// Services
#include <manipulation_msgs/JointTraj.h>
#include <manipulation_msgs/JointTrajPoint.h>
-#include <diagnostic_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticArray.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
#include <pr2_mechanism_controllers/TrajectoryQuery.h>
@@ -176,7 +176,7 @@
bool watch_dog_active_;
- realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage>* diagnostics_publisher_ ; /**< Publishes controller information as a diagnostic message */
+ realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticArray>* diagnostics_publisher_ ; /**< Publishes controller information as a diagnostic message */
/*!
* \brief mutex lock for setting and getting ros messages
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-08-08 03:15:54 UTC (rev 21122)
@@ -27,7 +27,7 @@
<depend package="filters" />
<depend package="geometry_msgs" />
<depend package="manipulation_msgs" />
-
+ <depend package="diagnostic_msgs" />
<url>http://pr.willowgarage.com</url>
<repository>http://pr.willowgarage.com/repos</repository>
<export>
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-08-08 03:15:54 UTC (rev 21122)
@@ -409,7 +409,7 @@
if (diagnostics_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete diagnostics_publisher_ ;
- diagnostics_publisher_ = new realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 2) ;
+ diagnostics_publisher_ = new realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticArray> ("/diagnostics", 2) ;
last_diagnostics_publish_time_ = c_->robot_->hw_->current_time_;
node_->param<double>(service_prefix_ + "/diagnostics_publish_delta_time",diagnostics_publish_delta_time_,0.05);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-08-08 03:15:54 UTC (rev 21122)
@@ -35,7 +35,7 @@
* Author: Sachin Chitta
*********************************************************************/
#include <pr2_mechanism_controllers/base_trajectory_controller.h>
-#include <diagnostic_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticArray.h>
#include <diagnostic_msgs/DiagnosticStatus.h>
#include <ros/rate.h>
@@ -85,7 +85,7 @@
ros_node_.advertise<geometry_msgs::Twist>(control_topic_name_, 1);
ros_node_.subscribe(path_input_topic_name_,path_msg_in_, &BaseTrajectoryController::pathCallback, this, 1);
- ros_node_.advertise<diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 1) ;
+ ros_node_.advertise<diagnostic_msgs::DiagnosticArray> ("/diagnostics", 1) ;
last_diagnostics_publish_time_ = ros::Time::now();
current_time_ = ros::Time::now().toSec();
@@ -279,7 +279,7 @@
return;
}
- diagnostic_msgs::DiagnosticMessage message;
+ diagnostic_msgs::DiagnosticArray message;
std::vector<diagnostic_msgs::DiagnosticStatus> statuses;
std::vector<diagnostic_msgs::KeyValue> values;
std::vector<diagnostic_msgs::DiagnosticString> strings;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-08-08 03:15:54 UTC (rev 21122)
@@ -162,7 +162,7 @@
if (diagnostics_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete diagnostics_publisher_ ;
- diagnostics_publisher_ = new realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 2) ;
+ diagnostics_publisher_ = new realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticArray> ("/diagnostics", 2) ;
last_diagnostics_publish_time_ = robot_->hw_->current_time_;
node_->param<double>(prefix_+"diagnostics_publish_delta_time",diagnostics_publish_delta_time_,0.05);
Deleted: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h 2009-08-08 03:15:54 UTC (rev 21122)
@@ -1,134 +0,0 @@
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2008, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above
- * copyright notice, this list of conditions and the following
- * disclaimer in the documentation and/or other materials provided
- * with the distribution.
- * * Neither the name of the Willow Garage nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-
-#pragma once
-
-/***************************************************/
-/*! \class controller::BacklashController
- \brief Backlash Controller
-
- This class attempts to find backlash in joint.
-*/
-/***************************************************/
-
-
-#include <ros/node.h>
-#include <math.h>
-#include <diagnostic_msgs/DiagnosticMessage.h>
-#include <realtime_tools/realtime_publisher.h>
-#include <realtime_tools/realtime_srv_call.h>
-#include <mechanism_control/controller.h>
-#include <control_toolbox/sine_sweep.h>
-#include <robot_mechanism_controllers/joint_velocity_controller.h>
-#include <joint_qualification_controllers/TestData.h>
-
-namespace controller
-{
-
-class BacklashController : public Controller
-{
-public:
- /*!
- * \brief Default Constructor of the BacklashController class.
- *
- */
- BacklashController();
-
- /*!
- * \brief Destructor of the BacklashController class.
- */
- ~BacklashController();
-
- /*!
- * \brief Functional way to initialize.
- * \param freq Freq of backlash test (Hz).
- * \param amplitude The amplitude of the sweep (N).
- * \param duration The duration in seconds from start to finish (s).
- * \param error_tolerance Maximum error permitted
- * \param time The current hardware time.
- * \param *robot The robot that is being controlled.
- */
- void init(double freq, double duration, double amplitude, double error_tolerance, double time, std::string name,mechanism::RobotState *robot);
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- void analysis();
- virtual void update();
-
- inline bool done() { return done_; }
-
- diagnostic_msgs::DiagnosticMessage diagnostic_message_;
- joint_qualification_controllers::TestData::Request test_data_;
-
-private:
- mechanism::JointState *joint_state_; /**< Joint we're controlling. */
- mechanism::RobotState *robot_; /**< Pointer to robot structure. */
- double duration_; /**< Duration of the test. */
- double initial_time_; /**< Start time of the test. */
- int count_;
- bool done_;
- double last_time_;
- double amplitude_;
- double freq_;
-
-};
-
-/***************************************************/
-/*! \class controller::BacklashControllerNode
- \brief Backlash Controller ROS Node
-
-*/
-/***************************************************/
-
-class BacklashControllerNode : public Controller
-{
-public:
-
- BacklashControllerNode();
- ~BacklashControllerNode();
-
- void update();
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
-private:
- bool data_sent_;
- BacklashController *c_;
- mechanism::RobotState *robot_;
-
- double last_publish_time_;
- realtime_tools::RealtimeSrvCall<joint_qualification_controllers::TestData::Request, joint_qualification_controllers::TestData::Response> call_service_;
- realtime_tools::RealtimePublisher<diagnostic_msgs::DiagnosticMessage> pub_diagnostics_;
-};
-}
-
-
Modified: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/manifest.xml 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/manifest.xml 2009-08-08 03:15:54 UTC (rev 21122)
@@ -7,7 +7,6 @@
<depend package="mechanism_model" />
<depend package="wg_robot_description_parser" />
<depend package="realtime_tools" />
- <depend package="robot_msgs" />
<depend package="control_toolbox" />
<depend package="roscpp" />
<depend package="robot_mechanism_controllers" />
Deleted: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/src/backlash_controller.cpp
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/src/backlash_controller.cpp 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/src/backlash_controller.cpp 2009-08-08 03:15:54 UTC (rev 21122)
@@ -1,226 +0,0 @@
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2008, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above
- * copyright notice, this list of conditions and the following
- * disclaimer in the documentation and/or other materials provided
- * with the distribution.
- * * Neither the name of the Willow Garage nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-#include <joint_qualification_controllers/backlash_controller.h>
-#include <math.h>
-
-using namespace std;
-using namespace control_toolbox;
-
-namespace controller {
-
-ROS_REGISTER_CONTROLLER(BacklashController)
-
-BacklashController::BacklashController():
-joint_state_(NULL), robot_(NULL)
-{
- test_data_.test_name ="backlash";
- test_data_.joint_name = "default joint";
- test_data_.time.resize(80000);
- test_data_.cmd.resize(80000);
- test_data_.effort.resize(80000);
- test_data_.position.resize(80000);
- test_data_.velocity.resize(80000);
- test_data_.arg_name.resize(1);
- test_data_.arg_name[0]="error_tolerance";
- test_data_.arg_value.resize(1);
- duration_ =0.0;
- initial_time_=0;
- last_time_=0;
- count_=0;
- done_=0;
-}
-
-BacklashController::~BacklashController()
-{
-}
-
-void BacklashController::init(double freq, double duration, double amplitude, double error_tolerance, double time, std::string name,mechanism::RobotState *robot)
-{
- assert(robot);
- robot_ = robot;
- joint_state_ = robot->getJointState(name);
- test_data_.joint_name = name;
- freq_ = freq;
- amplitude_ = amplitude;
- test_data_.arg_value[0] = error_tolerance;
- duration_ = duration; //in seconds
- initial_time_ = time; //in seconds
-
-}
-
-bool BacklashController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
-{
-
- TiXmlElement *jnt = config->FirstChildElement("joint");
- if (jnt)
- {
- double freq = atof(jnt->FirstChildElement("controller_defaults")->Attribute("freq"));
- double amplitude = atof(jnt->FirstChildElement("controller_defaults")->Attribute("amplitude"));
- double duration = atof(jnt->FirstChildElement("controller_defaults")->Attribute("duration"));
- double error_tolerance = atof(jnt->FirstChildElement("controller_defaults")->Attribute("error_tolerance"));
- init(freq, duration, amplitude, error_tolerance, robot->hw_->current_time_,jnt->Attribute("name"), robot);
- }
- return true;
-}
-
-void BacklashController::update()
-{
- double time = robot_->hw_->current_time_;
- // wait until the joint is calibrated if it has limits
- if(!joint_state_->calibrated_ && joint_state_->joint_->type_!=mechanism::JOINT_CONTINUOUS)
- {
- initial_time_ = time;
- last_time_ = time;
- return;
- }
-
- if((time-initial_time_)<=duration_)
- {
- //double A=amplitude_*(time-initial_time_)/duration_;
- //joint_state_->commanded_effort_ = A*sin((time-initial_time_)*2*M_PI*freq_);
-
- double A=amplitude_; //Eric's hack
- joint_state_->commanded_effort_ = A * ((sin(time-initial_time_*2*M_PI*freq_))>0 ? 1 : -1);
-
- if (count_<80000 && !done_)
- {
- test_data_.time[count_] = time;
- test_data_.cmd[count_] = joint_state_->commanded_effort_;
- test_data_.effort[count_] = joint_state_->applied_effort_;
- test_data_.position[count_] = joint_state_->position_;
- test_data_.velocity[count_] = joint_state_->velocity_;
- count_++;
- }
- }
- else if(!done_)
- {
- joint_state_->commanded_effort_=0;
- analysis();
- done_=1;
- }
- else
- {
- joint_state_->commanded_effort_=0;
- }
-}
-
-void BacklashController::analysis()
-{
- diagnostic_message_.set_status_size(1);
- robot_msgs::DiagnosticStatus *status = &diagnostic_message_.status[0];
-
- status->name = "BacklashTest";
- count_ = count_ - 1;
- //test done
- assert(count_ > 0);
- status->level = 0;
- status->message = "OK: Done.";
- test_data_.time.resize(count_);
- test_data_.cmd.resize(count_);
- test_data_.effort.resize(count_);
- test_data_.position.resize(count_);
- test_data_.velocity.resize(count_);
-
- return;
-}
-
-
-
-
-ROS_REGISTER_CONTROLLER(BacklashControllerNode)
-BacklashControllerNode::BacklashControllerNode() : data_sent_(false), last_publish_time_(0), call_service_("/test_data"), pub_diagnostics_("/diagnostics", 1)
-{
- c_ = new BacklashController();
-}
-
-BacklashControllerNode::~BacklashControllerNode()
-{
- delete c_;
-}
-
-void BacklashControllerNode::update()
-{
- c_->update();
-
- // Publishes service response
- if (c_->done())
- {
- if(!data_sent_)
- {
- if (call_service_.trylock())
- {
- joint_qualification_controllers::TestData::Request *out = &call_service_.srv_req_;
- out->test_name = c_->test_data_.test_name;
- out->joint_name = c_->test_data_.joint_name;
- out->time = c_->test_data_.time;
- out->cmd = c_->test_data_.cmd;
- out->effort = c_->test_data_.effort;
- out->position = c_->test_data_.position;
- out->velocity = c_->test_data_.velocity;
- out->arg_name = c_->test_data_.arg_name;
- out->arg_value = c_->test_data_.arg_value;
- call_service_.unlockAndCall();
- data_sent_ = true;
- }
- }
- if (last_publish_time_ + 0.5 < robot_->hw_->current_time_)
- {
- if (pub_diagnostics_.trylock())
- {
- last_publish_time_ = robot_->hw_->current_time_;
-
- robot_msgs::DiagnosticStatus *out = &pub_diagnostics_.msg_.status[0];
- out->name = c_->diagnostic_message_.status[0].name;
- out->level = c_->diagnostic_message_.status[0].level;
- out->message = c_->diagnostic_message_.status[0].message;
- pub_diagnostics_.unlockAndPublish();
- }
- }
- }
-}
-
-
-bool BacklashControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
-{
- assert(robot);
- robot_ = robot;
-
- if (!c_->initXml(robot, config))
- return false;
-
- pub_diagnostics_.msg_.set_status_size(1);
- return true;
-}
-
-}
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h 2009-08-08 03:15:54 UTC (rev 21122)
@@ -43,7 +43,7 @@
#include <mechanism_control/controller.h>
#include <mechanism_model/chain.h>
#include <tf/transform_datatypes.h>
-#include <diagnostic_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticArray.h>
#include <realtime_tools/realtime_publisher.h>
#include <boost/scoped_ptr.hpp>
@@ -79,8 +79,8 @@
KDL::JntArray jnt_pos_, jnt_eff_;
KDL::Jacobian jacobian_;
- diagnostic_msgs::DiagnosticMessage diagnostics_;
- realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage> diagnostics_publisher_;
+ diagnostic_msgs::DiagnosticArray diagnostics_;
+ realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticArray> diagnostics_publisher_;
ros::Time diagnostics_time_;
ros::Duration diagnostics_interval_;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_inverse_dynamics_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_inverse_dynamics_controller.h 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_inverse_dynamics_controller.h 2009-08-08 03:15:54 UTC (rev 21122)
@@ -49,7 +49,7 @@
#include <mechanism_control/controller.h>
#include <mechanism_model/chain.h>
#include <tf/transform_datatypes.h>
-#include <diagnostic_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticArray.h>
#include <realtime_tools/realtime_publisher.h>
#include <boost/scoped_ptr.hpp>
#include <filters/filter_chain.h>
@@ -94,8 +94,8 @@
KDL::JntArrayVel jnt_posvel_meas_;
KDL::JntArrayAcc jnt_posvelacc_control_;
double Kp_acc_,Kv_acc_,Kf_acc_,Kp_tau_,Kv_tau_;
- diagnostic_msgs::DiagnosticMessage diagnostics_;
- realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage> diagnostics_publisher_;
+ diagnostic_msgs::DiagnosticArray diagnostics_;
+ realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticArray> diagnostics_publisher_;
ros::Time diagnostics_time_;
ros::Duration diagnostics_interval_;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-08-08 03:15:54 UTC (rev 21122)
@@ -26,6 +26,7 @@
<depend package="joy" />
<depend package="eigen" />
<depend package="filters" />
+ <depend package="diagnostic_msgs" />
<url>http://pr.willowgarage.com</url>
<repository>http://pr.willowgarage.com/repos</repository>
<export>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_battery.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_battery.h 2009-08-08 03:14:30 UTC (rev 21121)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_battery.h 2009-08-08 03:15:54 UTC (rev 21122)
@@ -36,7 +36,7 @@
#include <gazebo/Entity.hh>
#include <gazebo/Model.hh>
#include <pr2_msgs/BatteryState.h>
-#include <diagnostic_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticArray.h>
#include <diagnostic_msgs/DiagnosticStatus.h>
#include <gazebo_plugin/PlugCommand.h>
#include <ros/ros.h>
@@ -111,7 +111,7 @@
pr2_msgs::BatteryState battery_state_;
/// \brief ros message for diagnostic messages
- di...
[truncated message content] |
|
From: <ehb...@us...> - 2009-08-08 03:29:24
|
Revision: 21124
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21124&view=rev
Author: ehberger
Date: 2009-08-08 03:29:16 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
Deprecating JointCmd.msg
Modified Paths:
--------------
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_pd_controller.h
Added Paths:
-----------
pkg/trunk/deprecated/deprecated_msgs/msg/JointCmd.msg
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_msgs/msg/JointCmd.msg
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_pd_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_pd_controller.h 2009-08-08 03:19:41 UTC (rev 21123)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_pd_controller.h 2009-08-08 03:29:16 UTC (rev 21124)
@@ -62,7 +62,7 @@
#include <robot_mechanism_controllers/SetPDCommand.h>
#include <robot_mechanism_controllers/GetPDActual.h>
#include <robot_mechanism_controllers/GetPDCommand.h>
-#include <robot_msgs/JointCmd.h>
+#include <deprecated_msgs/JointCmd.h>
namespace controller
{
Copied: pkg/trunk/deprecated/deprecated_msgs/msg/JointCmd.msg (from rev 21117, pkg/trunk/stacks/common_msgs/robot_msgs/msg/JointCmd.msg)
===================================================================
--- pkg/trunk/deprecated/deprecated_msgs/msg/JointCmd.msg (rev 0)
+++ pkg/trunk/deprecated/deprecated_msgs/msg/JointCmd.msg 2009-08-08 03:29:16 UTC (rev 21124)
@@ -0,0 +1,6 @@
+string[] names
+float64[] efforts
+float64[] positions
+# FIXME: should be plural like the rest
+float64[] velocity
+float64[] acc
Property changes on: pkg/trunk/deprecated/deprecated_msgs/msg/JointCmd.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/robot_msgs/msg/JointCmd.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/JointCmd.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/JointCmd.msg 2009-08-08 03:19:41 UTC (rev 21123)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/JointCmd.msg 2009-08-08 03:29:16 UTC (rev 21124)
@@ -1,6 +0,0 @@
-string[] names
-float64[] efforts
-float64[] positions
-# FIXME: should be plural like the rest
-float64[] velocity
-float64[] acc
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-08-08 03:41:00
|
Revision: 21126
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21126&view=rev
Author: tfoote
Date: 2009-08-08 03:40:53 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
removing DiagnosticString and DiagnosticValue and last few references to them #1903
Modified Paths:
--------------
pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py
pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py
pkg/trunk/stacks/hardware_test/diagnostic_test/src/diagnostic_test/expected.py
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticString.msg
pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticValue.msg
Modified: pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py
===================================================================
--- pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py 2009-08-08 03:37:17 UTC (rev 21125)
+++ pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py 2009-08-08 03:40:53 UTC (rev 21126)
@@ -69,8 +69,8 @@
#diag.values.append(KeyValue(value=timestamp, label="Time"))
# Display the actuator and joint names for this monitor
- diag.strings.append(DiagnosticString(value=self._actuator, label="Actuator"))
- diag.strings.append(DiagnosticString(value=self._joint, label="Joint"))
+ diag.strings.append(KeyValue(value=self._actuator, label="Actuator"))
+ diag.strings.append(KeyValue(value=self._joint, label="Joint"))
# Check if we can find both the joint and actuator
act_names = [x.name for x in mech_state.actuator_states]
@@ -113,8 +113,8 @@
flag_deadbands = len([x for x in self._hist if x == FLAG_DEADBAND])
flag_errors = len([x for x in self._hist if x == FLAG_ERROR])
- diag.strings.append(DiagnosticString(value=self._flag_lookup[sample_result],
- label="Flag Check Result"))
+ diag.strings.append(KeyValue(value=self._flag_lookup[sample_result],
+ label="Flag Check Result"))
diag.values.append(KeyValue(value=flag_oks,
label="Flag OKs"))
Modified: pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py
===================================================================
--- pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py 2009-08-08 03:37:17 UTC (rev 21125)
+++ pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py 2009-08-08 03:40:53 UTC (rev 21126)
@@ -97,10 +97,10 @@
diag.values = [ ]
diag.strings = [ ]
- diag.strings.append(DiagnosticString(value=self._joint, label="Joint"))
- diag.strings.append(DiagnosticString(value=self._actuator, label="Actuator"))
- diag.strings.append(DiagnosticString(value=str(self._positive), label="Positive Joint"))
- diag.strings.append(DiagnosticString(value=str(self._continuous), label="Continuous Joint"))
+ diag.strings.append(KeyValue(value=self._joint, label="Joint"))
+ diag.strings.append(KeyValue(value=self._actuator, label="Actuator"))
+ diag.strings.append(KeyValue(value=str(self._positive), label="Positive Joint"))
+ diag.strings.append(KeyValue(value=str(self._continuous), label="Continuous Joint"))
diag.values.append(KeyValue(value=float(self._ref_position), label="Reference Position"))
diag.values.append(KeyValue(value=float(self._deadband), label="Deadband"))
diag.values.append(KeyValue(value=float(self._rx_count), label="Mech State RX Count"))
@@ -122,8 +122,8 @@
calibrated = (mech_state.joint_states[joint_names.index(self._joint)].is_calibrated == 1)
- diag.strings.append(DiagnosticString(value=str(act_exists), label='Actuator Exists'))
- diag.strings.append(DiagnosticString(value=str(joint_exists), label='Joint Exists'))
+ diag.strings.append(KeyValue(value=str(act_exists), label='Actuator Exists'))
+ diag.strings.append(KeyValue(value=str(joint_exists), label='Joint Exists'))
@@ -147,9 +147,9 @@
diag.message = 'Broken'
diag.level = 2
- diag.strings.insert(0, DiagnosticString(value=diag.message, label='Transmission Status'))
- diag.strings.insert(1, DiagnosticString(value=reading_msg, label='Current Reading'))
- diag.strings.append(DiagnosticString(value=str(calibrated), label='Is Calibrated'))
+ diag.strings.insert(0, KeyValue(value=diag.message, label='Transmission Status'))
+ diag.strings.insert(1, KeyValue(value=reading_msg, label='Current Reading'))
+ diag.strings.append(KeyValue(value=str(calibrated), label='Is Calibrated'))
diag.values.append(KeyValue(value=cal_reading, label='Calibration Reading'))
diag.values.append(KeyValue(value=position, label='Joint Position'))
Modified: pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py
===================================================================
--- pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py 2009-08-08 03:37:17 UTC (rev 21125)
+++ pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py 2009-08-08 03:40:53 UTC (rev 21126)
@@ -70,12 +70,12 @@
if retcode != 0:
diag_level = 2
diag_msg = [ 'ipmitool Error' ]
- diag_strs = [ DiagnosticString(label = 'IPMI Error', value = stderr) ]
+ diag_strs = [ KeyValue(label = 'IPMI Error', value = stderr) ]
return diag_strs, diag_vals, diag_msgs, diag_level
lines = stdout.split('\n')
if len(lines) < 2:
- diag_strs = [ DiagnosticString(label = 'ipmitool status', value = 'No output') ]
+ diag_strs = [ KeyValue(label = 'ipmitool status', value = 'No output') ]
diag_msgs = [ 'No response' ]
diag_level = 2
return diag_strs, diag_vals, diag_msgs, diag_level
@@ -112,7 +112,7 @@
else:
- diag_strs.append(DiagnosticString(label = name, value = words[1]))
+ diag_strs.append(KeyValue(label = name, value = words[1]))
# MP, BP, FP temps
@@ -132,7 +132,7 @@
diag_msgs.append('%s Hot' % dev_name)
else:
- diag_strs.append(DiagnosticString(label = name, value = ipmi_val))
+ diag_strs.append(KeyValue(label = name, value = ipmi_val))
# CPU fan speeds
if (name.startswith('CPU') and name.endswith('Fan')) or name == 'MB Fan':
@@ -142,19 +142,19 @@
rpm = float(rpm)
diag_vals.append(KeyValue(label = name, value = rpm))
else:
- diag_strs.append(DiagnosticString(label = name, value = ipmi_val))
+ diag_strs.append(KeyValue(label = name, value = ipmi_val))
# If CPU is hot we get an alarm from ipmitool, report that too
if name.startswith('CPU') and name.endswith('hot'):
if ipmi_val == '0x01':
- diag_strs.append(DiagnosticString(label = name, value = 'OK'))
+ diag_strs.append(KeyValue(label = name, value = 'OK'))
else:
- diag_strs.append(DiagnosticString(label = name, value = 'Hot'))
+ diag_strs.append(KeyValue(label = name, value = 'Hot'))
diag_level = max(diag_level, 2)
diag_msgs.append('CPU Hot Alarm')
except Exception, e:
- diag_strs.append(DiagnosticString(label = 'Exception', value = traceback.format_exc()))
+ diag_strs.append(KeyValue(label = 'Exception', value = traceback.format_exc()))
diag_level = 2
diag_msgs.append('Exception')
@@ -183,7 +183,7 @@
if retcode != 0:
diag_level = 2
diag_msg = [ 'Core Temp Error' ]
- diag_strs = [ DiagnosticString(label = 'Core Temp Error', value = stderr), DiagnosticString(label = 'Output', value = stdout) ]
+ diag_strs = [ KeyValue(label = 'Core Temp Error', value = stderr), KeyValue(label = 'Output', value = stdout) ]
return diag_strs, diag_vals, diag_msgs, diag_level
tmp = stdout.strip()
@@ -199,7 +199,7 @@
diag_msgs.append('Hot')
else:
- diag_strs.append(DiagnosticString(label = 'Core %s Temp' % index, value = tmp))
+ diag_strs.append(KeyValue(label = 'Core %s Temp' % index, value = tmp))
return diag_strs, diag_vals, diag_msgs, diag_level
@@ -220,8 +220,8 @@
if retcode != 0:
lvl = 2
msgs = [ 'Clock speed error' ]
- strs = [ DiagnosticString(label = 'Clock speed error', value = stderr),
- DiagnosticString(label = 'Output', value = stdout) ]
+ strs = [ KeyValue(label = 'Clock speed error', value = stderr),
+ KeyValue(label = 'Output', value = stdout) ]
return (strs, vals, msgs, lvl)
@@ -242,7 +242,7 @@
else:
lvl = max(lvl, 2)
- strs.append(DiagnosticString(label = 'Core %d Speed' % index, value = speed))
+ strs.append(KeyValue(label = 'Core %d Speed' % index, value = speed))
if not enforce_speed:
lvl = 0
@@ -256,7 +256,7 @@
rospy.logerr(traceback.format_exc())
lvl = 2
msgs.append('Exception')
- strs.append(DiagnosticString(label = 'Exception', value = traceback.format_exc()))
+ strs.append(KeyValue(label = 'Exception', value = traceback.format_exc()))
return strs, vals, msgs, lvl
@@ -265,7 +265,7 @@
def check_uptime():
level = 0
vals = []
- str = DiagnosticString(label = 'Load Average Status', value = 'Error')
+ str = KeyValue(label = 'Load Average Status', value = 'Error')
try:
p = subprocess.Popen('uptime', stdout = subprocess.PIPE,
@@ -289,19 +289,19 @@
if load1 > 35 or load5 > 25 or load15 > 20:
level = 2
- str = DiagnosticString(label = 'Load Average Status', value = stat_dict[level])
+ str = KeyValue(label = 'Load Average Status', value = stat_dict[level])
except Exception, e:
rospy.logerr(traceback.format_exc())
level = 2
- str = DiagnosticString(label = 'Load Average Status', value = str(e))
+ str = KeyValue(label = 'Load Average Status', value = str(e))
return level, vals, str
# Add msgs output
def check_memory():
values = []
- str = DiagnosticString(label = 'Memory Status', value = 'Exception')
+ str = KeyValue(label = 'Memory Status', value = 'Exception')
level = 2
msg = ''
@@ -331,7 +331,7 @@
if free_mem < 5:
level = 2
- str = DiagnosticString(label = 'Total Memory', value = mem_dict[level])
+ str = KeyValue(label = 'Total Memory', value = mem_dict[level])
msg = mem_dict[level]
except Exception, e:
@@ -385,12 +385,12 @@
if user + nice> 90.0:
core_level = 2
- strs.append(DiagnosticString(label = 'CPU %s Status' % cpu_name, value = load_dict[core_level]))
+ strs.append(KeyValue(label = 'CPU %s Status' % cpu_name, value = load_dict[core_level]))
mp_level = max(mp_level, core_level)
except Exception, e:
mp_level = 2
- strs.append(DiagnosticString(label = 'mpstat Exception', value = str(e)))
+ strs.append(KeyValue(label = 'mpstat Exception', value = str(e)))
return mp_level, vals, strs
@@ -431,7 +431,7 @@
stat.strings.pop(0)
stat.values.pop(0)
- stat.strings.insert(0, DiagnosticString(label = 'Update Status', value = stale_status))
+ stat.strings.insert(0, KeyValue(label = 'Update Status', value = stale_status))
stat.values.insert(0, KeyValue(label = 'Time Since Update', value = time_since_update))
class CPUMonitor():
@@ -454,7 +454,7 @@
self._temp_stat.level = 2
self._temp_stat.hardware_id = hostname
self._temp_stat.message = 'No Data'
- self._temp_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
+ self._temp_stat.strings = [ KeyValue(label = 'Update Status', value = 'No Data' )]
self._temp_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
self._usage_stat = DiagnosticStatus()
@@ -462,7 +462,7 @@
self._usage_stat.level = 2
self._usage_stat.hardware_id = hostname
self._usage_stat.message = 'No Data'
- self._usage_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
+ self._usage_stat.strings = [ KeyValue(label = 'Update Status', value = 'No Data' )]
self._usage_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
self._nfs_stat = DiagnosticStatus()
@@ -470,7 +470,7 @@
self._nfs_stat.level = 2
self._nfs_stat.hardware_id = hostname
self._nfs_stat.message = 'No Data'
- self._nfs_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
+ self._nfs_stat.strings = [ KeyValue(label = 'Update Status', value = 'No Data' )]
self._nfs_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
self._last_temp_time = 0
@@ -509,7 +509,7 @@
nfs_level = 0
msg = 'OK'
- strs = [ DiagnosticString(label = 'Update Status', value = 'OK' )]
+ strs = [ KeyValue(label = 'Update Status', value = 'OK' )]
vals = [ KeyValue(label = 'Time Since Last Update', value = 0 )]
try:
@@ -552,7 +552,7 @@
rospy.logerr(traceback.format_exc())
nfs_level = 2
msg = 'Exception'
- strings.append(DiagnosticString(label = 'Exception', value = str(e)))
+ strings.append(KeyValue(label = 'Exception', value = str(e)))
self._mutex.acquire()
@@ -579,7 +579,7 @@
self._mutex.release()
return
- diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
+ diag_strs = [ KeyValue(label = 'Update Status', value = 'OK' ) ]
diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 ) ]
diag_msgs = []
diag_level = 0
@@ -633,7 +633,7 @@
return
diag_level = 0
- diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
+ diag_strs = [ KeyValue(label = 'Update Status', value = 'OK' ) ]
diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 )]
# Check mpstat
Modified: pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py
===================================================================
--- pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py 2009-08-08 03:37:17 UTC (rev 21125)
+++ pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py 2009-08-08 03:40:53 UTC (rev 21126)
@@ -48,7 +48,7 @@
import socket
-from diagnostic_msgs.msg import *
+from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
low_hd_level = 5
critical_hd_level = 1
@@ -109,7 +109,7 @@
stat.strings.pop(0)
stat.values.pop(0)
- stat.strings.insert(0, DiagnosticString(label = 'Update Status', value = stale_status))
+ stat.strings.insert(0, KeyValue(label = 'Update Status', value = stale_status))
stat.values.insert(0, KeyValue(label = 'Time Since Update', value = time_since_update))
class hdMonitor():
@@ -129,7 +129,7 @@
self._temp_stat.level = 2
self._temp_stat.hardware_id = hostname
self._temp_stat.message = 'No Data'
- self._temp_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
+ self._temp_stat.strings = [ KeyValue(label = 'Update Status', value = 'No Data' )]
self._temp_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
if self._home_dir != '':
@@ -137,7 +137,7 @@
self._usage_stat.level = 2
self._usage_stat.hardware_id = hostname
self._usage_stat.name = '%s HD Usage' % hostname
- self._usage_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
+ self._usage_stat.strings = [ KeyValue(label = 'Update Status', value = 'No Data' )]
self._usage_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000) ]
self.check_disk_usage()
@@ -169,7 +169,7 @@
self._mutex.release()
return
- diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
+ diag_strs = [ KeyValue(label = 'Update Status', value = 'OK' ) ]
diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 ) ]
diag_level = 0
diag_message = 'OK'
@@ -185,9 +185,9 @@
temp_level = 2
diag_level = max(diag_level, temp_level)
- diag_strs.append(DiagnosticString(label = 'Disk %d Temp Status' % index, value = temp_dict[temp_level]))
- diag_strs.append(DiagnosticString(label = 'Disk %d Mount Pt.' % index, value = drives[index]))
- diag_strs.append(DiagnosticString(label = 'Disk %d Device ID' % index, value = makes[index]))
+ diag_strs.append(KeyValue(label = 'Disk %d Temp Status' % index, value = temp_dict[temp_level]))
+ diag_strs.append(KeyValue(label = 'Disk %d Mount Pt.' % index, value = drives[index]))
+ diag_strs.append(KeyValue(label = 'Disk %d Device ID' % index, value = makes[index]))
diag_vals.append(KeyValue(label = 'Disk %d Temp' % index, value = temp))
if not temp_ok:
@@ -228,7 +228,7 @@
self._mutex.release()
return
- diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
+ diag_strs = [ KeyValue(label = 'Update Status', value = 'OK' ) ]
diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 ) ]
diag_level = 0
diag_message = 'OK'
@@ -241,7 +241,7 @@
if (retcode == 0):
- diag_strs.append(DiagnosticString(label = 'Disk Space Reading', value = 'OK'))
+ diag_strs.append(KeyValue(label = 'Disk Space Reading', value = 'OK'))
row_count = 0
for row in stdout.split('\n'):
if len(row.split()) < 2:
@@ -262,22 +262,22 @@
else:
level = 2
- diag_strs.append(DiagnosticString(
+ diag_strs.append(KeyValue(
label = 'Disk %d Name' % row_count, value = name))
- diag_vals.append(DiagnosticString(
+ diag_vals.append(KeyValue(
label = 'Disk %d Available' % row_count, value = g_available))
- diag_vals.append(DiagnosticString(
+ diag_vals.append(KeyValue(
label = 'Disk %d Size' % row_count, value = size))
- diag_strs.append(DiagnosticString(
+ diag_strs.append(KeyValue(
label = 'Disk %d Status' % row_count, value = stat_dict[level]))
- diag_strs.append(DiagnosticString(
+ diag_strs.append(KeyValue(
label = 'Disk %d Mount Point' % row_count, value = mount_pt))
diag_level = max(diag_level, level)
diag_message = usage_dict[diag_level]
else:
- diag_strs.append(DiagnosticString(label = 'Disk Space Reading', value = 'Failed'))
+ diag_strs.append(KeyValue(label = 'Disk Space Reading', value = 'Failed'))
diag_level = 2
diag_message = stat_dict[diag_level]
@@ -285,8 +285,8 @@
except:
rospy.logerr(traceback.format_exc())
- diag_strs.append(DiagnosticString(label = 'Disk Space Reading', value = 'Exception'))
- diag_strs.append(DiagnosticString(label = 'Disk Space Ex', value = traceback.format_exc()))
+ diag_strs.append(KeyValue(label = 'Disk Space Reading', value = 'Exception'))
+ diag_strs.append(KeyValue(label = 'Disk Space Ex', value = traceback.format_exc()))
diag_level = 2
diag_message = stat_dict[diag_level]
Deleted: pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticString.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticString.msg 2009-08-08 03:37:17 UTC (rev 21125)
+++ pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticString.msg 2009-08-08 03:40:53 UTC (rev 21126)
@@ -1,2 +0,0 @@
-string value # a string data type
-string label # what to label this value when viewing
Deleted: pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticValue.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticValue.msg 2009-08-08 03:37:17 UTC (rev 21125)
+++ pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticValue.msg 2009-08-08 03:40:53 UTC (rev 21126)
@@ -1,2 +0,0 @@
-float32 value # a value to track over time
-string label # what to label this value when viewing
Modified: pkg/trunk/stacks/hardware_test/diagnostic_test/src/diagnostic_test/expected.py
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_test/src/diagnostic_test/expected.py 2009-08-08 03:37:17 UTC (rev 21125)
+++ pkg/trunk/stacks/hardware_test/diagnostic_test/src/diagnostic_test/expected.py 2009-08-08 03:40:53 UTC (rev 21126)
@@ -62,7 +62,7 @@
else:
msg = 'Missing - Error'
status.level = max(status.level, 2)
- status.strings.append(DiagnosticString(label = name, value = msg))
+ status.strings.append(KeyValue(label = name, value = msg))
if "desired_present" in parameters:
@@ -75,7 +75,7 @@
else:
msg = 'Missing - Warning'
status.level = max(status.level, 1)
- status.strings.append(DiagnosticString(label = name, value = msg))
+ status.strings.append(KeyValue(label = name, value = msg))
status.message = stat_dict[status.level]
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-08-08 03:57:46
|
Revision: 21127
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21127&view=rev
Author: tfoote
Date: 2009-08-08 03:57:35 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
moving Path from robot_msgs to nav_msgs #2281
Modified Paths:
--------------
pkg/trunk/highlevel/writing/writing_core/include/writing_core/action_write_on_white_board.h
pkg/trunk/highlevel/writing/writing_core/nodes/run_generate_text_trajectory.py
pkg/trunk/highlevel/writing/writing_core/nodes/run_write_trajectory.py
pkg/trunk/highlevel/writing/writing_core/src/action_write_on_white_board.cpp
pkg/trunk/highlevel/writing/writing_core/src/run_write_on_white_board.cpp
pkg/trunk/stacks/common_msgs/nav_msgs/srv/GetPlan.srv
pkg/trunk/stacks/pr2/pr2_robot_actions/manifest.xml
pkg/trunk/stacks/pr2/pr2_robot_actions/msg/GenerateTextTrajectoryState.msg
pkg/trunk/stacks/pr2/pr2_robot_actions/msg/WritingState.msg
pkg/trunk/stacks/trex/trex_pr2_writing_test/nodes/test_move_to_helper.py
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/nav_msgs/msg/Path.msg
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_msgs/msg/Path.msg
Modified: pkg/trunk/highlevel/writing/writing_core/include/writing_core/action_write_on_white_board.h
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/include/writing_core/action_write_on_white_board.h 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/highlevel/writing/writing_core/include/writing_core/action_write_on_white_board.h 2009-08-08 03:57:35 UTC (rev 21127)
@@ -42,7 +42,7 @@
#include <ros/node.h>
// Msgs
-#include <robot_msgs/Path.h>
+#include <nav_msgs/Path.h>
#include <std_msgs/Empty.h>
@@ -52,13 +52,13 @@
namespace writing_core{
-class WriteOnWhiteBoardAction: public robot_actions::Action<robot_msgs::Path, std_msgs::Empty>
+class WriteOnWhiteBoardAction: public robot_actions::Action<nav_msgs::Path, std_msgs::Empty>
{
public:
WriteOnWhiteBoardAction();
~WriteOnWhiteBoardAction();
- robot_actions::ResultStatus execute(const robot_msgs::Path& text_trajectory, std_msgs::Empty&);
+ robot_actions::ResultStatus execute(const nav_msgs::Path& text_trajectory, std_msgs::Empty&);
private:
@@ -72,7 +72,7 @@
std::string arm_controller_;
std_msgs::Empty empty_;
- robot_msgs::Path text_trajectory_;
+ nav_msgs::Path text_trajectory_;
//robot_srvs::MoveToPose::Request req_pose_;
//robot_srvs::MoveToPose::Response res_pose_;
Modified: pkg/trunk/highlevel/writing/writing_core/nodes/run_generate_text_trajectory.py
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/nodes/run_generate_text_trajectory.py 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/highlevel/writing/writing_core/nodes/run_generate_text_trajectory.py 2009-08-08 03:57:35 UTC (rev 21127)
@@ -142,7 +142,7 @@
for t in traject(goal.text):
points += [(t[0][0], t[0][1], 0.10)] + [(x, y, -0.05) for (x, y) in t] + [(t[-1][0], t[-1][1], 0.10)]
- msg = robot_msgs.msg.Path()
+ msg = nav_msgs.msg.Path()
msg.poses = []
for (x, y, z) in points:
ps = robot_msgs.msg.PoseStamped()
@@ -161,7 +161,7 @@
w = GenerateTextTrajectoryAction("generate_text_trajectory",
pr2_robot_actions.msg.TextGoal,
pr2_robot_actions.msg.GenerateTextTrajectoryState,
- robot_msgs.msg.Path)
+ nav_msgs.msg.Path)
w.run()
rospy.spin();
Modified: pkg/trunk/highlevel/writing/writing_core/nodes/run_write_trajectory.py
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/nodes/run_write_trajectory.py 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/highlevel/writing/writing_core/nodes/run_write_trajectory.py 2009-08-08 03:57:35 UTC (rev 21127)
@@ -99,7 +99,7 @@
try:
rospy.init_node("write_trajectory", log_level=roslib.msg.Log.DEBUG)
- w = WriteTrajectoryAction("write_trajectory", robot_msgs.msg.Path, robot_actions.msg.WriteTracjectoryState, Empty)
+ w = WriteTrajectoryAction("write_trajectory", nav_msgs.msg.Path, robot_actions.msg.WriteTracjectoryState, Empty)
w.run()
rospy.spin();
Modified: pkg/trunk/highlevel/writing/writing_core/src/action_write_on_white_board.cpp
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/src/action_write_on_white_board.cpp 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/highlevel/writing/writing_core/src/action_write_on_white_board.cpp 2009-08-08 03:57:35 UTC (rev 21127)
@@ -40,7 +40,7 @@
{
WriteOnWhiteBoardAction::WriteOnWhiteBoardAction() :
- robot_actions::Action<robot_msgs::Path, std_msgs::Empty>("write_on_white_board"),
+ robot_actions::Action<nav_msgs::Path, std_msgs::Empty>("write_on_white_board"),
action_name_("write_on_white_board"),
node_(ros::Node::instance()),
arm_controller_("r_arm_cartesian_pose_controller")
@@ -61,7 +61,7 @@
{
};
-robot_actions::ResultStatus WriteOnWhiteBoardAction::execute(const robot_msgs::Path& text_trajectory, std_msgs::Empty& feedback)
+robot_actions::ResultStatus WriteOnWhiteBoardAction::execute(const nav_msgs::Path& text_trajectory, std_msgs::Empty& feedback)
{
ROS_DEBUG("%s: executing.", action_name_.c_str());
Modified: pkg/trunk/highlevel/writing/writing_core/src/run_write_on_white_board.cpp
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/src/run_write_on_white_board.cpp 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/highlevel/writing/writing_core/src/run_write_on_white_board.cpp 2009-08-08 03:57:35 UTC (rev 21127)
@@ -59,7 +59,7 @@
WriteOnWhiteBoardAction write_on_white_board;
robot_actions::ActionRunner runner(10.0);
- runner.connect<robot_msgs::Path, pr2_robot_actions::WritingState, std_msgs::Empty>(write_on_white_board);
+ runner.connect<nav_msgs::Path, pr2_robot_actions::WritingState, std_msgs::Empty>(write_on_white_board);
runner.run();
node.spin();
Copied: pkg/trunk/stacks/common_msgs/nav_msgs/msg/Path.msg (from rev 20633, pkg/trunk/stacks/common_msgs/robot_msgs/msg/Path.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/msg/Path.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/msg/Path.msg 2009-08-08 03:57:35 UTC (rev 21127)
@@ -0,0 +1 @@
+geometry_msgs/PoseStamped[] poses
Modified: pkg/trunk/stacks/common_msgs/nav_msgs/srv/GetPlan.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/srv/GetPlan.srv 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/srv/GetPlan.srv 2009-08-08 03:57:35 UTC (rev 21127)
@@ -1,4 +1,4 @@
geometry_msgs/PoseStamped goal
float32 tolerance
---
-robot_msgs/Path plan
+nav_msgs/Path plan
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/Path.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/Path.msg 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/Path.msg 2009-08-08 03:57:35 UTC (rev 21127)
@@ -1 +0,0 @@
-geometry_msgs/PoseStamped[] poses
Modified: pkg/trunk/stacks/pr2/pr2_robot_actions/manifest.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_robot_actions/manifest.xml 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/stacks/pr2/pr2_robot_actions/manifest.xml 2009-08-08 03:57:35 UTC (rev 21127)
@@ -7,7 +7,7 @@
<depend package="robot_actions"/>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
+ <depend package="nav_msgs"/>
<depend package="geometry_msgs"/>
<depend package="door_msgs"/>
<depend package="pr2_msgs"/>
Modified: pkg/trunk/stacks/pr2/pr2_robot_actions/msg/GenerateTextTrajectoryState.msg
===================================================================
--- pkg/trunk/stacks/pr2/pr2_robot_actions/msg/GenerateTextTrajectoryState.msg 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/stacks/pr2/pr2_robot_actions/msg/GenerateTextTrajectoryState.msg 2009-08-08 03:57:35 UTC (rev 21127)
@@ -10,4 +10,4 @@
TextGoal goal
# Feedback
-robot_msgs/Path feedback
+nav_msgs/Path feedback
Modified: pkg/trunk/stacks/pr2/pr2_robot_actions/msg/WritingState.msg
===================================================================
--- pkg/trunk/stacks/pr2/pr2_robot_actions/msg/WritingState.msg 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/stacks/pr2/pr2_robot_actions/msg/WritingState.msg 2009-08-08 03:57:35 UTC (rev 21127)
@@ -5,7 +5,7 @@
robot_actions/ActionStatus status
# Goal
-robot_msgs/Path goal
+nav_msgs/Path goal
# Feedback
std_msgs/Empty feedback
Modified: pkg/trunk/stacks/trex/trex_pr2_writing_test/nodes/test_move_to_helper.py
===================================================================
--- pkg/trunk/stacks/trex/trex_pr2_writing_test/nodes/test_move_to_helper.py 2009-08-08 03:40:53 UTC (rev 21126)
+++ pkg/trunk/stacks/trex/trex_pr2_writing_test/nodes/test_move_to_helper.py 2009-08-08 03:57:35 UTC (rev 21127)
@@ -148,7 +148,7 @@
generate_text_trajectory = python_actions.ActionClient("generate_text_trajectory",
pr2_robot_actions.msg.TextGoal,
pr2_robot_actions.msg.GenerateTextTrajectoryState,
- robot_msgs.msg.Path)
+ nav_msgs.msg.Path)
generate_text_trajectory.preempt()
time.sleep(2)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
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.
|
|
From: <jfa...@us...> - 2009-08-08 04:45:26
|
Revision: 21134
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21134&view=rev
Author: jfaustwg
Date: 2009-08-08 04:45:10 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
PointStamped::point -> PointStamped::data (#2276)
Modified Paths:
--------------
pkg/trunk/calibration/kinematic_calibration/test/msg_cache_unittest.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pan_tilt.cpp
pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle.cpp
pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle_no_camera.cpp
pkg/trunk/highlevel/plugs/plugs_core/src/action_detect_outlet_coarse.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_hybrid.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp
pkg/trunk/highlevel/writing/writing_core/nodes/run_track_helper.py
pkg/trunk/highlevel/writing/writing_core/src/whiteboard_detector.cpp
pkg/trunk/mapping/collision_map/src/collision_map.cpp
pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp
pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
pkg/trunk/sandbox/labeled_object_detector/src/segment_objects.cpp
pkg/trunk/sandbox/person_follower/.build_version
pkg/trunk/sandbox/person_follower/src/follower.cpp
pkg/trunk/sandbox/point_cloud_tutorials/src/planar_fit.cpp
pkg/trunk/sandbox/rf_detector/src/ObjectInPerspective.cpp
pkg/trunk/sandbox/webteleop/src/server.py
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PointStamped.msg
pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
pkg/trunk/stacks/geometry/tf/test/python_debug_test.py
pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/doors_detector.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/geometric_helper.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp
pkg/trunk/stacks/semantic_mapping/plug_onbase_detector/include/plug_onbase_detector/plug_onbase_detector.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_io/tools/bag_to_pcd.cpp
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation.cpp
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation_in_proc.cpp
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/planar_fit.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_ground_removal.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_inc_ground_removal.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator_omp.cpp
pkg/trunk/stacks/trex/trex_ros/src/adapter_utilities.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting2.cpp
pkg/trunk/util/message_sequencing/example/testdelay.cpp
pkg/trunk/util/message_sequencing/example/testgen.cpp
pkg/trunk/util/message_sequencing/example/testrecv.cpp
pkg/trunk/util/prosilica_capture_rectified/src/prosilica_capture.cpp
pkg/trunk/vision/recognition_lambertian/src/recognition_lambertian.cpp
pkg/trunk/vision/stereo_blob_tracker/src/listener.cpp
pkg/trunk/vision/stereo_blob_tracker/src/stereo_blob_tracker.cpp
Modified: pkg/trunk/calibration/kinematic_calibration/test/msg_cache_unittest.cpp
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/test/msg_cache_unittest.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/calibration/kinematic_calibration/test/msg_cache_unittest.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -53,7 +53,7 @@
cache.insertData(sample) ;
sample.header.stamp =ros::Time(2.0) ;
- sample.point.x = 11 ;
+ sample.data.x = 11 ;
cache.insertData(sample) ;
sample.header.stamp =ros::Time(3.0) ;
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pan_tilt.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pan_tilt.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pan_tilt.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -83,7 +83,7 @@
geometry_msgs::PointStamped target_point ;
target_point.header = snapshot_.header ;
- target_point.point = cur_marker.location ;
+ target_point.data = cur_marker.location ;
publish(topic, target_point) ;
Modified: pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -264,24 +264,24 @@
if (isPreemptRequested()) return false;
ROS_INFO("point head towards door");
geometry_msgs::PointStamped door_pnt;
- door_pnt.point.z = 0.9;
+ door_pnt.data.z = 0.9;
door_pnt.header.frame_id = door_in.header.frame_id;
if (door_in.hinge == door_in.HINGE_P1){
- door_pnt.point.x = 0.1*door_in.door_p1.x + 0.9*door_in.door_p2.x;
- door_pnt.point.y = 0.1*door_in.door_p1.y + 0.9*door_in.door_p2.y;
+ door_pnt.data.x = 0.1*door_in.door_p1.x + 0.9*door_in.door_p2.x;
+ door_pnt.data.y = 0.1*door_in.door_p1.y + 0.9*door_in.door_p2.y;
}
else if (door_in.hinge == door_in.HINGE_P2){
- door_pnt.point.x = 0.9*door_in.door_p1.x + 0.1*door_in.door_p2.x;
- door_pnt.point.y = 0.9*door_in.door_p1.y + 0.1*door_in.door_p2.y;
+ door_pnt.data.x = 0.9*door_in.door_p1.x + 0.1*door_in.door_p2.x;
+ door_pnt.data.y = 0.9*door_in.door_p1.y + 0.1*door_in.door_p2.y;
}
else{
ROS_ERROR("Door hinge side is not specified");
return false;
}
cout << "door_pnt.point " << door_in.header.frame_id << " "
- << door_pnt.point.x << " "
- << door_pnt.point.y << " "
- << door_pnt.point.z << endl;
+ << door_pnt.data.x << " "
+ << door_pnt.data.y << " "
+ << door_pnt.data.z << endl;
pub_.publish(door_pnt);
ros::Duration().fromSec(2).sleep();
Modified: pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle_no_camera.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle_no_camera.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle_no_camera.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -233,13 +233,13 @@
ROS_INFO("point head towards door");
geometry_msgs::PointStamped door_pnt;
door_pnt.header.frame_id = door_in.header.frame_id;
- door_pnt.point.x = (door_in.door_p1.x+door_in.door_p2.x)/2.0;
- door_pnt.point.y = (door_in.door_p1.y+door_in.door_p2.y)/2.0;
- door_pnt.point.z = 0.9;
+ door_pnt.data.x = (door_in.door_p1.x+door_in.door_p2.x)/2.0;
+ door_pnt.data.y = (door_in.door_p1.y+door_in.door_p2.y)/2.0;
+ door_pnt.data.z = 0.9;
cout << "door_pnt.point " << door_in.header.frame_id << " "
- << door_pnt.point.x << " "
- << door_pnt.point.y << " "
- << door_pnt.point.z << endl;
+ << door_pnt.data.x << " "
+ << door_pnt.data.y << " "
+ << door_pnt.data.z << endl;
pub_.publish(door_pnt);
ros::Duration().fromSec(2).sleep();
Modified: pkg/trunk/highlevel/plugs/plugs_core/src/action_detect_outlet_coarse.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/src/action_detect_outlet_coarse.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/highlevel/plugs/plugs_core/src/action_detect_outlet_coarse.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -109,7 +109,7 @@
geometry_msgs::PointStamped outlet_final_position;
outlet_final_position.header.frame_id = pose.header.frame_id;
outlet_final_position.header.stamp = pose.header.stamp;
- outlet_final_position.point = pose.pose.position;
+ outlet_final_position.data = pose.pose.position;
node_->publish(head_controller_ + "/point_head", outlet_final_position);
return true;
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -116,14 +116,14 @@
geometry_msgs::PointStamped guess;
#if 0
guess.header.frame_id = "odom_combined";
- guess.point.x = 4.0;
- guess.point.y = 0.0;
- guess.point.z = 0.4;
+ guess.data.x = 4.0;
+ guess.data.y = 0.0;
+ guess.data.z = 0.4;
#else
guess.header.frame_id = "map";
- guess.point.x = 9.899;
- guess.point.y = 24.91;
- guess.point.z = 0.4;
+ guess.data.x = 9.899;
+ guess.data.y = 24.91;
+ guess.data.z = 0.4;
#endif
geometry_msgs::PoseStamped coarse_outlet_pose_msg;
int tries = 0;
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -86,9 +86,9 @@
geometry_msgs::PoseStamped pose;
point.header.frame_id = "torso_lift_link";
- point.point.x=0;
- point.point.y=0;
- point.point.z=0;
+ point.data.x=0;
+ point.data.y=0;
+ point.data.z=0;
Duration switch_timeout = Duration(4.0);
@@ -160,9 +160,9 @@
if (switch_controllers.execute(switchlist, empty, switch_timeout) != robot_actions::SUCCESS) return -37;
geometry_msgs::PointStamped guess;
guess.header.frame_id = "base_link";
- guess.point.x = 2.0;
- guess.point.y = 0.0;
- guess.point.z = 0.4;
+ guess.data.x = 2.0;
+ guess.data.y = 0.0;
+ guess.data.z = 0.4;
geometry_msgs::PoseStamped coarse_outlet_pose_msg;
int tries = 0;
while (detect_outlet_coarse.execute(guess, coarse_outlet_pose_msg, Duration(300.0)) != robot_actions::SUCCESS)
@@ -191,7 +191,7 @@
geometry_msgs::PointStamped outlet_pt;
outlet_pt.header.frame_id = coarse_outlet_pose_msg.header.frame_id;
outlet_pt.header.stamp = coarse_outlet_pose_msg.header.stamp;
- outlet_pt.point = coarse_outlet_pose_msg.pose.position;
+ outlet_pt.data = coarse_outlet_pose_msg.pose.position;
if (detect_outlet_fine.execute(outlet_pt, pose, Duration(60.0)) != robot_actions::SUCCESS) return -70;
// untuck arm
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_hybrid.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_hybrid.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_hybrid.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -85,9 +85,9 @@
geometry_msgs::PoseStamped pose;
point.header.frame_id = "torso_lift_link";
- point.point.x=0;
- point.point.y=0;
- point.point.z=0;
+ point.data.x=0;
+ point.data.y=0;
+ point.data.z=0;
Duration timeout_short = Duration().fromSec(3.0);
Duration timeout_medium = Duration().fromSec(20.0);
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -103,9 +103,9 @@
geometry_msgs::PoseStamped pose;
point.header.frame_id = "odom_combined";
- point.point.x=3.373;
- point.point.y=0.543;
- point.point.z=0;
+ point.data.x=3.373;
+ point.data.y=0.543;
+ point.data.z=0;
Duration timeout_short = Duration().fromSec(2.0);
Duration timeout_medium = Duration().fromSec(5.0);
@@ -140,7 +140,7 @@
if (detect_outlet_coarse.execute(point, pose, timeout_long) != robot_actions::SUCCESS) return -1;
fine_outlet_point.header = pose.header;
- fine_outlet_point.point = pose.pose.position;
+ fine_outlet_point.data = pose.pose.position;
pose.pose = transformOutletPose(pose.pose, 0.6);
Modified: pkg/trunk/highlevel/writing/writing_core/nodes/run_track_helper.py
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/nodes/run_track_helper.py 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/highlevel/writing/writing_core/nodes/run_track_helper.py 2009-08-08 04:45:10 UTC (rev 21134)
@@ -67,14 +67,14 @@
rospy.logdebug("%s: executing.", self.name)
htp = geometry_msgs.msg.PointStamped()
htp.header = goal.header
- htp.point = goal.pose.position
+ htp.data = goal.pose.position
self.head_controller_publisher.publish(htp)
while not self.isPreemptRequested():
time.sleep(0.1)
- #print htp.header.frame_id, htp.point.x, htp.point.y, htp.point.z
+ #print htp.header.frame_id, htp.data.x, htp.data.y, htp.data.z
htp.header.stamp = rospy.get_rostime()
self.head_controller_publisher.publish(htp)
Modified: pkg/trunk/highlevel/writing/writing_core/src/whiteboard_detector.cpp
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/src/whiteboard_detector.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/highlevel/writing/writing_core/src/whiteboard_detector.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -141,18 +141,18 @@
geometry_msgs::PointStamped laser_origin;
laser_origin.header.frame_id = point_cloud.header.frame_id;
laser_origin.header.stamp = point_cloud.header.stamp;
- laser_origin.point.x = 0;
- laser_origin.point.y = 0;
- laser_origin.point.z = 0;
+ laser_origin.data.x = 0;
+ laser_origin.data.y = 0;
+ laser_origin.data.z = 0;
geometry_msgs::PointStamped odom_laser_origin;
tf_.transformPoint("odom_combined", laser_origin, odom_laser_origin);
geometry_msgs::Point32 before_projection;
- before_projection.x = odom_laser_origin.point.x;
- before_projection.y = odom_laser_origin.point.y;
- before_projection.z = odom_laser_origin.point.z;
+ before_projection.x = odom_laser_origin.data.x;
+ before_projection.y = odom_laser_origin.data.y;
+ before_projection.z = odom_laser_origin.data.z;
geometry_msgs::Point32 origin_projection;
cloud_geometry::projections::pointToPlane(before_projection, origin_projection, model);
@@ -160,9 +160,9 @@
geometry_msgs::PointStamped origin;
origin.header.stamp = odom_laser_origin.header.stamp;
origin.header.frame_id = odom_laser_origin.header.frame_id;
- origin.point.x = origin_projection.x;
- origin.point.y = origin_projection.y;
- origin.point.z = origin_projection.z;
+ origin.data.x = origin_projection.x;
+ origin.data.y = origin_projection.y;
+ origin.data.z = origin_projection.z;
addWhiteboardFrame(origin, model);
@@ -172,7 +172,7 @@
void addWhiteboardFrame(geometry_msgs::PointStamped origin, const vector<double>& plane)
{
- btVector3 position(origin.point.x,origin.point.y,origin.point.z);
+ btVector3 position(origin.data.x,origin.data.y,origin.data.z);
btQuaternion orientation;
btMatrix3x3 rotation;
Modified: pkg/trunk/mapping/collision_map/src/collision_map.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/mapping/collision_map/src/collision_map.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -205,14 +205,14 @@
cmap.boxes.resize (cloud_.points.size ());
geometry_msgs::PointStamped base_origin, torso_lift_origin;
- base_origin.point.x = base_origin.point.y = base_origin.point.z = 0.0;
+ base_origin.data.x = base_origin.data.y = base_origin.data.z = 0.0;
base_origin.header.frame_id = "torso_lift_link";
base_origin.header.stamp = ros::Time();
try
{
tf_.transformPoint ("base_link", base_origin, torso_lift_origin);
- //ROS_INFO ("Robot 'origin' is : %g,%g,%g", torso_lift_origin.point.x, torso_lift_origin.point.y, torso_lift_origin.point.z);
+ //ROS_INFO ("Robot 'origin' is : %g,%g,%g", torso_lift_origin.data.x, torso_lift_origin.data.y, torso_lift_origin.data.z);
}
catch (tf::ConnectivityException)
{
@@ -230,9 +230,9 @@
for (unsigned int i = 0; i < cloud_.points.size (); i++)
{
// We split the "distance" on all 3 dimensions to allow greater flexibility
- distance_sqr_x = fabs ((cloud_.points[i].x - torso_lift_origin.point.x) * (cloud_.points[i].x - torso_lift_origin.point.x));
- distance_sqr_y = fabs ((cloud_.points[i].y - torso_lift_origin.point.y) * (cloud_.points[i].y - torso_lift_origin.point.y));
- distance_sqr_z = fabs ((cloud_.points[i].z - torso_lift_origin.point.z) * (cloud_.points[i].z - torso_lift_origin.point.z));
+ distance_sqr_x = fabs ((cloud_.points[i].x - torso_lift_origin.data.x) * (cloud_.points[i].x - torso_lift_origin.data.x));
+ distance_sqr_y = fabs ((cloud_.points[i].y - torso_lift_origin.data.y) * (cloud_.points[i].y - torso_lift_origin.data.y));
+ distance_sqr_z = fabs ((cloud_.points[i].z - torso_lift_origin.data.z) * (cloud_.points[i].z - torso_lift_origin.data.z));
// If the point is within the bounds, use it for minP/maxP calculations
if (distance_sqr_x < robot_max_.x && distance_sqr_y < robot_max_.y && distance_sqr_z < robot_max_.z)
Modified: pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -266,14 +266,14 @@
computeLeaves (sensor_msgs::PointCloud *points, vector<Leaf> &leaves, sensor_msgs::PointCloud ¢ers)
{
geometry_msgs::PointStamped base_origin, torso_lift_origin;
- base_origin.point.x = base_origin.point.y = base_origin.point.z = 0.0;
+ base_origin.data.x = base_origin.data.y = base_origin.data.z = 0.0;
base_origin.header.frame_id = "torso_lift_link";
base_origin.header.stamp = ros::Time ();
try
{
tf_.transformPoint (points->header.frame_id, base_origin, torso_lift_origin);
- //ROS_INFO ("Robot 'origin' is : %g,%g,%g", torso_lift_origin.point.x, torso_lift_origin.point.y, torso_lift_origin.point.z);
+ //ROS_INFO ("Robot 'origin' is : %g,%g,%g", torso_lift_origin.data.x, torso_lift_origin.data.y, torso_lift_origin.data.z);
}
catch (tf::ConnectivityException)
{
@@ -291,9 +291,9 @@
for (unsigned int i = 0; i < points->points.size (); i++)
{
// We split the "distance" on all 3 dimensions to allow greater flexibility
- distance_sqr_x = fabs ((points->points[i].x - torso_lift_origin.point.x) * (points->points[i].x - torso_lift_origin.point.x));
- distance_sqr_y = fabs ((points->points[i].y - torso_lift_origin.point.y) * (points->points[i].y - torso_lift_origin.point.y));
- distance_sqr_z = fabs ((points->points[i].z - torso_lift_origin.point.z) * (points->points[i].z - torso_lift_origin.point.z));
+ distance_sqr_x = fabs ((points->points[i].x - torso_lift_origin.data.x) * (points->points[i].x - torso_lift_origin.data.x));
+ distance_sqr_y = fabs ((points->points[i].y - torso_lift_origin.data.y) * (points->points[i].y - torso_lift_origin.data.y));
+ distance_sqr_z = fabs ((points->points[i].z - torso_lift_origin.data.z) * (points->points[i].z - torso_lift_origin.data.z));
// If the point is within the bounds, use it for minP/maxP calculations
if (distance_sqr_x < robot_max_.x && distance_sqr_y < robot_max_.y && distance_sqr_z < robot_max_.z)
@@ -413,7 +413,7 @@
src.header.frame_id = end_effector_frame_l_;
src.header.stamp = stamp;
- src.point.x = src.point.y = src.point.z = 0.0;
+ src.data.x = src.data.y = src.data.z = 0.0;
try
{
tf_.transformPoint (tgt_frame, src, tgt);
@@ -428,7 +428,7 @@
ROS_ERROR("Extrapolation exception from %s to %s.", tgt_frame.c_str(), src.header.frame_id.c_str());
}
- center.x = tgt.point.x; center.y = tgt.point.y; center.z = tgt.point.z;
+ center.x = tgt.data.x; center.y = tgt.data.y; center.z = tgt.data.z;
src.header.frame_id = end_effector_frame_r_;
try
@@ -445,7 +445,7 @@
ROS_ERROR("Extrapolation exception from %s to %s.", tgt_frame.c_str(), src.header.frame_id.c_str());
}
- center.x += tgt.point.x; center.y += tgt.point.y; center.z += tgt.point.z;
+ center.x += tgt.data.x; center.y += tgt.data.y; center.z += tgt.data.z;
center.x /= 2.0; center.y /= 2.0; center.z /= 2.0;
return (true);
@@ -512,7 +512,7 @@
}
geometry_msgs::PointStamped ee_local, ee_global; // Transform the end effector position in global (source frame)
- ee_local.point.x = ee_local.point.y = ee_local.point.z = 0.0;
+ ee_local.data.x = ee_local.data.y = ee_local.data.z = 0.0;
ee_local.header.frame_id = target_frame;
ee_local.header.stamp = points->header.stamp;
@@ -529,7 +529,7 @@
return;
}
- ROS_DEBUG ("End effector position is: [%f, %f, %f].", ee_global.point.x, ee_global.point.y, ee_global.point.z);
+ ROS_DEBUG ("End effector position is: [%f, %f, %f].", ee_global.data.x, ee_global.data.y, ee_global.data.z);
// Compute the leaves
vector<Leaf> object_leaves;
Modified: pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp
===================================================================
--- pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -309,21 +309,21 @@
cloud_geometry::statistics::getMinMax (cloud_down_, inliers, minP, maxP);
// Transform to the global frame
geometry_msgs::PointStamped minPstamped_local, maxPstamped_local;
- minPstamped_local.point.x = minP.x;
- minPstamped_local.point.y = minP.y;
+ minPstamped_local.data.x = minP.x;
+ minPstamped_local.data.y = minP.y;
minPstamped_local.header = cloud_in_.header;
- maxPstamped_local.point.x = maxP.x;
- maxPstamped_local.point.y = maxP.y;
+ maxPstamped_local.data.x = maxP.x;
+ maxPstamped_local.data.y = maxP.y;
maxPstamped_local.header = cloud_in_.header;
geometry_msgs::PointStamped minPstamped_global, maxPstamped_global;
try
{
tf_.transformPoint (global_frame_, minPstamped_local, minPstamped_global);
tf_.transformPoint (global_frame_, maxPstamped_local, maxPstamped_global);
- resp.table.table_min.x = minPstamped_global.point.x;
- resp.table.table_min.y = minPstamped_global.point.y;
- resp.table.table_max.x = maxPstamped_global.point.x;
- resp.table.table_max.y = maxPstamped_global.point.y;
+ resp.table.table_min.x = minPstamped_global.data.x;
+ resp.table.table_min.y = minPstamped_global.data.y;
+ resp.table.table_max.x = maxPstamped_global.data.x;
+ resp.table.table_max.y = maxPstamped_global.data.y;
}
catch (tf::TransformException)
{
@@ -350,11 +350,11 @@
{
for (unsigned int j = 0; j < pmap_.polygons[i].points.size (); j++)
{
- local.point.x = pmap_.polygons[i].points[j].x;
- local.point.y = pmap_.polygons[i].points[j].y;
+ local.data.x = pmap_.polygons[i].points[j].x;
+ local.data.y = pmap_.polygons[i].points[j].y;
tf_.transformPoint (global_frame_, local, global);
- pmap_.polygons[i].points[j].x = global.point.x;
- pmap_.polygons[i].points[j].y = global.point.y;
+ pmap_.polygons[i].points[j].x = global.data.x;
+ pmap_.polygons[i].points[j].y = global.data.y;
}
}
}
@@ -552,7 +552,7 @@
geometry_msgs::PointStamped viewpoint_laser, viewpoint_cloud;
viewpoint_laser.header.frame_id = "laser_tilt_mount_link";
// Set the viewpoint in the laser coordinate system to 0,0,0
- viewpoint_laser.point.x = viewpoint_laser.point.y = viewpoint_laser.point.z = 0.0;
+ viewpoint_laser.data.x = viewpoint_laser.data.y = viewpoint_laser.data.z = 0.0;
try
{
@@ -560,7 +560,7 @@
}
catch (tf::TransformException)
{
- viewpoint_cloud.point.x = viewpoint_cloud.point.y = viewpoint_cloud.point.z = 0.0;
+ viewpoint_cloud.data.x = viewpoint_cloud.data.y = viewpoint_cloud.data.z = 0.0;
}
#pragma omp parallel for schedule(dynamic)
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -164,9 +164,9 @@
{
geometry_msgs::PointStamped psi;
psi.header = collisionMap->header;
- psi.point.x = collisionMap->boxes[i].center.x;
- psi.point.y = collisionMap->boxes[i].center.y;
- psi.point.z = collisionMap->boxes[i].center.z;
+ psi.data.x = collisionMap->boxes[i].center.x;
+ psi.data.y = collisionMap->boxes[i].center.y;
+ psi.data.z = collisionMap->boxes[i].center.z;
geometry_msgs::PointStamped pso;
try
@@ -180,7 +180,7 @@
}
poses[i].setIdentity();
- poses[i].setOrigin(btVector3(pso.point.x, pso.point.y, pso.point.z));
+ poses[i].setOrigin(btVector3(pso.data.x, pso.data.y, pso.data.z));
spheres[i] = new shapes::Sphere(maxCoord(collisionMap->boxes[i].extents) * 0.867 + pointcloud_padd_);
}
@@ -222,9 +222,9 @@
{
geometry_msgs::PointStamped psi;
psi.header = collisionMap->header;
- psi.point.x = collisionMap->boxes[i].center.x;
- psi.point.y = collisionMap->boxes[i].center.y;
- psi.point.z = collisionMap->boxes[i].center.z;
+ psi.data.x = collisionMap->boxes[i].center.x;
+ psi.data.y = collisionMap->boxes[i].center.y;
+ psi.data.z = collisionMap->boxes[i].center.z;
geometry_msgs::PointStamped pso;
try
@@ -238,7 +238,7 @@
}
poses[i].setRotation(btQuaternion(btVector3(collisionMap->boxes[i].axis.x, collisionMap->boxes[i].axis.y, collisionMap->boxes[i].axis.z), collisionMap->boxes[i].angle));
- poses[i].setOrigin(btVector3(pso.point.x, pso.point.y, pso.point.z));
+ poses[i].setOrigin(btVector3(pso.data.x, pso.data.y, pso.data.z));
boxes[i] = new shapes::Box(collisionMap->boxes[i].extents.x + pd, collisionMap->boxes[i].extents.y + pd, collisionMap->boxes[i].extents.z + pd);
}
Modified: pkg/trunk/sandbox/labeled_object_detector/src/segment_objects.cpp
===================================================================
--- pkg/trunk/sandbox/labeled_object_detector/src/segment_objects.cpp 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/sandbox/labeled_object_detector/src/segment_objects.cpp 2009-08-08 04:45:10 UTC (rev 21134)
@@ -149,18 +149,18 @@
PointStamped laser_origin;
laser_origin.header.frame_id = point_cloud.header.frame_id;
laser_origin.header.stamp = point_cloud.header.stamp;
- laser_origin.point.x = 0;
- laser_origin.point.y = 0;
- laser_origin.point.z = 0;
+ laser_origin.data.x = 0;
+ laser_origin.data.y = 0;
+ laser_origin.data.z = 0;
PointStamped odom_laser_origin;
tf_.transformPoint("odom_combined", laser_origin, odom_laser_origin);
Point32 before_projection;
- before_projection.x = odom_laser_origin.point.x;
- before_projection.y = odom_laser_origin.point.y;
- before_projection.z = odom_laser_origin.point.z;
+ before_projection.x = odom_laser_origin.data.x;
+ before_projection.y = odom_laser_origin.data.y;
+ before_projection.z = odom_laser_origin.data.z;
Point32 origin_projection;
cloud_geometry::projections::pointToPlane(before_projection, origin_projection, model);
@@ -168,9 +168,9 @@
PointStamped origin;
origin.header.stamp = odom_laser_origin.header.stamp;
origin.header.frame_id = odom_laser_origin.header.frame_id;
- origin.point.x = origin_projection.x;
- origin.point.y = origin_projection.y;
- origin.point.z = origin_projection.z;
+ origin.data.x = origin_projection.x;
+ origin.data.y = origin_projection.y;
+ origin.data.z = origin_projection.z;
addWhiteboardFrame(origin, model);
@@ -180,7 +180,7 @@
void addWhiteboardFrame(PointStamped origin, const vector<double>& plane)
{
- btVector3 position(origin.point.x,origin.point.y,origin.point.z);
+ btVector3 position(origin.data.x,origin.data.y,origin.data.z);
btQuaternion orientation;
btMatrix3x3 rotation;
Modified: pkg/trunk/sandbox/person_follower/.build_version
===================================================================
--- pkg/trunk/sandbox/person_follower/.build_version 2009-08-08 04:41:39 UTC (rev 21133)
+++ pkg/trunk/sandbox/person_follower...
[truncated message content] |
|
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.
|
|
From: <sf...@us...> - 2009-08-08 05:22:50
|
Revision: 21141
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21141&view=rev
Author: sfkwc
Date: 2009-08-08 05:22:40 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
undoing r21137, keeping Vector3Stamped as was, but keeping in fix to door_handle_detector 'using' bug
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 05:21:08 UTC (rev 21140)
+++ pkg/trunk/demos/plug_in/fake_camera_frame.py 2009-08-08 05:22:40 UTC (rev 21141)
@@ -65,8 +65,8 @@
t.header.frame_id = 'high_def_frame'
t.header.seq = 0
t.parent_id = 'base_link'
-t.data.translation = xyz(0, 0, 1.25)
-t.data.rotation = rpy(0, 1.3, 0)
+t.transform.translation = xyz(0, 0, 1.25)
+t.transform.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 05:21:08 UTC (rev 21140)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_bumper.cpp 2009-08-08 05:22:40 UTC (rev 21141)
@@ -87,9 +87,9 @@
// Initialize the controller
void RosBumper::InitChild()
{
- this->forceMsg.data.x = 0;
- this->forceMsg.data.y = 0;
- this->forceMsg.data.z = 0;
+ this->forceMsg.vector.x = 0;
+ this->forceMsg.vector.y = 0;
+ this->forceMsg.vector.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.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->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->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 05:21:08 UTC (rev 21140)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_f3d.cpp 2009-08-08 05:22:40 UTC (rev 21141)
@@ -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.data.x = force.x;
- this->vector3Msg.data.y = force.y;
- this->vector3Msg.data.z = force.z;
+ this->vector3Msg.vector.x = force.x;
+ this->vector3Msg.vector.y = force.y;
+ this->vector3Msg.vector.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 05:21:08 UTC (rev 21140)
+++ pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp 2009-08-08 05:22:40 UTC (rev 21141)
@@ -300,18 +300,18 @@
geometry_msgs::Vector3Stamped axis_original;
ROS_INFO("Original axis: %f %f %f",axis_.x,axis_.y,axis_.z);
- axis_original.data.x = axis_.x;
- axis_original.data.y = axis_.y;
- axis_original.data.z = axis_.z;
+ axis_original.vector.x = axis_.x;
+ axis_original.vector.y = axis_.y;
+ axis_original.vector.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.data.x;
- axis_point_32.y = axis_transformed.data.y;
- axis_point_32.z = axis_transformed.data.z;
+ axis_point_32.x = axis_transformed.vector.x;
+ axis_point_32.y = axis_transformed.vector.y;
+ axis_point_32.z = axis_transformed.vector.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 05:21:08 UTC (rev 21140)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/migration_rules/migration_rules.py 2009-08-08 05:22:40 UTC (rev 21141)
@@ -155,7 +155,7 @@
new_type = "geometry_msgs/Vector3Stamped"
new_full_text = """
Header header
-Vector3 data
+Vector3 vector
================================================================================
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.data)
+ self.migrate(old_msg.vector, new_msg.vector)
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 05:21:08 UTC (rev 21140)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/Vector3Stamped.msg 2009-08-08 05:22:40 UTC (rev 21141)
@@ -1,2 +1,2 @@
Header header
-Vector3 data
+Vector3 vector
Modified: pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
===================================================================
--- pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-08 05:21:08 UTC (rev 21140)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-08 05:22:40 UTC (rev 21141)
@@ -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.data, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
+{vector3MsgToTF(msg.vector, 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.data); 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 */
Modified: pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
===================================================================
--- pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 05:21:08 UTC (rev 21140)
+++ pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 05:22:40 UTC (rev 21141)
@@ -51,9 +51,9 @@
self.tfvector_stamped.stamp = roslib.rostime.Time(10, 0)
self.msgvector_stamped = robot_msgs.msg.Vector3Stamped()
- self.msgvector_stamped.data.x = 0
- self.msgvector_stamped.data.y = 0
- self.msgvector_stamped.data.z = 0
+ self.msgvector_stamped.vector.x = 0
+ self.msgvector_stamped.vector.y = 0
+ self.msgvector_stamped.vector.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.
|
|
From: <jfa...@us...> - 2009-08-08 05:45:09
|
Revision: 21149
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21149&view=rev
Author: jfaustwg
Date: 2009-08-08 05:44:57 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
Reverse r21134, PointStamped::point->PointStamped::data
Modified Paths:
--------------
pkg/trunk/calibration/kinematic_calibration/test/msg_cache_unittest.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pan_tilt.cpp
pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle.cpp
pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle_no_camera.cpp
pkg/trunk/highlevel/plugs/plugs_core/src/action_detect_outlet_coarse.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_hybrid.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp
pkg/trunk/highlevel/writing/writing_core/nodes/run_track_helper.py
pkg/trunk/highlevel/writing/writing_core/src/whiteboard_detector.cpp
pkg/trunk/mapping/collision_map/src/collision_map.cpp
pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp
pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
pkg/trunk/sandbox/labeled_object_detector/src/segment_objects.cpp
pkg/trunk/sandbox/person_follower/src/follower.cpp
pkg/trunk/sandbox/point_cloud_tutorials/src/planar_fit.cpp
pkg/trunk/sandbox/rf_detector/src/ObjectInPerspective.cpp
pkg/trunk/sandbox/webteleop/src/server.py
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PointStamped.msg
pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
pkg/trunk/stacks/geometry/tf/test/python_debug_test.py
pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/doors_detector.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/geometric_helper.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp
pkg/trunk/stacks/semantic_mapping/plug_onbase_detector/include/plug_onbase_detector/plug_onbase_detector.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_io/tools/bag_to_pcd.cpp
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation.cpp
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation_in_proc.cpp
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/planar_fit.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_ground_removal.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_inc_ground_removal.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator_omp.cpp
pkg/trunk/stacks/trex/trex_ros/src/adapter_utilities.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting2.cpp
pkg/trunk/util/message_sequencing/example/testdelay.cpp
pkg/trunk/util/message_sequencing/example/testgen.cpp
pkg/trunk/util/message_sequencing/example/testrecv.cpp
pkg/trunk/util/prosilica_capture_rectified/src/prosilica_capture.cpp
pkg/trunk/vision/recognition_lambertian/src/recognition_lambertian.cpp
pkg/trunk/vision/stereo_blob_tracker/src/listener.cpp
pkg/trunk/vision/stereo_blob_tracker/src/stereo_blob_tracker.cpp
Modified: pkg/trunk/calibration/kinematic_calibration/test/msg_cache_unittest.cpp
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/test/msg_cache_unittest.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/calibration/kinematic_calibration/test/msg_cache_unittest.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -53,7 +53,7 @@
cache.insertData(sample) ;
sample.header.stamp =ros::Time(2.0) ;
- sample.data.x = 11 ;
+ sample.point.x = 11 ;
cache.insertData(sample) ;
sample.header.stamp =ros::Time(3.0) ;
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pan_tilt.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pan_tilt.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pan_tilt.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -83,7 +83,7 @@
geometry_msgs::PointStamped target_point ;
target_point.header = snapshot_.header ;
- target_point.data = cur_marker.location ;
+ target_point.point = cur_marker.location ;
publish(topic, target_point) ;
Modified: pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -264,24 +264,24 @@
if (isPreemptRequested()) return false;
ROS_INFO("point head towards door");
geometry_msgs::PointStamped door_pnt;
- door_pnt.data.z = 0.9;
+ door_pnt.point.z = 0.9;
door_pnt.header.frame_id = door_in.header.frame_id;
if (door_in.hinge == door_in.HINGE_P1){
- door_pnt.data.x = 0.1*door_in.door_p1.x + 0.9*door_in.door_p2.x;
- door_pnt.data.y = 0.1*door_in.door_p1.y + 0.9*door_in.door_p2.y;
+ door_pnt.point.x = 0.1*door_in.door_p1.x + 0.9*door_in.door_p2.x;
+ door_pnt.point.y = 0.1*door_in.door_p1.y + 0.9*door_in.door_p2.y;
}
else if (door_in.hinge == door_in.HINGE_P2){
- door_pnt.data.x = 0.9*door_in.door_p1.x + 0.1*door_in.door_p2.x;
- door_pnt.data.y = 0.9*door_in.door_p1.y + 0.1*door_in.door_p2.y;
+ door_pnt.point.x = 0.9*door_in.door_p1.x + 0.1*door_in.door_p2.x;
+ door_pnt.point.y = 0.9*door_in.door_p1.y + 0.1*door_in.door_p2.y;
}
else{
ROS_ERROR("Door hinge side is not specified");
return false;
}
cout << "door_pnt.point " << door_in.header.frame_id << " "
- << door_pnt.data.x << " "
- << door_pnt.data.y << " "
- << door_pnt.data.z << endl;
+ << door_pnt.point.x << " "
+ << door_pnt.point.y << " "
+ << door_pnt.point.z << endl;
pub_.publish(door_pnt);
ros::Duration().fromSec(2).sleep();
Modified: pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle_no_camera.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle_no_camera.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/highlevel/doors/doors_core/src/action_detect_handle_no_camera.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -233,13 +233,13 @@
ROS_INFO("point head towards door");
geometry_msgs::PointStamped door_pnt;
door_pnt.header.frame_id = door_in.header.frame_id;
- door_pnt.data.x = (door_in.door_p1.x+door_in.door_p2.x)/2.0;
- door_pnt.data.y = (door_in.door_p1.y+door_in.door_p2.y)/2.0;
- door_pnt.data.z = 0.9;
+ door_pnt.point.x = (door_in.door_p1.x+door_in.door_p2.x)/2.0;
+ door_pnt.point.y = (door_in.door_p1.y+door_in.door_p2.y)/2.0;
+ door_pnt.point.z = 0.9;
cout << "door_pnt.point " << door_in.header.frame_id << " "
- << door_pnt.data.x << " "
- << door_pnt.data.y << " "
- << door_pnt.data.z << endl;
+ << door_pnt.point.x << " "
+ << door_pnt.point.y << " "
+ << door_pnt.point.z << endl;
pub_.publish(door_pnt);
ros::Duration().fromSec(2).sleep();
Modified: pkg/trunk/highlevel/plugs/plugs_core/src/action_detect_outlet_coarse.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/src/action_detect_outlet_coarse.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/highlevel/plugs/plugs_core/src/action_detect_outlet_coarse.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -109,7 +109,7 @@
geometry_msgs::PointStamped outlet_final_position;
outlet_final_position.header.frame_id = pose.header.frame_id;
outlet_final_position.header.stamp = pose.header.stamp;
- outlet_final_position.data = pose.pose.position;
+ outlet_final_position.point = pose.pose.position;
node_->publish(head_controller_ + "/point_head", outlet_final_position);
return true;
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -116,14 +116,14 @@
geometry_msgs::PointStamped guess;
#if 0
guess.header.frame_id = "odom_combined";
- guess.data.x = 4.0;
- guess.data.y = 0.0;
- guess.data.z = 0.4;
+ guess.point.x = 4.0;
+ guess.point.y = 0.0;
+ guess.point.z = 0.4;
#else
guess.header.frame_id = "map";
- guess.data.x = 9.899;
- guess.data.y = 24.91;
- guess.data.z = 0.4;
+ guess.point.x = 9.899;
+ guess.point.y = 24.91;
+ guess.point.z = 0.4;
#endif
geometry_msgs::PoseStamped coarse_outlet_pose_msg;
int tries = 0;
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -86,9 +86,9 @@
geometry_msgs::PoseStamped pose;
point.header.frame_id = "torso_lift_link";
- point.data.x=0;
- point.data.y=0;
- point.data.z=0;
+ point.point.x=0;
+ point.point.y=0;
+ point.point.z=0;
Duration switch_timeout = Duration(4.0);
@@ -160,9 +160,9 @@
if (switch_controllers.execute(switchlist, empty, switch_timeout) != robot_actions::SUCCESS) return -37;
geometry_msgs::PointStamped guess;
guess.header.frame_id = "base_link";
- guess.data.x = 2.0;
- guess.data.y = 0.0;
- guess.data.z = 0.4;
+ guess.point.x = 2.0;
+ guess.point.y = 0.0;
+ guess.point.z = 0.4;
geometry_msgs::PoseStamped coarse_outlet_pose_msg;
int tries = 0;
while (detect_outlet_coarse.execute(guess, coarse_outlet_pose_msg, Duration(300.0)) != robot_actions::SUCCESS)
@@ -191,7 +191,7 @@
geometry_msgs::PointStamped outlet_pt;
outlet_pt.header.frame_id = coarse_outlet_pose_msg.header.frame_id;
outlet_pt.header.stamp = coarse_outlet_pose_msg.header.stamp;
- outlet_pt.data = coarse_outlet_pose_msg.pose.position;
+ outlet_pt.point = coarse_outlet_pose_msg.pose.position;
if (detect_outlet_fine.execute(outlet_pt, pose, Duration(60.0)) != robot_actions::SUCCESS) return -70;
// untuck arm
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_hybrid.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_hybrid.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_hybrid.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -85,9 +85,9 @@
geometry_msgs::PoseStamped pose;
point.header.frame_id = "torso_lift_link";
- point.data.x=0;
- point.data.y=0;
- point.data.z=0;
+ point.point.x=0;
+ point.point.y=0;
+ point.point.z=0;
Duration timeout_short = Duration().fromSec(3.0);
Duration timeout_medium = Duration().fromSec(20.0);
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -103,9 +103,9 @@
geometry_msgs::PoseStamped pose;
point.header.frame_id = "odom_combined";
- point.data.x=3.373;
- point.data.y=0.543;
- point.data.z=0;
+ point.point.x=3.373;
+ point.point.y=0.543;
+ point.point.z=0;
Duration timeout_short = Duration().fromSec(2.0);
Duration timeout_medium = Duration().fromSec(5.0);
@@ -140,7 +140,7 @@
if (detect_outlet_coarse.execute(point, pose, timeout_long) != robot_actions::SUCCESS) return -1;
fine_outlet_point.header = pose.header;
- fine_outlet_point.data = pose.pose.position;
+ fine_outlet_point.point = pose.pose.position;
pose.pose = transformOutletPose(pose.pose, 0.6);
Modified: pkg/trunk/highlevel/writing/writing_core/nodes/run_track_helper.py
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/nodes/run_track_helper.py 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/highlevel/writing/writing_core/nodes/run_track_helper.py 2009-08-08 05:44:57 UTC (rev 21149)
@@ -67,14 +67,14 @@
rospy.logdebug("%s: executing.", self.name)
htp = geometry_msgs.msg.PointStamped()
htp.header = goal.header
- htp.data = goal.pose.position
+ htp.point = goal.pose.position
self.head_controller_publisher.publish(htp)
while not self.isPreemptRequested():
time.sleep(0.1)
- #print htp.header.frame_id, htp.data.x, htp.data.y, htp.data.z
+ #print htp.header.frame_id, htp.point.x, htp.point.y, htp.point.z
htp.header.stamp = rospy.get_rostime()
self.head_controller_publisher.publish(htp)
Modified: pkg/trunk/highlevel/writing/writing_core/src/whiteboard_detector.cpp
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/src/whiteboard_detector.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/highlevel/writing/writing_core/src/whiteboard_detector.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -141,18 +141,18 @@
geometry_msgs::PointStamped laser_origin;
laser_origin.header.frame_id = point_cloud.header.frame_id;
laser_origin.header.stamp = point_cloud.header.stamp;
- laser_origin.data.x = 0;
- laser_origin.data.y = 0;
- laser_origin.data.z = 0;
+ laser_origin.point.x = 0;
+ laser_origin.point.y = 0;
+ laser_origin.point.z = 0;
geometry_msgs::PointStamped odom_laser_origin;
tf_.transformPoint("odom_combined", laser_origin, odom_laser_origin);
geometry_msgs::Point32 before_projection;
- before_projection.x = odom_laser_origin.data.x;
- before_projection.y = odom_laser_origin.data.y;
- before_projection.z = odom_laser_origin.data.z;
+ before_projection.x = odom_laser_origin.point.x;
+ before_projection.y = odom_laser_origin.point.y;
+ before_projection.z = odom_laser_origin.point.z;
geometry_msgs::Point32 origin_projection;
cloud_geometry::projections::pointToPlane(before_projection, origin_projection, model);
@@ -160,9 +160,9 @@
geometry_msgs::PointStamped origin;
origin.header.stamp = odom_laser_origin.header.stamp;
origin.header.frame_id = odom_laser_origin.header.frame_id;
- origin.data.x = origin_projection.x;
- origin.data.y = origin_projection.y;
- origin.data.z = origin_projection.z;
+ origin.point.x = origin_projection.x;
+ origin.point.y = origin_projection.y;
+ origin.point.z = origin_projection.z;
addWhiteboardFrame(origin, model);
@@ -172,7 +172,7 @@
void addWhiteboardFrame(geometry_msgs::PointStamped origin, const vector<double>& plane)
{
- btVector3 position(origin.data.x,origin.data.y,origin.data.z);
+ btVector3 position(origin.point.x,origin.point.y,origin.point.z);
btQuaternion orientation;
btMatrix3x3 rotation;
Modified: pkg/trunk/mapping/collision_map/src/collision_map.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/mapping/collision_map/src/collision_map.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -205,14 +205,14 @@
cmap.boxes.resize (cloud_.points.size ());
geometry_msgs::PointStamped base_origin, torso_lift_origin;
- base_origin.data.x = base_origin.data.y = base_origin.data.z = 0.0;
+ base_origin.point.x = base_origin.point.y = base_origin.point.z = 0.0;
base_origin.header.frame_id = "torso_lift_link";
base_origin.header.stamp = ros::Time();
try
{
tf_.transformPoint ("base_link", base_origin, torso_lift_origin);
- //ROS_INFO ("Robot 'origin' is : %g,%g,%g", torso_lift_origin.data.x, torso_lift_origin.data.y, torso_lift_origin.data.z);
+ //ROS_INFO ("Robot 'origin' is : %g,%g,%g", torso_lift_origin.point.x, torso_lift_origin.point.y, torso_lift_origin.point.z);
}
catch (tf::ConnectivityException)
{
@@ -230,9 +230,9 @@
for (unsigned int i = 0; i < cloud_.points.size (); i++)
{
// We split the "distance" on all 3 dimensions to allow greater flexibility
- distance_sqr_x = fabs ((cloud_.points[i].x - torso_lift_origin.data.x) * (cloud_.points[i].x - torso_lift_origin.data.x));
- distance_sqr_y = fabs ((cloud_.points[i].y - torso_lift_origin.data.y) * (cloud_.points[i].y - torso_lift_origin.data.y));
- distance_sqr_z = fabs ((cloud_.points[i].z - torso_lift_origin.data.z) * (cloud_.points[i].z - torso_lift_origin.data.z));
+ distance_sqr_x = fabs ((cloud_.points[i].x - torso_lift_origin.point.x) * (cloud_.points[i].x - torso_lift_origin.point.x));
+ distance_sqr_y = fabs ((cloud_.points[i].y - torso_lift_origin.point.y) * (cloud_.points[i].y - torso_lift_origin.point.y));
+ distance_sqr_z = fabs ((cloud_.points[i].z - torso_lift_origin.point.z) * (cloud_.points[i].z - torso_lift_origin.point.z));
// If the point is within the bounds, use it for minP/maxP calculations
if (distance_sqr_x < robot_max_.x && distance_sqr_y < robot_max_.y && distance_sqr_z < robot_max_.z)
Modified: pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -266,14 +266,14 @@
computeLeaves (sensor_msgs::PointCloud *points, vector<Leaf> &leaves, sensor_msgs::PointCloud ¢ers)
{
geometry_msgs::PointStamped base_origin, torso_lift_origin;
- base_origin.data.x = base_origin.data.y = base_origin.data.z = 0.0;
+ base_origin.point.x = base_origin.point.y = base_origin.point.z = 0.0;
base_origin.header.frame_id = "torso_lift_link";
base_origin.header.stamp = ros::Time ();
try
{
tf_.transformPoint (points->header.frame_id, base_origin, torso_lift_origin);
- //ROS_INFO ("Robot 'origin' is : %g,%g,%g", torso_lift_origin.data.x, torso_lift_origin.data.y, torso_lift_origin.data.z);
+ //ROS_INFO ("Robot 'origin' is : %g,%g,%g", torso_lift_origin.point.x, torso_lift_origin.point.y, torso_lift_origin.point.z);
}
catch (tf::ConnectivityException)
{
@@ -291,9 +291,9 @@
for (unsigned int i = 0; i < points->points.size (); i++)
{
// We split the "distance" on all 3 dimensions to allow greater flexibility
- distance_sqr_x = fabs ((points->points[i].x - torso_lift_origin.data.x) * (points->points[i].x - torso_lift_origin.data.x));
- distance_sqr_y = fabs ((points->points[i].y - torso_lift_origin.data.y) * (points->points[i].y - torso_lift_origin.data.y));
- distance_sqr_z = fabs ((points->points[i].z - torso_lift_origin.data.z) * (points->points[i].z - torso_lift_origin.data.z));
+ distance_sqr_x = fabs ((points->points[i].x - torso_lift_origin.point.x) * (points->points[i].x - torso_lift_origin.point.x));
+ distance_sqr_y = fabs ((points->points[i].y - torso_lift_origin.point.y) * (points->points[i].y - torso_lift_origin.point.y));
+ distance_sqr_z = fabs ((points->points[i].z - torso_lift_origin.point.z) * (points->points[i].z - torso_lift_origin.point.z));
// If the point is within the bounds, use it for minP/maxP calculations
if (distance_sqr_x < robot_max_.x && distance_sqr_y < robot_max_.y && distance_sqr_z < robot_max_.z)
@@ -413,7 +413,7 @@
src.header.frame_id = end_effector_frame_l_;
src.header.stamp = stamp;
- src.data.x = src.data.y = src.data.z = 0.0;
+ src.point.x = src.point.y = src.point.z = 0.0;
try
{
tf_.transformPoint (tgt_frame, src, tgt);
@@ -428,7 +428,7 @@
ROS_ERROR("Extrapolation exception from %s to %s.", tgt_frame.c_str(), src.header.frame_id.c_str());
}
- center.x = tgt.data.x; center.y = tgt.data.y; center.z = tgt.data.z;
+ center.x = tgt.point.x; center.y = tgt.point.y; center.z = tgt.point.z;
src.header.frame_id = end_effector_frame_r_;
try
@@ -445,7 +445,7 @@
ROS_ERROR("Extrapolation exception from %s to %s.", tgt_frame.c_str(), src.header.frame_id.c_str());
}
- center.x += tgt.data.x; center.y += tgt.data.y; center.z += tgt.data.z;
+ center.x += tgt.point.x; center.y += tgt.point.y; center.z += tgt.point.z;
center.x /= 2.0; center.y /= 2.0; center.z /= 2.0;
return (true);
@@ -512,7 +512,7 @@
}
geometry_msgs::PointStamped ee_local, ee_global; // Transform the end effector position in global (source frame)
- ee_local.data.x = ee_local.data.y = ee_local.data.z = 0.0;
+ ee_local.point.x = ee_local.point.y = ee_local.point.z = 0.0;
ee_local.header.frame_id = target_frame;
ee_local.header.stamp = points->header.stamp;
@@ -529,7 +529,7 @@
return;
}
- ROS_DEBUG ("End effector position is: [%f, %f, %f].", ee_global.data.x, ee_global.data.y, ee_global.data.z);
+ ROS_DEBUG ("End effector position is: [%f, %f, %f].", ee_global.point.x, ee_global.point.y, ee_global.point.z);
// Compute the leaves
vector<Leaf> object_leaves;
Modified: pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp
===================================================================
--- pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -309,21 +309,21 @@
cloud_geometry::statistics::getMinMax (cloud_down_, inliers, minP, maxP);
// Transform to the global frame
geometry_msgs::PointStamped minPstamped_local, maxPstamped_local;
- minPstamped_local.data.x = minP.x;
- minPstamped_local.data.y = minP.y;
+ minPstamped_local.point.x = minP.x;
+ minPstamped_local.point.y = minP.y;
minPstamped_local.header = cloud_in_.header;
- maxPstamped_local.data.x = maxP.x;
- maxPstamped_local.data.y = maxP.y;
+ maxPstamped_local.point.x = maxP.x;
+ maxPstamped_local.point.y = maxP.y;
maxPstamped_local.header = cloud_in_.header;
geometry_msgs::PointStamped minPstamped_global, maxPstamped_global;
try
{
tf_.transformPoint (global_frame_, minPstamped_local, minPstamped_global);
tf_.transformPoint (global_frame_, maxPstamped_local, maxPstamped_global);
- resp.table.table_min.x = minPstamped_global.data.x;
- resp.table.table_min.y = minPstamped_global.data.y;
- resp.table.table_max.x = maxPstamped_global.data.x;
- resp.table.table_max.y = maxPstamped_global.data.y;
+ resp.table.table_min.x = minPstamped_global.point.x;
+ resp.table.table_min.y = minPstamped_global.point.y;
+ resp.table.table_max.x = maxPstamped_global.point.x;
+ resp.table.table_max.y = maxPstamped_global.point.y;
}
catch (tf::TransformException)
{
@@ -350,11 +350,11 @@
{
for (unsigned int j = 0; j < pmap_.polygons[i].points.size (); j++)
{
- local.data.x = pmap_.polygons[i].points[j].x;
- local.data.y = pmap_.polygons[i].points[j].y;
+ local.point.x = pmap_.polygons[i].points[j].x;
+ local.point.y = pmap_.polygons[i].points[j].y;
tf_.transformPoint (global_frame_, local, global);
- pmap_.polygons[i].points[j].x = global.data.x;
- pmap_.polygons[i].points[j].y = global.data.y;
+ pmap_.polygons[i].points[j].x = global.point.x;
+ pmap_.polygons[i].points[j].y = global.point.y;
}
}
}
@@ -552,7 +552,7 @@
geometry_msgs::PointStamped viewpoint_laser, viewpoint_cloud;
viewpoint_laser.header.frame_id = "laser_tilt_mount_link";
// Set the viewpoint in the laser coordinate system to 0,0,0
- viewpoint_laser.data.x = viewpoint_laser.data.y = viewpoint_laser.data.z = 0.0;
+ viewpoint_laser.point.x = viewpoint_laser.point.y = viewpoint_laser.point.z = 0.0;
try
{
@@ -560,7 +560,7 @@
}
catch (tf::TransformException)
{
- viewpoint_cloud.data.x = viewpoint_cloud.data.y = viewpoint_cloud.data.z = 0.0;
+ viewpoint_cloud.point.x = viewpoint_cloud.point.y = viewpoint_cloud.point.z = 0.0;
}
#pragma omp parallel for schedule(dynamic)
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -164,9 +164,9 @@
{
geometry_msgs::PointStamped psi;
psi.header = collisionMap->header;
- psi.data.x = collisionMap->boxes[i].center.x;
- psi.data.y = collisionMap->boxes[i].center.y;
- psi.data.z = collisionMap->boxes[i].center.z;
+ psi.point.x = collisionMap->boxes[i].center.x;
+ psi.point.y = collisionMap->boxes[i].center.y;
+ psi.point.z = collisionMap->boxes[i].center.z;
geometry_msgs::PointStamped pso;
try
@@ -180,7 +180,7 @@
}
poses[i].setIdentity();
- poses[i].setOrigin(btVector3(pso.data.x, pso.data.y, pso.data.z));
+ poses[i].setOrigin(btVector3(pso.point.x, pso.point.y, pso.point.z));
spheres[i] = new shapes::Sphere(maxCoord(collisionMap->boxes[i].extents) * 0.867 + pointcloud_padd_);
}
@@ -222,9 +222,9 @@
{
geometry_msgs::PointStamped psi;
psi.header = collisionMap->header;
- psi.data.x = collisionMap->boxes[i].center.x;
- psi.data.y = collisionMap->boxes[i].center.y;
- psi.data.z = collisionMap->boxes[i].center.z;
+ psi.point.x = collisionMap->boxes[i].center.x;
+ psi.point.y = collisionMap->boxes[i].center.y;
+ psi.point.z = collisionMap->boxes[i].center.z;
geometry_msgs::PointStamped pso;
try
@@ -238,7 +238,7 @@
}
poses[i].setRotation(btQuaternion(btVector3(collisionMap->boxes[i].axis.x, collisionMap->boxes[i].axis.y, collisionMap->boxes[i].axis.z), collisionMap->boxes[i].angle));
- poses[i].setOrigin(btVector3(pso.data.x, pso.data.y, pso.data.z));
+ poses[i].setOrigin(btVector3(pso.point.x, pso.point.y, pso.point.z));
boxes[i] = new shapes::Box(collisionMap->boxes[i].extents.x + pd, collisionMap->boxes[i].extents.y + pd, collisionMap->boxes[i].extents.z + pd);
}
Modified: pkg/trunk/sandbox/labeled_object_detector/src/segment_objects.cpp
===================================================================
--- pkg/trunk/sandbox/labeled_object_detector/src/segment_objects.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/sandbox/labeled_object_detector/src/segment_objects.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -149,18 +149,18 @@
PointStamped laser_origin;
laser_origin.header.frame_id = point_cloud.header.frame_id;
laser_origin.header.stamp = point_cloud.header.stamp;
- laser_origin.data.x = 0;
- laser_origin.data.y = 0;
- laser_origin.data.z = 0;
+ laser_origin.point.x = 0;
+ laser_origin.point.y = 0;
+ laser_origin.point.z = 0;
PointStamped odom_laser_origin;
tf_.transformPoint("odom_combined", laser_origin, odom_laser_origin);
Point32 before_projection;
- before_projection.x = odom_laser_origin.data.x;
- before_projection.y = odom_laser_origin.data.y;
- before_projection.z = odom_laser_origin.data.z;
+ before_projection.x = odom_laser_origin.point.x;
+ before_projection.y = odom_laser_origin.point.y;
+ before_projection.z = odom_laser_origin.point.z;
Point32 origin_projection;
cloud_geometry::projections::pointToPlane(before_projection, origin_projection, model);
@@ -168,9 +168,9 @@
PointStamped origin;
origin.header.stamp = odom_laser_origin.header.stamp;
origin.header.frame_id = odom_laser_origin.header.frame_id;
- origin.data.x = origin_projection.x;
- origin.data.y = origin_projection.y;
- origin.data.z = origin_projection.z;
+ origin.point.x = origin_projection.x;
+ origin.point.y = origin_projection.y;
+ origin.point.z = origin_projection.z;
addWhiteboardFrame(origin, model);
@@ -180,7 +180,7 @@
void addWhiteboardFrame(PointStamped origin, const vector<double>& plane)
{
- btVector3 position(origin.data.x,origin.data.y,origin.data.z);
+ btVector3 position(origin.point.x,origin.point.y,origin.point.z);
btQuaternion orientation;
btMatrix3x3 rotation;
Modified: pkg/trunk/sandbox/person_follower/src/follower.cpp
===================================================================
--- pkg/trunk/sandbox/person_follower/src/follower.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/sandbox/person_follower/src/follower.cpp 2009-08-08 05:44:57 UTC (...
[truncated message content] |
|
From: <jfa...@us...> - 2009-08-08 06:00:43
|
Revision: 21151
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21151&view=rev
Author: jfaustwg
Date: 2009-08-08 06:00:31 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
PoseWithCovarianceStamped::data -> PoseWithCovarianceStamped::pose
Modified Paths:
--------------
pkg/trunk/sandbox/labeled_object_detector/test/test_nearest_action2.cpp
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithCovarianceStamped.msg
pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp
pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp
pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp
pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
pkg/trunk/stacks/navigation/nav_view/src/nav_view/tools.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/tools/pose_tool.cpp
pkg/trunk/vision/vslam/nodes/picmap.py
pkg/trunk/vision/vslam/nodes/roadmap.py
Modified: pkg/trunk/sandbox/labeled_object_detector/test/test_nearest_action2.cpp
===================================================================
--- pkg/trunk/sandbox/labeled_object_detector/test/test_nearest_action2.cpp 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/sandbox/labeled_object_detector/test/test_nearest_action2.cpp 2009-08-08 06:00:31 UTC (rev 21151)
@@ -53,7 +53,7 @@
ROS_INFO_STREAM("pose "<<count <<","<<pose);
PoseStamped goal;
- goal.pose=pose->data.pose;
+ goal.pose=pose->pose.pose;
goal.header=pose->header;
PoseStamped feedback;
robot_actions::ResultStatus result = client.execute(goal, feedback, ros::Duration(5));
Modified: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithCovarianceStamped.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithCovarianceStamped.msg 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithCovarianceStamped.msg 2009-08-08 06:00:31 UTC (rev 21151)
@@ -1,2 +1,2 @@
Header header
-PoseWithCovariance data
+PoseWithCovariance pose
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp 2009-08-08 06:00:31 UTC (rev 21151)
@@ -344,7 +344,7 @@
return;
}
transformer_.lookupTransform("base_footprint","odom", ros::Time(), tmp);
- poseTFToMsg(tmp, estimate.data.pose);
+ poseTFToMsg(tmp, estimate.pose.pose);
// header
estimate.header.stamp = tmp.stamp_;
@@ -354,7 +354,7 @@
SymmetricMatrix covar = filter_->PostGet()->CovarianceGet();
for (unsigned int i=0; i<6; i++)
for (unsigned int j=0; j<6; j++)
- estimate.data.covariance[6*i+j] = covar(i+1,j+1);
+ estimate.pose.covariance[6*i+j] = covar(i+1,j+1);
};
// correct for angle overflow
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp 2009-08-08 06:00:31 UTC (rev 21151)
@@ -142,20 +142,20 @@
EXPECT_GT(Duration(ekf_msg_.header.stamp - odom_msg_.header.stamp).toSec(), -1.0);
// check filter result
- EXPECT_GT(ekf_begin_.data.pose.position.x, 0.038043 - EPS_trans);
- EXPECT_LT(ekf_begin_.data.pose.position.x, 0.038043 + EPS_trans);
- EXPECT_GT(ekf_begin_.data.pose.position.y, -0.001618 - EPS_trans);
- EXPECT_LT(ekf_begin_.data.pose.position.y, -0.001618 + EPS_trans);
- EXPECT_GT(ekf_begin_.data.pose.position.z, 0.000000 - EPS_trans);
- EXPECT_LT(ekf_begin_.data.pose.position.z, 0.000000 + EPS_trans);
- EXPECT_GT(ekf_begin_.data.pose.orientation.x, 0.000000 - EPS_rot);
- EXPECT_LT(ekf_begin_.data.pose.orientation.x, 0.000000 + EPS_rot);
- EXPECT_GT(ekf_begin_.data.pose.orientation.y, 0.000000 - EPS_rot);
- EXPECT_LT(ekf_begin_.data.pose.orientation.y, 0.000000 + EPS_rot);
- EXPECT_GT(ekf_begin_.data.pose.orientation.z, 0.088400 - EPS_rot);
- EXPECT_LT(ekf_begin_.data.pose.orientation.z, 0.088400 + EPS_rot);
- EXPECT_GT(ekf_begin_.data.pose.orientation.w, 0.996085 - EPS_rot);
- EXPECT_LT(ekf_begin_.data.pose.orientation.w, 0.996085 + EPS_rot);
+ EXPECT_GT(ekf_begin_.pose.pose.position.x, 0.038043 - EPS_trans);
+ EXPECT_LT(ekf_begin_.pose.pose.position.x, 0.038043 + EPS_trans);
+ EXPECT_GT(ekf_begin_.pose.pose.position.y, -0.001618 - EPS_trans);
+ EXPECT_LT(ekf_begin_.pose.pose.position.y, -0.001618 + EPS_trans);
+ EXPECT_GT(ekf_begin_.pose.pose.position.z, 0.000000 - EPS_trans);
+ EXPECT_LT(ekf_begin_.pose.pose.position.z, 0.000000 + EPS_trans);
+ EXPECT_GT(ekf_begin_.pose.pose.orientation.x, 0.000000 - EPS_rot);
+ EXPECT_LT(ekf_begin_.pose.pose.orientation.x, 0.000000 + EPS_rot);
+ EXPECT_GT(ekf_begin_.pose.pose.orientation.y, 0.000000 - EPS_rot);
+ EXPECT_LT(ekf_begin_.pose.pose.orientation.y, 0.000000 + EPS_rot);
+ EXPECT_GT(ekf_begin_.pose.pose.orientation.z, 0.088400 - EPS_rot);
+ EXPECT_LT(ekf_begin_.pose.pose.orientation.z, 0.088400 + EPS_rot);
+ EXPECT_GT(ekf_begin_.pose.pose.orientation.w, 0.996085 - EPS_rot);
+ EXPECT_LT(ekf_begin_.pose.pose.orientation.w, 0.996085 + EPS_rot);
SUCCEED();
}
Modified: pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp 2009-08-08 06:00:31 UTC (rev 21151)
@@ -669,10 +669,10 @@
p.header.frame_id = "map";
p.header.stamp = laser_scan->header.stamp;
// Copy in the pose
- p.data.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
- p.data.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
+ p.pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
+ p.pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
tf::quaternionTFToMsg(tf::Quaternion(hyps[max_weight_hyp].pf_pose_mean.v[2], 0.0, 0.0),
- p.data.pose.orientation);
+ p.pose.pose.orientation);
// Copy in the covariance, converting from 3-D to 6-D
pf_sample_set_t* set = pf_->sets + pf_->current_set;
for(int i=0; i<2; i++)
@@ -682,13 +682,13 @@
// Report the overall filter covariance, rather than the
// covariance for the highest-weight cluster
//p.covariance[6*i+j] = hyps[max_weight_hyp].pf_pose_cov.m[i][j];
- p.data.covariance[6*i+j] = set->cov.m[i][j];
+ p.pose.covariance[6*i+j] = set->cov.m[i][j];
}
}
// Report the overall filter covariance, rather than the
// covariance for the highest-weight cluster
//p.covariance[6*3+3] = hyps[max_weight_hyp].pf_pose_cov.m[2][2];
- p.data.covariance[6*3+3] = set->cov.m[2][2];
+ p.pose.covariance[6*3+3] = set->cov.m[2][2];
/*
printf("cov:\n");
@@ -821,11 +821,11 @@
ros::Node::instance()->setParam("~initial_pose_y", map_pose.getOrigin().y());
ros::Node::instance()->setParam("~initial_pose_a", yaw);
ros::Node::instance()->setParam("~initial_cov_xx",
- last_published_pose.data.covariance[6*0+0]);
+ last_published_pose.pose.covariance[6*0+0]);
ros::Node::instance()->setParam("~initial_cov_yy",
- last_published_pose.data.covariance[6*1+1]);
+ last_published_pose.pose.covariance[6*1+1]);
ros::Node::instance()->setParam("~initial_cov_aa",
- last_published_pose.data.covariance[6*3+3]);
+ last_published_pose.pose.covariance[6*3+3]);
save_pose_last_time = now;
}
}
@@ -861,7 +861,7 @@
}
tf::Pose pose_old, pose_new;
- tf::poseMsgToTF(initial_pose_.data.pose, pose_old);
+ tf::poseMsgToTF(initial_pose_.pose.pose, pose_old);
pose_new = tx_odom.inverse() * pose_old;
ROS_INFO("Setting pose (%.6f): %.3f %.3f %.3f",
@@ -880,10 +880,10 @@
{
for(int j=0; j<2; j++)
{
- pf_init_pose_cov.m[i][j] = initial_pose_.data.covariance[6*i+j];
+ pf_init_pose_cov.m[i][j] = initial_pose_.pose.covariance[6*i+j];
}
}
- pf_init_pose_cov.m[2][2] = initial_pose_.data.covariance[6*3+3];
+ pf_init_pose_cov.m[2][2] = initial_pose_.pose.covariance[6*3+3];
pf_mutex_.lock();
pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
Modified: pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
===================================================================
--- pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-08 06:00:31 UTC (rev 21151)
@@ -205,16 +205,16 @@
// Publish localized pose
m_currentPos.header = message->header;
m_currentPos.header.frame_id = "/map"; ///\todo fixme hack
- m_currentPos.data.pose.position.x = x;
- m_currentPos.data.pose.position.y = y;
+ m_currentPos.pose.pose.position.x = x;
+ m_currentPos.pose.pose.position.y = y;
// Leave z as zero
tf::quaternionTFToMsg(tf::Quaternion(yaw, 0.0, 0.0),
- m_currentPos.data.pose.orientation);
+ m_currentPos.pose.pose.orientation);
// Leave covariance as zero
publish("amcl_pose", m_currentPos);
// The particle cloud is the current position. Quite convenient.
- m_particleCloud.poses[0] = m_currentPos.data.pose;
+ m_particleCloud.poses[0] = m_currentPos.pose.pose;
publish("particlecloud", m_particleCloud);
}
};
Modified: pkg/trunk/stacks/navigation/nav_view/src/nav_view/tools.cpp
===================================================================
--- pkg/trunk/stacks/navigation/nav_view/src/nav_view/tools.cpp 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/stacks/navigation/nav_view/src/nav_view/tools.cpp 2009-08-08 06:00:31 UTC (rev 21151)
@@ -172,13 +172,13 @@
else
{
geometry_msgs::PoseWithCovarianceStamped pose;
- pose.data.pose.position.x = pos_.x;
- pose.data.pose.position.y = pos_.y;
+ pose.pose.pose.position.x = pos_.x;
+ pose.pose.pose.position.y = pos_.y;
tf::quaternionTFToMsg(tf::Quaternion(angle, 0.0, 0.0),
- pose.data.pose.orientation);
- pose.data.covariance[6*0+0] = 0.5 * 0.5;
- pose.data.covariance[6*1+1] = 0.5 * 0.5;
- pose.data.covariance[6*3+3] = M_PI/12.0 * M_PI/12.0;
+ pose.pose.pose.orientation);
+ pose.pose.covariance[6*0+0] = 0.5 * 0.5;
+ pose.pose.covariance[6*1+1] = 0.5 * 0.5;
+ pose.pose.covariance[6*3+3] = M_PI/12.0 * M_PI/12.0;
ROS_INFO( "setting pose: %.3f %.3f %.3f\n", pos_.x, pos_.y, angle );
pose_pub_.publish( pose );
}
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/tools/pose_tool.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/tools/pose_tool.cpp 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/tools/pose_tool.cpp 2009-08-08 06:00:31 UTC (rev 21151)
@@ -160,13 +160,13 @@
else
{
geometry_msgs::PoseWithCovarianceStamped pose;
- pose.data.pose.position.x = robot_pos_transformed.x();
- pose.data.pose.position.y = robot_pos_transformed.y();
+ pose.pose.pose.position.x = robot_pos_transformed.x();
+ pose.pose.pose.position.y = robot_pos_transformed.y();
tf::quaternionTFToMsg(tf::Quaternion(angle, 0.0, 0.0),
- pose.data.pose.orientation);
- pose.data.covariance[6*0+0] = 0.5 * 0.5;
- pose.data.covariance[6*1+1] = 0.5 * 0.5;
- pose.data.covariance[6*3+3] = M_PI/12.0 * M_PI/12.0;
+ pose.pose.pose.orientation);
+ pose.pose.covariance[6*0+0] = 0.5 * 0.5;
+ pose.pose.covariance[6*1+1] = 0.5 * 0.5;
+ pose.pose.covariance[6*3+3] = M_PI/12.0 * M_PI/12.0;
ROS_INFO("Setting pose: %.3f %.3f %.3f [frame=%s]",
robot_pos_transformed.x(),
robot_pos_transformed.y(),
Modified: pkg/trunk/vision/vslam/nodes/picmap.py
===================================================================
--- pkg/trunk/vision/vslam/nodes/picmap.py 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/vision/vslam/nodes/picmap.py 2009-08-08 06:00:31 UTC (rev 21151)
@@ -191,8 +191,8 @@
def handle_amcl_pose(self, msg):
if self.vo:
print "handle_amcl_pose(", msg, ")"
- happy = max([msg.data.covariance[0], msg.data.covariance[7]]) < 0.003
- print "picmap node got amcl", msg.header.stamp.to_seconds(), msg.data.covariance[0], msg.data.covariance[7], "happy", happy
+ happy = max([msg.pose.covariance[0], msg.pose.covariance[7]]) < 0.003
+ print "picmap node got amcl", msg.header.stamp.to_seconds(), msg.pose.covariance[0], msg.pose.covariance[7], "happy", happy
self.pmlock.acquire()
self.pm.newLocalization(msg.header.stamp.to_seconds(), happy)
self.pmlock.release()
Modified: pkg/trunk/vision/vslam/nodes/roadmap.py
===================================================================
--- pkg/trunk/vision/vslam/nodes/roadmap.py 2009-08-08 05:59:29 UTC (rev 21150)
+++ pkg/trunk/vision/vslam/nodes/roadmap.py 2009-08-08 06:00:31 UTC (rev 21151)
@@ -259,9 +259,9 @@
self.send_map(msg.header.stamp)
def handle_localizedpose(self, msg):
- th = tf.transformations.euler_from_quaternion([msg.data.pose.orientation.x, msg.data.pose.orientation.y, msg.data.pose.orientation.z, msg.data.pose.orientation.w])[2]
- x = msg.data.pose.position.x
- y = msg.data.pose.position.y
+ th = tf.transformations.euler_from_quaternion([msg.pose.pose.orientation.x, msg.pose.pose.orientation.y, msg.pose.pose.orientation.z, msg.pose.pose.orientation.w])[2]
+ x = msg.pose.pose.position.x
+ y = msg.pose.pose.position.y
print x, y, th
n = (x, y, th)
if self.nodes == [] or (dist(self.nodes[-1], n) > 1.0) or (abs(self.nodes[-1][2] - n[2]) > (2.0 * pi / 180)):
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-08-08 20:21:50
|
Revision: 21190
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21190&view=rev
Author: tfoote
Date: 2009-08-08 20:21:30 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
removing last of robot_msgs and all dependencies on it
Modified Paths:
--------------
pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/manifest.xml
pkg/trunk/calibration/auto_arm_commander/manifest.xml
pkg/trunk/calibration/calibration_msgs/manifest.xml
pkg/trunk/calibration/joint_calibration_monitor/manifest.xml
pkg/trunk/calibration/laser_camera_calibration/manifest.xml
pkg/trunk/calibration/laser_cb_processing/manifest.xml
pkg/trunk/calibration/optical_flag_calibration/manifest.xml
pkg/trunk/calibration/sandbox/laser_head_updater/manifest.xml
pkg/trunk/calibration/sandbox/pr2_calibration_actions/manifest.xml
pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml
pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
pkg/trunk/demos/2dnav_gazebo/manifest.xml
pkg/trunk/demos/arm_gazebo/manifest.xml
pkg/trunk/demos/erratic_gazebo/manifest.xml
pkg/trunk/demos/handhold/manifest.xml
pkg/trunk/demos/plug_in/manifest.xml
pkg/trunk/demos/pr2_gazebo/manifest.xml
pkg/trunk/demos/tabletop_manipulation/tabletop_msgs/manifest.xml
pkg/trunk/demos/tabletop_manipulation/tabletop_srvs/manifest.xml
pkg/trunk/demos/test_2dnav_gazebo/manifest.xml
pkg/trunk/demos/test_2dnav_gazebo/set_goal.py
pkg/trunk/deprecated/deprecated_srvs/manifest.xml
pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml
pkg/trunk/drivers/robot/pr2/pr2_phase_space/manifest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
pkg/trunk/drivers/simulator/test_gazebo_plugin/manifest.xml
pkg/trunk/drivers/simulator/test_pr2_collision_gazebo/manifest.xml
pkg/trunk/drivers/ups/apcupsd_node/manifest.xml
pkg/trunk/highlevel/doors/doors_core/manifest.xml
pkg/trunk/highlevel/move_arm/manifest.xml
pkg/trunk/highlevel/plugs/plugs_core/manifest.xml
pkg/trunk/highlevel/plugs/plugs_functions/manifest.xml
pkg/trunk/highlevel/safety/safety_core/manifest.xml
pkg/trunk/highlevel/writing/writing_core/manifest.xml
pkg/trunk/mapping/annotated_map_msgs/manifest.xml
pkg/trunk/mapping/annotated_planar_patch_map/manifest.xml
pkg/trunk/mapping/collision_map/manifest.xml
pkg/trunk/mapping/door_stereo_detector/manifest.xml
pkg/trunk/mapping/door_tracker/manifest.xml
pkg/trunk/mapping/hallway_tracker/manifest.xml
pkg/trunk/mapping/stereo_convex_patch_histogram/manifest.xml
pkg/trunk/mapping/table_object_detector/manifest.xml
pkg/trunk/motion_planning/mpglue/manifest.xml
pkg/trunk/motion_planning/ompl_planning/manifest.xml
pkg/trunk/motion_planning/plan_ompl_path/manifest.xml
pkg/trunk/motion_planning/planning_environment/manifest.xml
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/manifest.xml
pkg/trunk/motion_planning/planning_research/sbpl_door_planner/manifest.xml
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/manifest.xml
pkg/trunk/motion_planning/planning_research/sbpl_planner_node/manifest.xml
pkg/trunk/nav/people_aware_nav/manifest.xml
pkg/trunk/nav/visual_nav/manifest.xml
pkg/trunk/openrave_planning/orrosplanning/manifest.xml
pkg/trunk/pr2/motorconf_gui/manifest.xml
pkg/trunk/pr2/qualification/manifest.xml
pkg/trunk/pr2/teleop/teleop_head/manifest.xml
pkg/trunk/pr2/teleop/teleop_spacenav/manifest.xml
pkg/trunk/sandbox/3dnav_pr2/manifest.xml
pkg/trunk/sandbox/camera_calibration/manifest.xml
pkg/trunk/sandbox/descriptors_3d/manifest.xml
pkg/trunk/sandbox/experimental_controllers/manifest.xml
pkg/trunk/sandbox/functional_m3n/manifest.xml
pkg/trunk/sandbox/labeled_object_detector/manifest.xml
pkg/trunk/sandbox/manipulation_msgs/manifest.xml
pkg/trunk/sandbox/manipulation_srvs/manifest.xml
pkg/trunk/sandbox/mapping_msgs/manifest.xml
pkg/trunk/sandbox/neighborhood_index/manifest.xml
pkg/trunk/sandbox/pcd_novelty/manifest.xml
pkg/trunk/sandbox/person_follower/manifest.xml
pkg/trunk/sandbox/planar_objects/manifest.xml
pkg/trunk/sandbox/point_cloud_clustering/manifest.xml
pkg/trunk/sandbox/point_cloud_tutorials/manifest.xml
pkg/trunk/sandbox/poseviz/manifest.xml
pkg/trunk/sandbox/pr2_ik_with_collision/manifest.xml
pkg/trunk/sandbox/pr2_startup/manifest.xml
pkg/trunk/sandbox/rf_detector/manifest.xml
pkg/trunk/sandbox/test_arm_vision_calibration/manifest.xml
pkg/trunk/sandbox/tf_node/manifest.xml
pkg/trunk/sandbox/webteleop/manifest.xml
pkg/trunk/stacks/camera_drivers/forearm_cam/manifest.xml
pkg/trunk/stacks/common/robot_actions/manifest.xml
pkg/trunk/stacks/common_msgs/nav_msgs/manifest.xml
pkg/trunk/stacks/estimation/robot_pose_ekf/manifest.xml
pkg/trunk/stacks/geometry/tf/manifest.xml
pkg/trunk/stacks/mechanism/mechanism_control/manifest.xml
pkg/trunk/stacks/mechanism/mechanism_msgs/manifest.xml
pkg/trunk/stacks/mechanism/robot_state_publisher/manifest.xml
pkg/trunk/stacks/navigation/amcl/manifest.xml
pkg/trunk/stacks/navigation/carrot_planner/manifest.xml
pkg/trunk/stacks/navigation/costmap_2d/manifest.xml
pkg/trunk/stacks/navigation/fake_localization/manifest.xml
pkg/trunk/stacks/pr2_drivers/pr2_msgs/manifest.xml
pkg/trunk/stacks/pr2_drivers/pr2_srvs/manifest.xml
pkg/trunk/stacks/pr2_ethercat_drivers/fingertip_pressure/manifest.xml
pkg/trunk/stacks/pr2_power_drivers/ocean_battery_driver/manifest.xml
pkg/trunk/stacks/semantic_mapping/door_handle_detector/manifest.xml
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/manifest.xml
pkg/trunk/stacks/sound_drivers/sound_play/manifest.xml
pkg/trunk/stacks/stereo/stereo_image_proc/manifest.xml
pkg/trunk/stacks/trex/trex_pr2/manifest.xml
pkg/trunk/stacks/trex/trex_pr2_writing_test/manifest.xml
pkg/trunk/stacks/visualization_core/visualization_msgs/manifest.xml
pkg/trunk/util/bagserver/manifest.xml
pkg/trunk/util/logsetta/manifest.xml
pkg/trunk/util/or_robot_self_filter/manifest.xml
pkg/trunk/util/prosilica_capture_rectified/manifest.xml
pkg/trunk/util/robot_self_filter/manifest.xml
pkg/trunk/util/self_watch/manifest.xml
pkg/trunk/vision/calib_converter/manifest.xml
pkg/trunk/vision/led_detection/manifest.xml
pkg/trunk/vision/recognition_lambertian/manifest.xml
pkg/trunk/vision/spacetime_stereo/manifest.xml
pkg/trunk/vision/stereo_capture/manifest.xml
pkg/trunk/vision/stereo_checkerboard_detector/manifest.xml
pkg/trunk/vision/vision_tests/manifest.xml
pkg/trunk/vision/visual_odometry/manifest.xml
pkg/trunk/vision/vslam/manifest.xml
pkg/trunk/world_models/test_collision_space/manifest.xml
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_msgs/
Modified: pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/manifest.xml
===================================================================
--- pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/applications/2dnav_pr2_app/2dnav_pr2/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -21,7 +21,6 @@
<!-- packages used in the test scripts -->
<depend package="robot_actions"/>
<depend package="nav_robot_actions"/>
- <depend package="robot_msgs"/>
<depend package="tf"/>
<depend package="bullet"/>
</package>
Modified: pkg/trunk/calibration/auto_arm_commander/manifest.xml
===================================================================
--- pkg/trunk/calibration/auto_arm_commander/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/calibration/auto_arm_commander/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -9,7 +9,6 @@
<depend package="pr2_mechanism_controllers" />
<depend package="std_msgs" />
- <depend package="robot_msgs" />
<depend package="manipulation_msgs" />
Modified: pkg/trunk/calibration/calibration_msgs/manifest.xml
===================================================================
--- pkg/trunk/calibration/calibration_msgs/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/calibration/calibration_msgs/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -8,7 +8,6 @@
<url>http://pr.willowgarage.com/wiki/calibration_msgs</url>
<depend package="std_msgs" />
- <depend package="robot_msgs" />
<depend package="sensor_msgs" />
<export>
Modified: pkg/trunk/calibration/joint_calibration_monitor/manifest.xml
===================================================================
--- pkg/trunk/calibration/joint_calibration_monitor/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/calibration/joint_calibration_monitor/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -3,7 +3,6 @@
<author>Vijay Pradeep</author>
<license>BSD</license>
<review status="unreviewed" notes=""/>
- <depend package="robot_msgs" />
<depend package="std_msgs" />
<depend package="rospy" />
<depend package="diagnostic_msgs" />
Modified: pkg/trunk/calibration/laser_camera_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/laser_camera_calibration/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/calibration/laser_camera_calibration/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -9,7 +9,6 @@
<url>http://pr.willowgarage.com/wiki/laser_camera_calibration</url>
<license>BSD</license>
<review status="unreviewed" notes=""/>
- <depend package="robot_msgs"/>
<depend package="std_msgs"/>
<depend package="sensor_msgs"/>
<depend package="rospy"/>
Modified: pkg/trunk/calibration/laser_cb_processing/manifest.xml
===================================================================
--- pkg/trunk/calibration/laser_cb_processing/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/calibration/laser_cb_processing/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -8,7 +8,6 @@
<!-- url>http://pr.willowgarage.com/wiki/laser_cb_detection</url -->
<depend package="topic_synchronizer" />
- <depend package="robot_msgs" />
<depend package="opencv_latest" />
<depend package="sensor_msgs" />
<depend package="dense_laser_assembler" />
Modified: pkg/trunk/calibration/optical_flag_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/optical_flag_calibration/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/calibration/optical_flag_calibration/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -5,7 +5,6 @@
<review status="experimental" notes=""/>
<!-- depend package="kdl" / -->
<!-- depend package="phase_space" / -->
- <depend package="robot_msgs" />
<depend package="std_msgs" />
<!-- depend package="robot_kinematics" / -->
<!-- depend package="topic_synchronizer" / -->
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/manifest.xml
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -5,7 +5,6 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="kdl" />
- <depend package="robot_msgs" />
<depend package="mechanism_msgs" />
<depend package="std_msgs" />
<depend package="tf" />
Modified: pkg/trunk/calibration/sandbox/pr2_calibration_actions/manifest.xml
===================================================================
--- pkg/trunk/calibration/sandbox/pr2_calibration_actions/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/calibration/sandbox/pr2_calibration_actions/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -8,7 +8,6 @@
<url>http://pr.willowgarage.com/wiki/calibration_msgs</url>
<depend package="std_msgs" />
- <depend package="robot_msgs" />
<depend package="sensor_msgs" />
<depend package="calibration_msgs" />
<depend package="pr2_msgs" />
Modified: pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -4,7 +4,6 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="tf" />
- <depend package="robot_msgs" />
<depend package="nav_msgs" />
<depend package="roscpp" />
<depend package="pr2_mechanism_controllers" />
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -17,7 +17,6 @@
<depend package="nav_msgs" />
<depend package="pr2_msgs" />
<depend package="pr2_srvs"/>
- <depend package="robot_msgs" />
<depend package="visualization_msgs" />
<depend package="robot_actions" />
<depend package="rosconsole" />
Modified: pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -15,7 +15,6 @@
<depend package="roscpp" />
<depend package="std_msgs" />
<depend package="deprecated_srvs" />
- <depend package="robot_msgs" />
<depend package="geometry_msgs" />
<depend package="manipulation_msgs" />
<depend package="visualization_msgs" />
Modified: pkg/trunk/demos/2dnav_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/2dnav_gazebo/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -5,7 +5,6 @@
<review status="NA" notes=""/>
<url>http://pr.willowgarage.com/wiki/Simulator</url>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
<depend package="nav_view"/>
<depend package="move_base"/>
<depend package="gazebo_plugin"/>
Modified: pkg/trunk/demos/arm_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/arm_gazebo/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/arm_gazebo/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -18,5 +18,4 @@
<depend package="rospy"/>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
</package>
Modified: pkg/trunk/demos/erratic_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/erratic_gazebo/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/erratic_gazebo/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -13,5 +13,4 @@
<depend package="tf"/>
<depend package="rospy"/>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
</package>
Modified: pkg/trunk/demos/handhold/manifest.xml
===================================================================
--- pkg/trunk/demos/handhold/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/handhold/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -8,7 +8,6 @@
<depend package="tf" />
<depend package="pr2_default_controllers" />
<depend package="geometry_msgs" />
- <depend package="robot_msgs" />
<url>http://pr.willowgarage.com</url>
<export>
</export>
Modified: pkg/trunk/demos/plug_in/manifest.xml
===================================================================
--- pkg/trunk/demos/plug_in/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/plug_in/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -22,6 +22,5 @@
<depend package="tf" />
<depend package="visualization_msgs" />
- <depend package="robot_msgs" />
<depend package="manipulation_msgs" />
</package>
Modified: pkg/trunk/demos/pr2_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/pr2_gazebo/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/pr2_gazebo/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -18,6 +18,5 @@
<depend package="rospy"/>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
<depend package="door_handle_detector"/>
</package>
Modified: pkg/trunk/demos/tabletop_manipulation/tabletop_msgs/manifest.xml
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_msgs/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_msgs/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -9,7 +9,6 @@
<review status="unreviewed" notes=""/>
<url>http://pr.willowgarage.com/wiki/tabletop_msgs</url>
- <depend package="robot_msgs" />
<depend package="geometry_msgs" />
<depend package="std_msgs"/>
Modified: pkg/trunk/demos/tabletop_manipulation/tabletop_srvs/manifest.xml
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_srvs/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_srvs/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -10,7 +10,6 @@
<url>http://pr.willowgarage.com/wiki/tabletop_srvs</url>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
<depend package="geometry_msgs"/>
<depend package="tabletop_msgs"/>
Modified: pkg/trunk/demos/test_2dnav_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/test_2dnav_gazebo/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/test_2dnav_gazebo/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -16,7 +16,6 @@
<depend package="tf"/>
<depend package="point_cloud_assembler"/>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
<depend package="robot_actions"/>
<depend package="pr2_robot_actions"/>
<depend package="nav_msgs"/>
Modified: pkg/trunk/demos/test_2dnav_gazebo/set_goal.py
===================================================================
--- pkg/trunk/demos/test_2dnav_gazebo/set_goal.py 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/demos/test_2dnav_gazebo/set_goal.py 2009-08-08 20:21:30 UTC (rev 21190)
@@ -49,7 +49,6 @@
from std_msgs.msg import String
from nav_robot_actions.msg import MoveBaseState
from geometry_msgs.msg import Pose,Quaternion,Point, PoseWithRatesStamped, PoseStamped, PoseWithCovarianceStamped
-from robot_msgs.msg import PoseDot
from nav_msgs.msg import Odometry
import tf.transformations as tft
from numpy import float64
@@ -232,7 +231,7 @@
rospy.Subscriber("/amcl_pose" , PoseWithCovarianceStamped , self.amclInput)
# below only for debugging build 303, base not moving
- rospy.Subscriber("cmd_vel" , PoseDot , self.cmd_velInput)
+ #rospy.Subscriber("cmd_vel" , PoseDot , self.cmd_velInput)
rospy.init_node(NAME, anonymous=True)
Modified: pkg/trunk/deprecated/deprecated_srvs/manifest.xml
===================================================================
--- pkg/trunk/deprecated/deprecated_srvs/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/deprecated/deprecated_srvs/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -13,7 +13,6 @@
<logo>http://www.willowgarage.com/files/willowgarage/robot10.jpg</logo>
<depend package="roslib"/>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
<depend package="geometry_msgs"/>
<depend package="deprecated_msgs"/>
<export>
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -8,7 +8,6 @@
<url>http://pr.willowgarage.com</url>
<depend package="sensor_msgs"/>
<depend package="std_msgs"/>
-<depend package="robot_msgs"/>
<depend package="geometry_msgs"/>
<depend package="roscpp"/>
<depend package="tf"/>
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -12,7 +12,6 @@
<depend package="roscpp"/>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
<depend package="mechanism_msgs" />
<depend package="sensor_msgs"/>
<depend package="pr2_msgs"/>
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -6,7 +6,6 @@
<depend package="roscpp" />
<depend package="std_msgs" />
<depend package="nav_msgs" />
- <depend package="robot_msgs" />
<depend package="mocap_msgs" />
<depend package="phase_space" />
<depend package="tf" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -22,7 +22,6 @@
<depend package="opencv_latest" />
<depend package="sensor_msgs" />
<depend package="pr2_msgs" />
- <depend package="robot_msgs" />
<depend package="geometry_msgs" />
<depend package="diagnostic_msgs" />
<depend package="angles" />
Modified: pkg/trunk/drivers/simulator/test_gazebo_plugin/manifest.xml
===================================================================
--- pkg/trunk/drivers/simulator/test_gazebo_plugin/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/drivers/simulator/test_gazebo_plugin/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -9,5 +9,4 @@
<depend package="gazebo_plugin"/>
<depend package="examples_gazebo" />
<depend package="gazebo_worlds" />
- <depend package="robot_msgs" />
</package>
Modified: pkg/trunk/drivers/simulator/test_pr2_collision_gazebo/manifest.xml
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_collision_gazebo/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/drivers/simulator/test_pr2_collision_gazebo/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -10,5 +10,4 @@
<depend package="pr2_gazebo" />
<depend package="pr2_ogre" />
<depend package="gazebo_worlds" />
- <depend package="robot_msgs" />
</package>
Modified: pkg/trunk/drivers/ups/apcupsd_node/manifest.xml
===================================================================
--- pkg/trunk/drivers/ups/apcupsd_node/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/drivers/ups/apcupsd_node/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -9,7 +9,6 @@
<url>http://pr.willowgarage.com/wiki/apcupsd_node</url>
<depend package="rospy"/>
<depend package="diagnostic_msgs"/>
- <depend package="robot_msgs"/>
<rosdep name="apcupsd"/>
</package>
Modified: pkg/trunk/highlevel/doors/doors_core/manifest.xml
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/highlevel/doors/doors_core/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -11,7 +11,6 @@
<depend package="roscpp" />
<depend package="std_msgs" />
- <depend package="robot_msgs" />
<depend package="diagnostic_msgs" />
<depend package="manipulation_msgs" />
<depend package="door_msgs" />
Modified: pkg/trunk/highlevel/move_arm/manifest.xml
===================================================================
--- pkg/trunk/highlevel/move_arm/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/highlevel/move_arm/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -12,7 +12,6 @@
<depend package="roscpp"/>
<depend package="rosconsole"/>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
<depend package="motion_planning_msgs"/>
<depend package="geometry_msgs"/>
<depend package="mapping_msgs"/>
Modified: pkg/trunk/highlevel/plugs/plugs_core/manifest.xml
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/highlevel/plugs/plugs_core/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -10,7 +10,6 @@
<depend package="roscpp" />
<depend package="geometry_msgs" />
- <depend package="robot_msgs" />
<depend package="deprecated_srvs" />
<depend package="mechanism_msgs" />
<depend package="std_msgs" />
Modified: pkg/trunk/highlevel/plugs/plugs_functions/manifest.xml
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_functions/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/highlevel/plugs/plugs_functions/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -9,7 +9,6 @@
<review status="experimental" notes="beta"/>
<depend package="roscpp" />
- <depend package="robot_msgs" />
<depend package="tf"/>
Modified: pkg/trunk/highlevel/safety/safety_core/manifest.xml
===================================================================
--- pkg/trunk/highlevel/safety/safety_core/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/highlevel/safety/safety_core/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -9,7 +9,6 @@
<review status="experimental" notes="beta"/>
<depend package="roscpp" />
- <depend package="robot_msgs" />
<depend package="robot_actions" />
<depend package="pr2_robot_actions" />
<depend package="plug_onbase_detector" />
Modified: pkg/trunk/highlevel/writing/writing_core/manifest.xml
===================================================================
--- pkg/trunk/highlevel/writing/writing_core/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/highlevel/writing/writing_core/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -11,7 +11,6 @@
<depend package="roscpp" />
<depend package="roslib" />
- <depend package="robot_msgs" />
<depend package="robot_actions" />
<depend package="pr2_robot_actions" />
<depend package="point_cloud_mapping" />
Modified: pkg/trunk/mapping/annotated_map_msgs/manifest.xml
===================================================================
--- pkg/trunk/mapping/annotated_map_msgs/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/mapping/annotated_map_msgs/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -7,7 +7,6 @@
<review status="unreviewed" notes=""/>
<url>http://pr.willowgarage.com/wiki/annotated_map_msgs</url>
<depend package="std_msgs"/>
- <depend package="robot_msgs"/>
<depend package="sensor_msgs"/>
<depend package="geometry_msgs"/>
Modified: pkg/trunk/mapping/annotated_planar_patch_map/manifest.xml
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/mapping/annotated_planar_patch_map/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -10,7 +10,6 @@
<depend package="roscpp" />
<depend package="std_msgs"/>
- <depend package="robot_msgs" />
<depend package="mapping_msgs" />
<depend package="sensor_msgs" />
<depend package="geometry_msgs" />
Modified: pkg/trunk/mapping/collision_map/manifest.xml
===================================================================
--- pkg/trunk/mapping/collision_map/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/mapping/collision_map/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -11,7 +11,6 @@
<depend package="roscpp" />
<depend package="std_msgs" />
<depend package="tf" />
- <depend package="robot_msgs" />
<depend package="visualization_msgs" />
<depend package="tabletop_msgs" />
<depend package="tabletop_srvs" />
Modified: pkg/trunk/mapping/door_stereo_detector/manifest.xml
===================================================================
--- pkg/trunk/mapping/door_stereo_detector/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/mapping/door_stereo_detector/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -9,7 +9,6 @@
<review status="experimental" notes="beta"/>
<depend package="roscpp" />
- <depend package="robot_msgs" />
<depend package="mapping_msgs" />
<depend package="kdl" />
<depend package="angles" />
Modified: pkg/trunk/mapping/door_tracker/manifest.xml
===================================================================
--- pkg/trunk/mapping/door_tracker/manifest.xml 2009-08-08 20:20:11 UTC (rev 21189)
+++ pkg/trunk/mapping/door_tracker/manifest.xml 2009-08-08 20:21:30 UTC (rev 21190)
@@ -12,7 +12,6 @@
<depend package="roscpp" />
<depend package="laser_scan" />
<depend package="sensor_msgs" />
- <depend package="robot_msgs" />
<depend package="geometry_msgs" />
<depend package="door_msgs" />
<depend package="an...
[truncated message content] |
|
From: <tf...@us...> - 2009-08-09 00:07:01
|
Revision: 21196
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21196&view=rev
Author: tfoote
Date: 2009-08-09 00:06:54 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
Switching IMU to sensor_msgs/Imu related to #2277
Modified Paths:
--------------
pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml
pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp
pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Imu.msg
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/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp
pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc
pkg/trunk/stacks/imu_drivers/imu_node/manifest.xml
pkg/trunk/util/logsetta/imu/imu_extract.cpp
Modified: pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml 2009-08-08 23:50:51 UTC (rev 21195)
+++ pkg/trunk/calibration/wheel_odometry_calibration/manifest.xml 2009-08-09 00:06:54 UTC (rev 21196)
@@ -5,6 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="tf" />
<depend package="nav_msgs" />
+ <depend package="sensor_msgs" />
<depend package="roscpp" />
<depend package="pr2_mechanism_controllers" />
</package>
Modified: pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp 2009-08-08 23:50:51 UTC (rev 21195)
+++ pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp 2009-08-09 00:06:54 UTC (rev 21196)
@@ -90,9 +90,9 @@
void odom_calib::imu_callback()
{
_imu_mutex.lock();
- double tmp, yaw; Transform tf;
- poseMsgToTF(_imu.pose_with_rates.pose, tf);
- tf.getBasis().getEulerZYX(yaw, tmp, tmp);
+ double tmp, yaw; btQuaternion tf;
+ quaternionMsgToTF(_imu.orientation, tf);
+ btMatrix3x3(tf).getEulerZYX(yaw, tmp, tmp);
if (!_imu_active){
_imu_begin = yaw;
Modified: pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h 2009-08-08 23:50:51 UTC (rev 21195)
+++ pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.h 2009-08-09 00:06:54 UTC (rev 21196)
@@ -44,7 +44,7 @@
// messages
#include "nav_msgs/Odometry.h"
#include "geometry_msgs/Twist.h"
-#include "geometry_msgs/PoseWithRatesStamped.h"
+#include "sensor_msgs/Imu.h"
#include "mechanism_msgs/MechanismState.h"
namespace calibration
@@ -80,7 +80,7 @@
// messages to receive
nav_msgs::Odometry _odom;
- geometry_msgs::PoseWithRatesStamped _imu;
+ sensor_msgs::Imu _imu;
mechanism_msgs::MechanismState _mech;
// estimated robot pose message to send
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Imu.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Imu.msg 2009-08-08 23:50:51 UTC (rev 21195)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Imu.msg 2009-08-09 00:06:54 UTC (rev 21196)
@@ -1,7 +1,12 @@
# This is a message to hold IMU data
-Header stamp
+Header header
+
+geometry_msgs/Quaternion orientation
+float64[9] orientation_covarience # Row major about x, y, z axes
+
geometry_msgs/Vector3 angular_velocity
-float64[9] angualar_velocity_covarience # Row major about z, y, x axes
+float64[9] angualar_velocity_covarience # Row major about x, y, z axes
+
geometry_msgs/Vector3 linear_acceleration
float64[9] linear_acceleration_covarience # Row major x, y z
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 23:50:51 UTC (rev 21195)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/include/robot_pose_ekf/odom_estimation_node.h 2009-08-09 00:06:54 UTC (rev 21196)
@@ -47,7 +47,7 @@
// messages
#include "nav_msgs/Odometry.h"
#include "geometry_msgs/Twist.h"
-#include "geometry_msgs/PoseWithRatesStamped.h"
+#include "sensor_msgs/Imu.h"
#include "geometry_msgs/PoseStamped.h"
#include "deprecated_msgs/VOPose.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
@@ -70,7 +70,7 @@
*/
typedef boost::shared_ptr<nav_msgs::Odometry const> OdomConstPtr;
-typedef boost::shared_ptr<geometry_msgs::PoseWithRatesStamped const> ImuConstPtr;
+typedef boost::shared_ptr<sensor_msgs::Imu const> ImuConstPtr;
typedef boost::shared_ptr<geometry_msgs::Twist const> VelConstPtr;
class OdomEstimationNode
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/manifest.xml
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/manifest.xml 2009-08-08 23:50:51 UTC (rev 21195)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/manifest.xml 2009-08-09 00:06:54 UTC (rev 21196)
@@ -10,6 +10,7 @@
<depend package="bfl" />
<depend package="std_msgs" />
<depend package="geometry_msgs" />
+<depend package="sensor_msgs" />
<depend package="deprecated_msgs" />
<depend package="nav_msgs" />
<depend package="tf" />
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 23:50:51 UTC (rev 21195)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2009-08-09 00:06:54 UTC (rev 21196)
@@ -209,7 +209,9 @@
boost::mutex::scoped_lock lock(imu_mutex_);
imu_stamp_ = imu->header.stamp;
imu_time_ = Time::now();
- poseMsgToTF(imu->pose_with_rates.pose, imu_meas_);
+ btQuaternion orientation;
+ quaternionMsgToTF(imu->orientation, orientation);
+ imu_meas_ = btTransform(orientation, btVector3(0,0,0));
my_filter_.addMeasurement(Stamped<Transform>(imu_meas_, imu_stamp_, "imu", "base_footprint"));
// activate imu
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp 2009-08-08 23:50:51 UTC (rev 21195)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/test/test_robot_pose_ekf.cpp 2009-08-09 00:06:54 UTC (rev 21196)
@@ -38,7 +38,7 @@
#include <gtest/gtest.h>
#include "ros/node.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
-#include "geometry_msgs/PoseWithRatesStamped.h"
+#include "sensor_msgs/Imu.h"
using namespace ros;
@@ -57,7 +57,7 @@
{
public:
geometry_msgs::PoseWithCovarianceStamped ekf_msg_, ekf_begin_;
- geometry_msgs::PoseWithRatesStamped odom_msg_;
+ sensor_msgs::Imu odom_msg_;
double ekf_counter_, odom_counter_;
Time ekf_time_begin_, odom_time_begin_;
Node* node_;
@@ -136,26 +136,17 @@
EXPECT_GT(Duration(ekf_msg_.header.stamp - ekf_time_begin_).toSec(), ekf_duration * 0.85);
// check if ekf time is same as odom time
- EXPECT_LT(Duration(ekf_time_begin_ - odom_time_begin_).toSec(), 1.0);
- EXPECT_GT(Duration(ekf_time_begin_ - odom_time_begin_).toSec(), -1.0);
- EXPECT_LT(Duration(ekf_msg_.header.stamp - odom_msg_.header.stamp).toSec(), 1.0);
- EXPECT_GT(Duration(ekf_msg_.header.stamp - odom_msg_.header.stamp).toSec(), -1.0);
+ EXPECT_NEAR(ekf_time_begin_.toSec(), odom_time_begin_.toSec(), 1.0);
+ EXPECT_NEAR(ekf_msg_.header.stamp.toSec(), odom_msg_.header.stamp.toSec(), 1.0);
// check filter result
- EXPECT_GT(ekf_begin_.pose.pose.position.x, 0.038043 - EPS_trans);
- EXPECT_LT(ekf_begin_.pose.pose.position.x, 0.038043 + EPS_trans);
- EXPECT_GT(ekf_begin_.pose.pose.position.y, -0.001618 - EPS_trans);
- EXPECT_LT(ekf_begin_.pose.pose.position.y, -0.001618 + EPS_trans);
- EXPECT_GT(ekf_begin_.pose.pose.position.z, 0.000000 - EPS_trans);
- EXPECT_LT(ekf_begin_.pose.pose.position.z, 0.000000 + EPS_trans);
- EXPECT_GT(ekf_begin_.pose.pose.orientation.x, 0.000000 - EPS_rot);
- EXPECT_LT(ekf_begin_.pose.pose.orientation.x, 0.000000 + EPS_rot);
- EXPECT_GT(ekf_begin_.pose.pose.orientation.y, 0.000000 - EPS_rot);
- EXPECT_LT(ekf_begin_.pose.pose.orientation.y, 0.000000 + EPS_rot);
- EXPECT_GT(ekf_begin_.pose.pose.orientation.z, 0.088400 - EPS_rot);
- EXPECT_LT(ekf_begin_.pose.pose.orientation.z, 0.088400 + EPS_rot);
- EXPECT_GT(ekf_begin_.pose.pose.orientation.w, 0.996085 - EPS_rot);
- EXPECT_LT(ekf_begin_.pose.pose.orientation.w, 0.996085 + EPS_rot);
+ EXPECT_NEAR(ekf_begin_.pose.pose.position.x, 0.038043, EPS_trans);
+ EXPECT_NEAR(ekf_begin_.pose.pose.position.y, -0.001618, EPS_trans);
+ EXPECT_NEAR(ekf_begin_.pose.pose.position.z, 0.000000, EPS_trans);
+ EXPECT_NEAR(ekf_begin_.pose.pose.orientation.x, 0.000000, EPS_rot);
+ EXPECT_NEAR(ekf_begin_.pose.pose.orientation.y, 0.000000, EPS_rot);
+ EXPECT_NEAR(ekf_begin_.pose.pose.orientation.z, 0.088400, EPS_rot);
+ EXPECT_NEAR(ekf_begin_.pose.pose.orientation.w, 0.996085, EPS_rot);
SUCCEED();
}
Modified: pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc
===================================================================
--- pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc 2009-08-08 23:50:51 UTC (rev 21195)
+++ pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc 2009-08-09 00:06:54 UTC (rev 21196)
@@ -41,7 +41,7 @@
@section information Information
-The IMU provides a single message PoseWithRatesStamped messaged at 100Hz
+The IMU provides a single message Imu messaged at 100Hz
which is taken from the 3DMGX2 ACCEL_ANGRATE_ORIENTATION message.
<hr>
@@ -62,7 +62,7 @@
- None
Publishes to (name / type):
-- @b "imu_data"/<a href="../../std_msgs/html/classstd__msgs_1_1PoseWithRatesStamped.html">std_msgs/PoseWithRatesStamped</a> : the imu data
+- @b "imu_data"/<a href="../../sensor_msgs/html/classstd__msgs_1_1Imu.html">sensor_msgs/Imu</a> : the imu data
- @b "/diagnostics"/<a href="../../diagnostic_msgs/html/classrobot__msgs_1_1DiagnosticMessage.html">diagnostic_msgs/DiagnosticMessage</a> : diagnostic status information.
<hr>
@@ -98,7 +98,7 @@
#include "diagnostic_updater/diagnostic_updater.h"
#include "diagnostic_updater/update_functions.h"
-#include "geometry_msgs/PoseWithRatesStamped.h"
+#include "sensor_msgs/Imu.h"
#include "std_srvs/Empty.h"
#include "imu_node/GetBoolStatus.h"
@@ -113,7 +113,7 @@
{
public:
ms_3dmgx2_driver::IMU imu;
- geometry_msgs::PoseWithRatesStamped reading;
+ sensor_msgs::Imu reading;
string port;
@@ -154,7 +154,7 @@
desired_freq_(100),
freq_diag_(diagnostic_updater::FrequencyStatusParam(&desired_freq_, &desired_freq_, 0.05))
{
- imu_data_pub_ = node_handle_.advertise<geometry_msgs::PoseWithRatesStamped>("imu_data", 100);
+ imu_data_pub_ = node_handle_.advertise<sensor_msgs::Imu>("imu_data", 100);
add_offset_serv_ = node_handle_.advertiseService("imu/add_offset", &ImuNode::addOffset, this);
calibrate_serv_ = node_handle_.advertiseService("imu/calibrate", &ImuNode::calibrate, this);
@@ -284,22 +284,22 @@
ROS_WARN("Gathering data took %f ms. Nominal is 10ms.", 1000 * (endtime - starttime));
prevtime = starttime;
- reading.pose_with_rates.acceleration.linear.x = accel[0];
- reading.pose_with_rates.acceleration.linear.y = accel[1];
- reading.pose_with_rates.acceleration.linear.z = accel[2];
+ reading.linear_acceleration.x = accel[0];
+ reading.linear_acceleration.y = accel[1];
+ reading.linear_acceleration.z = accel[2];
- reading.pose_with_rates.velocity.angular.x = angrate[0];
- reading.pose_with_rates.velocity.angular.y = angrate[1];
- reading.pose_with_rates.velocity.angular.z = angrate[2];
+ reading.angular_velocity.x = angrate[0];
+ reading.angular_velocity.y = angrate[1];
+ reading.angular_velocity.z = angrate[2];
- btTransform pose(btMatrix3x3(orientation[0], orientation[1], orientation[2],
- orientation[3], orientation[4], orientation[5],
- orientation[6], orientation[7], orientation[8]),
- btVector3(0,0,0));
-
- tf::poseTFToMsg(pose, reading.pose_with_rates.pose);
+ btQuaternion quat;
+ btMatrix3x3(orientation[0], orientation[1], orientation[2],
+ orientation[3], orientation[4], orientation[5],
+ orientation[6], orientation[7], orientation[8]).getRotation(quat);
+ tf::quaternionTFToMsg(quat, reading.orientation);
+
reading.header.stamp = ros::Time::now().fromNSec(time);
reading.header.frame_id = frameid_;
Modified: pkg/trunk/stacks/imu_drivers/imu_node/manifest.xml
===================================================================
--- pkg/trunk/stacks/imu_drivers/imu_node/manifest.xml 2009-08-08 23:50:51 UTC (rev 21195)
+++ pkg/trunk/stacks/imu_drivers/imu_node/manifest.xml 2009-08-09 00:06:54 UTC (rev 21196)
@@ -6,7 +6,7 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
- <depend package="std_msgs"/>
+ <depend package="sensor_msgs"/>
<depend package="3dmgx2_driver"/>
<depend package="self_test"/>
<depend package="diagnostic_updater"/>
Modified: pkg/trunk/util/logsetta/imu/imu_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/imu/imu_extract.cpp 2009-08-08 23:50:51 UTC (rev 21195)
+++ pkg/trunk/util/logsetta/imu/imu_extract.cpp 2009-08-09 00:06:54 UTC (rev 21196)
@@ -32,19 +32,19 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-#include "geometry_msgs/PoseWithRatesStamped.h"
+#include "sensor_msgs/Imu.h"
#include <string>
#include "rosrecord/Player.h"
-void imu_callback(std::string name, geometry_msgs::PoseWithRatesStamped* imu, ros::Time t, ros::Time t_no_use, void* f)
+void imu_callback(std::string name, sensor_msgs::Imu* imu, ros::Time t, ros::Time t_no_use, void* f)
{
FILE* file = (FILE*)f;
fprintf(file, "%.5f %.5f %.5f %.5f %.5f %.5f %.5f %.5f\n",
t.toSec(),
imu->header.stamp.toSec(),
- imu->pose_with_rates.acceleration.linear.x, imu->pose_with_rates.acceleration.linear.y, imu->pose_with_rates.acceleration.linear.z,
- imu->pose_with_rates.velocity.angular.x, imu->pose_with_rates.velocity.angular.y, imu->pose_with_rates.velocity.angular.z);
+ imu->linear_acceleration.x, imu->linear_acceleration.y, imu->linear_acceleration.z,
+ imu->angular_velocity.x, imu->angular_velocity.y, imu->angular_velocity.z);
}
int main(int argc, char **argv)
@@ -63,7 +63,7 @@
FILE* file = fopen("imu.txt", "w");
- player.addHandler<geometry_msgs::PoseWithRatesStamped>(std::string("*"), &imu_callback, file);
+ player.addHandler<sensor_msgs::Imu>(std::string("*"), &imu_callback, file);
while(player.nextMsg()) {}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jfa...@us...> - 2009-08-09 01:24:11
|
Revision: 21203
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21203&view=rev
Author: jfaustwg
Date: 2009-08-09 01:23:59 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
Fixes for diagnostic_msgs::KeyValue::label -> key
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_inverse_dynamics_controller.cpp
pkg/trunk/demos/led_demo/led_status_demo.py
pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp
pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
pkg/trunk/pr2/qualification/scripts/run_selftest.py
pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
pkg/trunk/stacks/camera_drivers/dcam/src/nodes/stereodcam.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py
pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h
pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp
pkg/trunk/stacks/hardware_test/diagnostics_analysis/export_csv.py
pkg/trunk/stacks/hardware_test/self_test/src/run_selftest.cpp
pkg/trunk/stacks/hardware_test/self_test/src/selftest_example.cpp
pkg/trunk/stacks/hardware_test/self_test/src/selftest_rostest.cpp
pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc
pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp
pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ek1122.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ethercat_hardware.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg014.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg0x.cpp
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node.cpp
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node_simulator.cpp
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/pr2_power_board/pr2_power_board_panel.py
pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -702,18 +702,18 @@
for(unsigned int i=0; i < c_->joint_pd_controllers_.size(); i++)
{
- v.label = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Actual";
+ v.key = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Actual";
v.value = c_->joint_pd_controllers_[i]->joint_state_->position_;
values.push_back(v);
// ROS_INFO("Diagnostics %d: 1",i);
- v.label = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Command";
+ v.key = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Command";
c_->joint_pd_controllers_[i]->getCommand(cmd);
v.value = cmd.positions[0];
values.push_back(v);
- v.label = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Error (Command-Actual)";
+ v.key = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Error (Command-Actual)";
v.value = cmd.positions[0] - c_->joint_pd_controllers_[i]->joint_state_->position_;
values.push_back(v);
@@ -721,35 +721,35 @@
}
- v.label = "Trajectory id";
+ v.key = "Trajectory id";
v.value = current_trajectory_id_;
values.push_back(v);
// ROS_INFO("Diagnostics 2");
- v.label = "Trajectory Status:: ";
+ v.key = "Trajectory Status:: ";
std::map<int, int>::const_iterator it = joint_trajectory_status_.find((int)current_trajectory_id_);
if(it == joint_trajectory_status_.end())
{
- v.label += "UNKNOWN";
+ v.key += "UNKNOWN";
v.value = -1;
}
else
{
- v.label += JointTrajectoryStatusString[it->second];
+ v.key += JointTrajectoryStatusString[it->second];
v.value = it->second;
}
values.push_back(v);
// ROS_INFO("Diagnostics 3");
- v.label = "Trajectory Current Time";
+ v.key = "Trajectory Current Time";
v.value = c_->current_time_-c_->trajectory_start_time_;
values.push_back(v);
// ROS_INFO("Diagnostics 4");
- v.label = "Trajectory Expected End Time (computed)";
+ v.key = "Trajectory Expected End Time (computed)";
v.value = c_->trajectory_end_time_-c_->trajectory_start_time_;
values.push_back(v);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -288,55 +288,55 @@
status.name = ros_node_.getName();
status.message = control_state_;
- v.label = "Error.x";
+ v.key = "Error.x";
v.value = error_x_;
values.push_back(v);
- v.label = "Error.y";
+ v.key = "Error.y";
v.value = error_y_;
values.push_back(v);
- v.label = "Error.th";
+ v.key = "Error.th";
v.value = error_th_;
values.push_back(v);
- v.label = "Goal.x";
+ v.key = "Goal.x";
v.value = goal_.q_[0];
values.push_back(v);
- v.label = "Goal.y";
+ v.key = "Goal.y";
v.value = goal_.q_[1];
values.push_back(v);
- v.label = "Goal.th";
+ v.key = "Goal.th";
v.value = goal_.q_[2];
values.push_back(v);
- v.label = "Number of waypoints";
+ v.key = "Number of waypoints";
v.value = path_msg_.get_points_size();
values.push_back(v);
- v.label = "Controller frequency (Hz)";
+ v.key = "Controller frequency (Hz)";
v.value = controller_frequency_;
values.push_back(v);
- v.label = "Max update delta time (s)";
+ v.key = "Max update delta time (s)";
v.value = max_update_time_;
values.push_back(v);
- v.label = "Control topic name";
+ v.key = "Control topic name";
v.value = control_topic_name_;
values.push_back(v);
- v.label = "Global frame";
+ v.key = "Global frame";
v.value = global_frame_;
values.push_back(v);
- v.label = "Path input topic name";
+ v.key = "Path input topic name";
v.value = path_input_topic_name_;
values.push_back(v);
- v.label = "Trajectory type";
+ v.key = "Trajectory type";
v.value = trajectory_type_;
values.push_back(v);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -948,93 +948,93 @@
for(unsigned int i=0; i < joint_pv_controllers_.size(); i++)
{
- v.label = joint_pv_controllers_[i]->getJointName() + "/Position/Actual";
+ v.key = joint_pv_controllers_[i]->getJointName() + "/Position/Actual";
v.value = joint_pv_controllers_[i]->joint_state_->position_;
values.push_back(v);
- v.label = joint_pv_controllers_[i]->getJointName() + "/Position/Command";
+ v.key = joint_pv_controllers_[i]->getJointName() + "/Position/Command";
joint_pv_controllers_[i]->getCommand(cmd);
v.value = cmd.positions[0];
values.push_back(v);
- v.label = joint_pv_controllers_[i]->getJointName() + "/Position/Error (Command-Actual)";
+ v.key = joint_pv_controllers_[i]->getJointName() + "/Position/Error (Command-Actual)";
v.value = cmd.positions[0] - joint_pv_controllers_[i]->joint_state_->position_;
values.push_back(v);
}
- v.label = "Trajectory id";
+ v.key = "Trajectory id";
v.value = current_trajectory_id_;
values.push_back(v);
- v.label = "Trajectory Status:: ";
+ v.key = "Trajectory Status:: ";
if(current_trajectory_id_ < 0)
{
- v.label += "AT REST";
+ v.key += "AT REST";
v.value = -1;
}
else
{
- v.label += JointTrajectoryStatusString[joint_trajectory_status_[current_trajectory_id_]];
+ v.key += JointTrajectoryStatusString[joint_trajectory_status_[current_trajectory_id_]];
v.value = joint_trajectory_status_[current_trajectory_id_];
}
values.push_back(v);
- v.label = "Trajectory Current Time";
+ v.key = "Trajectory Current Time";
v.value = current_time_-trajectory_start_time_;
values.push_back(v);
- v.label = "Trajectory Expected End Time (computed)";
+ v.key = "Trajectory Expected End Time (computed)";
v.value = trajectory_end_time_-trajectory_start_time_;
values.push_back(v);
- v.label = "Current trajectory queue index";
+ v.key = "Current trajectory queue index";
v.value = current_trajectory_index_;
values.push_back(v);
- v.label = "Number queued trajectories";
+ v.key = "Number queued trajectories";
v.value = num_trajectory_available_;
values.push_back(v);
- v.label = "Next queue free index";
+ v.key = "Next queue free index";
v.value = next_free_index_;
values.push_back(v);
- v.label = "Number joints";
+ v.key = "Number joints";
v.value = num_joints_;
values.push_back(v);
- v.label = "Velocity scaling factor";
+ v.key = "Velocity scaling factor";
v.value = velocity_scaling_factor_;
values.push_back(v);
- v.label = "Trajectory wait timeout";
+ v.key = "Trajectory wait timeout";
v.value = trajectory_wait_timeout_;
values.push_back(v);
- v.label = "Max allowed update time";
+ v.key = "Max allowed update time";
v.value = max_allowed_update_time_;
values.push_back(v);
- v.label = "Diagnostics publish time";
+ v.key = "Diagnostics publish time";
v.value = diagnostics_publish_delta_time_;
values.push_back(v);
- v.label = "Max trajectory queue size";
+ v.key = "Max trajectory queue size";
v.value = max_trajectory_queue_size_;
values.push_back(v);
- v.label = "Listen topic name";
+ v.key = "Listen topic name";
v.value = listen_topic_name_;
values.push_back(v);
- v.label = "Trajectory set service";
+ v.key = "Trajectory set service";
v.value = name_ + "/TrajectoryStart";
values.push_back(v);
- v.label = "Trajectory query service";
+ v.key = "Trajectory query service";
v.value = name_ + "/TrajectoryQuery";
values.push_back(v);
- v.label = "Trajectory cancel service";
+ v.key = "Trajectory cancel service";
v.value = name_ + "/TrajectoryCancel";
values.push_back(v);
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -119,10 +119,10 @@
diagnostics_.status[0].name = "Wrench Controller";
diagnostics_.status[0].values.resize(2);
diagnostics_.status[0].values[0].value = "3";
- diagnostics_.status[0].values[0].label = "TestValueLabel";
+ diagnostics_.status[0].values[0].key = "TestValueLabel";
diagnostics_.status[0].values[1].value = "TestValue";
- diagnostics_.status[0].values[1].label = "TestLabel";
+ diagnostics_.status[0].values[1].key = "TestLabel";
diagnostics_time_ = ros::Time::now();
diagnostics_interval_ = ros::Duration().fromSec(1.0);
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_inverse_dynamics_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_inverse_dynamics_controller.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_inverse_dynamics_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -124,10 +124,10 @@
diagnostics_.status[0].name = "Inverse Dynamics Controller";
diagnostics_.status[0].values.resize(2);
diagnostics_.status[0].values[0].value = "3";
- diagnostics_.status[0].values[0].label = "TestValueLabel";
+ diagnostics_.status[0].values[0].key = "TestValueLabel";
diagnostics_.status[0].values[1].value = "TestValue";
- diagnostics_.status[0].values[1].label = "TestLabel";
+ diagnostics_.status[0].values[1].key = "TestLabel";
diagnostics_time_ = ros::Time::now();
diagnostics_interval_ = ros::Duration().fromSec(1.0);
Modified: pkg/trunk/demos/led_demo/led_status_demo.py
===================================================================
--- pkg/trunk/demos/led_demo/led_status_demo.py 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/demos/led_demo/led_status_demo.py 2009-08-09 01:23:59 UTC (rev 21203)
@@ -50,7 +50,7 @@
## @TODO process byte level
print "Name: %s \nMessage: %s"%(s.name, s.message)
for v in s.strings + s.values:
- print " %s: %s" % (v.label, v.value)
+ print " %s: %s" % (v.key, v.value)
sys.stdout.flush()
def battery_callback(state):
Modified: pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp
===================================================================
--- pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -170,9 +170,9 @@
status.level = 0;
status.message = "Retrieved image successfully.";
status.set_values_size(2);
- status.values[0].label = "Width";
+ status.values[0].key = "Width";
status.values[0].value = images.images[0].width;
- status.values[1].label = "Height";
+ status.values[1].key = "Height";
status.values[1].value = images.images[0].height;
}
}
Modified: pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -346,75 +346,75 @@
status.name = "Door Reactive Planner";
status.level = 0;
#warning These need a MACRO/function to do num to string
- v.label = "Goal x";
+ v.key = "Goal x";
v.value = goal_.x;
values.push_back(v);
- v.label = "Goal y";
+ v.key = "Goal y";
v.value = goal_.y;
values.push_back(v);
- v.label = "Goal theta";
+ v.key = "Goal theta";
v.value = goal_.th;
values.push_back(v);
- v.label = "Carrot x";
+ v.key = "Carrot x";
v.value = carrot_.x;
values.push_back(v);
- v.label = "Carrot y";
+ v.key = "Carrot y";
v.value = carrot_.y;
values.push_back(v);
- v.label = "Carrot theta";
+ v.key = "Carrot theta";
v.value = carrot_.th;
values.push_back(v);
- v.label = "Centerline angle";
+ v.key = "Centerline angle";
v.value = centerline_angle_;
values.push_back(v);
- v.label = "Travel angle";
+ v.key = "Travel angle";
v.value = travel_angle_;
values.push_back(v);
- v.label = "Sideslip.x";
+ v.key = "Sideslip.x";
v.value = vector_along_door_.x;
values.push_back(v);
- v.label = "Sideslip.y";
+ v.key = "Sideslip.y";
v.value = vector_along_door_.y;
values.push_back(v);
- v.label = "Plan delta angle";
+ v.key = "Plan delta angle";
v.value = delta_angle_;
values.push_back(v);
- v.label = "Plan length";
+ v.key = "Plan length";
v.value = plan_length_;
values.push_back(v);
- v.label = "Centerline distance";
+ v.key = "Centerline distance";
v.value = centerline_distance_;
values.push_back(v);
- v.label = "Current x";
+ v.key = "Current x";
v.value = current_position_.x;
values.push_back(v);
- v.label = "Current y";
+ v.key = "Current y";
v.value = current_position_.y;
values.push_back(v);
- v.label = "Current th";
+ v.key = "Current th";
v.value = current_position_.th;
values.push_back(v);
- v.label = "Cell distance from obstacles";
+ v.key = "Cell distance from obstacles";
v.value = cell_distance_from_obstacles_;
values.push_back(v);
- v.label = "Current position in collision";
+ v.key = "Current position in collision";
v.value = current_position_in_collision_;
values.push_back(v);
Modified: pkg/trunk/pr2/qualification/scripts/run_selftest.py
===================================================================
--- pkg/trunk/pr2/qualification/scripts/run_selftest.py 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/pr2/qualification/scripts/run_selftest.py 2009-08-09 01:23:59 UTC (rev 21203)
@@ -95,9 +95,7 @@
html += "<table border=\"1\" cellpadding=\"2\" cellspacing=\"0\">\n"
html += "<tr><b><td>Label</td><td>Value</td></b></tr>\n"
for val in stat.values:
- html += "<tr><td>%s</td><td>%f</td></tr>\n" % (val.label, val.value)
- for val in stat.strings:
- html += "<tr><td>%s</td><td>%s</td></tr>\n" % (val.label, val.value)
+ html += "<tr><td>%s</td><td>%s</td></tr>\n" % (val.key, val.value)
html += "</table></p>\n"
html += "<hr size=\"2\">\n"
Modified: pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -323,11 +323,11 @@
}
status.set_values_size(3);
- status.values[0].label = "Images in interval";
+ status.values[0].key = "Images in interval";
status.values[0].value = count_;
- status.values[1].label = "Desired frequency";
+ status.values[1].key = "Desired frequency";
status.values[1].value = desired_freq_;
- status.values[2].label = "Actual frequency";
+ status.values[2].key = "Actual frequency";
status.values[2].value = freq;
printf("%g fps\n", freq);
Modified: pkg/trunk/stacks/camera_drivers/dcam/src/nodes/stereodcam.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/dcam/src/nodes/stereodcam.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/camera_drivers/dcam/src/nodes/stereodcam.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -429,11 +429,11 @@
}
status.set_values_size(3);
- status.values[0].label = "Images in interval";
+ status.values[0].key = "Images in interval";
status.values[0].value = count_;
- status.values[1].label = "Desired frequency";
+ status.values[1].key = "Desired frequency";
status.values[1].value = desired_freq_;
- status.values[2].label = "Actual frequency";
+ status.values[2].key = "Actual frequency";
status.values[2].value = freq;
printf("%g fps\n", freq);
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -314,11 +314,11 @@
}
status.set_values_size(3);
- status.values[0].label = "Images in interval";
+ status.values[0].key = "Images in interval";
status.values[0].value = count_;
- status.values[1].label = "Desired frequency";
+ status.values[1].key = "Desired frequency";
status.values[1].value = desired_freq_;
- status.values[2].label = "Actual frequency";
+ status.values[2].key = "Actual frequency";
status.values[2].value = freq;
count_ = 0;
@@ -362,15 +362,15 @@
}
status.set_values_size(5);
- status.values[0].label = "Camera Frame Rate";
+ status.values[0].key = "Camera Frame Rate";
status.values[0].value = frame_rate;
- status.values[1].label = "Recent % Frames Completed";
+ status.values[1].key = "Recent % Frames Completed";
status.values[1].value = recent_ratio * 100.0f;
- status.values[2].label = "Overall % Frames Completed";
+ status.values[2].key = "Overall % Frames Completed";
status.values[2].value = total_ratio * 100.0f;
- status.values[3].label = "Frames Completed";
+ status.values[3].key = "Frames Completed";
status.values[3].value = completed;
- status.values[4].label = "Frames Dropped";
+ status.values[4].key = "Frames Dropped";
status.values[4].value = dropped;
}
@@ -433,19 +433,19 @@
#endif
status.set_values_size(7);
- status.values[0].label = "Recent % Packets Received";
+ status.values[0].key = "Recent % Packets Received";
status.values[0].value = recent_ratio * 100.0f;
- status.values[1].label = "Overall % Packets Received";
+ status.values[1].key = "Overall % Packets Received";
status.values[1].value = total_ratio * 100.0f;
- status.values[2].label = "Received Packets";
+ status.values[2].key = "Received Packets";
status.values[2].value = received;
- status.values[3].label = "Missed Packets";
+ status.values[3].key = "Missed Packets";
status.values[3].value = missed;
- status.values[4].label = "Requested Packets";
+ status.values[4].key = "Requested Packets";
status.values[4].value = requested;
- status.values[5].label = "Resent Packets";
+ status.values[5].key = "Resent Packets";
status.values[5].value = resent;
- status.values[6].label = "Data Rate (bytes/s)";
+ status.values[6].key = "Data Rate (bytes/s)";
status.values[6].value = data_rate;
}
@@ -465,7 +465,7 @@
}
status.set_values_size(1);
- status.values[0].label = "Erroneous Packets";
+ status.values[0].key = "Erroneous Packets";
status.values[0].value = erroneous;
}
Modified: pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py 2009-08-09 01:23:59 UTC (rev 21203)
@@ -56,10 +56,8 @@
## Also stores last time of message, allows stale checks.
def status_to_map(status):
str_map = {}
- for s in status.strings:
- str_map[s.label] = s.value;
for val in status.values:
- str_map[val.label] = val.value;
+ str_map[val.key] = val.value;
str_map["name"]= status.name
str_map["message"] = status.message
str_map["level"] = status.level
Modified: pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h 2009-08-09 01:23:59 UTC (rev 21203)
@@ -127,7 +127,7 @@
void DiagnosticStatusWrapper::adds<std::string>(const std::string &key, const std::string &s)
{
diagnostic_msgs::KeyValue ds;
- ds.label = key;
+ ds.key = key;
ds.value = s;
values.push_back(ds);
}
Modified: pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -103,9 +103,9 @@
EXPECT_STREQ("5.0", stat.values[0].value.c_str()) << "Bad value, adding a value with addsf";
EXPECT_STREQ("5", stat.values[1].value.c_str()) << "Bad value, adding a string with adds";
EXPECT_STREQ("00027", stat.values[2].value.c_str()) << "Bad value, adding a string with addsf";
- EXPECT_STREQ("toto", stat.values[0].label.c_str()) << "Bad label, adding a value with addv";
- EXPECT_STREQ("baba", stat.values[1].label.c_str()) << "Bad label, adding a string with adds";
- EXPECT_STREQ("foo", stat.values[2].label.c_str()) << "Bad label, adding a string with addsf";
+ EXPECT_STREQ("toto", stat.values[0].key.c_str()) << "Bad label, adding a value with addv";
+ EXPECT_STREQ("baba", stat.values[1].key.c_str()) << "Bad label, adding a string with adds";
+ EXPECT_STREQ("foo", stat.values[2].key.c_str()) << "Bad label, adding a string with addsf";
}
TEST(DiagnosticUpdater, testFrequencyStatus)
Modified: pkg/trunk/stacks/hardware_test/diagnostics_analysis/export_csv.py
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostics_analysis/export_csv.py 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/diagnostics_analysis/export_csv.py 2009-08-09 01:23:59 UTC (rev 21203)
@@ -63,8 +63,8 @@
if(not stats.has_key(name)):
stats[name] = {}
- stats[name]['string_fields'] = [s.label for s in status.strings]
- stats[name]['float_fields'] = [s.label for s in status.values]
+ stats[name]['string_fields'] = [s.key for s in status.strings]
+ stats[name]['float_fields'] = [s.key for s in status.values]
stats[name]['level'] = status.level
stats[name]['message'] = status.message
@@ -77,14 +77,14 @@
# Need stuff for different string fields
# Store as dictionary, then convert to CSV?
- if (not [s.label for s in status.strings] == stats[name]['string_fields']):
- #print "ERROR, mismatched field names in component %s. Label: %s" %(name, s.label)
- #print [s.label for s in status.strings]
+ if (not [s.key for s in status.strings] == stats[name]['string_fields']):
+ #print "ERROR, mismatched field names in component %s. Label: %s" %(name, s.key)
+ #print [s.key for s in status.strings]
#print str(stats[name]['string_fields'])
#return stats
continue
- if (not [s.label for s in status.values] == stats[name]['float_fields']):
- #print "ERROR, mismatched field names in component %s. Label: %s" %(name, s.label)
+ if (not [s.key for s in status.values] == stats[name]['float_fields']):
+ #print "ERROR, mismatched field names in component %s. Label: %s" %(name, s.key)
#return stats
continue
Modified: pkg/trunk/stacks/hardware_test/self_test/src/run_selftest.cpp
===================================================================
--- pkg/trunk/stacks/hardware_test/self_test/src/run_selftest.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/self_test/src/run_selftest.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -69,7 +69,7 @@
printf("%s\n", res.status[i].message.c_str());
for (size_t j = 0; j < res.status[i].get_values_size(); j++)
- printf(" [%s] %f\n", res.status[i].values[j].label.c_str(), res.status[i].values[j].value);
+ printf(" [%s] %f\n", res.status[i].values[j].key.c_str(), res.status[i].values[j].value);
printf("\n");
}
Modified: pkg/trunk/stacks/hardware_test/self_test/src/selftest_example.cpp
===================================================================
--- pkg/trunk/stacks/hardware_test/self_test/src/selftest_example.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/self_test/src/selftest_example.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -136,7 +136,7 @@
status.set_values_size(1);
status.values[0].value = some_val;
- status.values[0].label = "some value";
+ status.values[0].key = "some value";
status.level = 0;
status.message = "We successfully changed the value.";
Modified: pkg/trunk/stacks/hardware_test/self_test/src/selftest_rostest.cpp
===================================================================
--- pkg/trunk/stacks/hardware_test/self_test/src/selftest_rostest.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/self_test/src/selftest_rostest.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -82,7 +82,7 @@
EXPECT_EQ(0, res.status[i].level) << res.status[i].name << " did not PASS: " << res.status[i].message;
for (size_t j = 0; j < res.status[i].get_values_size(); j++)
- printf(" [%s] %f\n", res.status[i].values[j].label.c_str(), res.status[i].values[j].value);
+ printf(" [%s] %f\n", res.status[i].values[j].key.c_str(), res.status[i].values[j].value);
printf("\n");
}
Modified: pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc
===================================================================
--- pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc 2009-08-09 01:23:59 UTC (rev 21203)
@@ -405,11 +405,11 @@
status.message = "Succes...
[truncated message content] |
|
From: <tf...@us...> - 2009-08-09 02:25:09
|
Revision: 21206
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21206&view=rev
Author: tfoote
Date: 2009-08-09 02:24:51 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
switching from PosewithRatesStamped to Odometry #2277
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp
pkg/trunk/demos/arm_gazebo/manifest.xml
pkg/trunk/demos/arm_gazebo/scripts/grasp_preprogrammed.py
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_p3d.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_sim_iface.h
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_sim_iface.cpp
pkg/trunk/nav/teleop_base/manifest.xml
pkg/trunk/nav/teleop_base/src/ground_truth_controller.cpp
pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
pkg/trunk/stacks/simulators/stage/src/stageros.cpp
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithRatesStamped.msg
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp 2009-08-09 02:24:51 UTC (rev 21206)
@@ -34,7 +34,7 @@
#include <pr2_mechanism_controllers/Pose3D.h>
#include <ros/node.h>
-#include <geometry_msgs/PoseWithRatesStamped.h>
+#include <nav_msgs/Odometry.h>
#include <geometry_msgs/Twist.h>
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/Quaternion.h>
@@ -86,7 +86,7 @@
~test_run_base() {}
- geometry_msgs::PoseWithRatesStamped ground_truth;
+ nav_msgs::Odometry ground_truth;
nav_msgs::Odometry odom;
@@ -117,7 +117,7 @@
// receive messages from 2dnav stack
- geometry_msgs::PoseWithRatesStamped ground_truth;
+ nav_msgs::Odometry ground_truth;
test_run_base tb;
@@ -172,8 +172,8 @@
if(run_time_set && delta_time.toSec() > run_time)
break;
// ang_rates = GetAsEuler(tb.ground_truth.vel.ang_vel);
- ground_truth_angles = GetAsEuler(tb.ground_truth.pos.orientation);
- cout << "g:: " << tb.ground_truth.vel.linear.x << " " << tb.ground_truth.vel.linear.y << " " << tb.ground_truth.vel.angular.z << " " << tb.ground_truth.pos.position.x << " " << tb.ground_truth.pos.position.y << " " << ground_truth_angles.z << " " << tb.ground_truth.header.stamp.sec + tb.ground_truth.header.stamp.nsec/1.0e9 << std::endl;
+ ground_truth_angles = GetAsEuler(tb.ground_truth.pose_with_covariance.pose.orientation);
+ cout << "g:: " << tb.ground_truth.twist_with_covariance.twist.linear.x << " " << tb.ground_truth.twist_with_covariance.twist.linear.y << " " << tb.ground_truth.twist_with_covariance.twist.angular.z << " " << tb.ground_truth.pose_with_covariance.pose.position.x << " " << tb.ground_truth.pose_with_covariance.pose.position.y << " " << ground_truth_angles.z << " " << tb.ground_truth.header.stamp.sec + tb.ground_truth.header.stamp.nsec/1.0e9 << std::endl;
cout << "o:: " << tb.odom.twist_with_covariance.twist.linear.x << " " << tb.odom.twist_with_covariance.twist.linear.y << " " << tb.odom.twist_with_covariance.twist.angular.z << " " << tb.odom.pose_with_covariance.pose.position.x << " " << tb.odom.pose_with_covariance.pose.position.y << " " << tf::getYaw(tb.odom.pose_with_covariance.pose.orientation) << " " << tb.odom.header.stamp.sec + tb.odom.header.stamp.nsec/1.0e9 << std::endl;
// cout << delta_time.toSec() << " " << run_time << endl;
node->publish("cmd_vel",cmd);
Modified: pkg/trunk/demos/arm_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/arm_gazebo/manifest.xml 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/demos/arm_gazebo/manifest.xml 2009-08-09 02:24:51 UTC (rev 21206)
@@ -17,5 +17,5 @@
<depend package="robot_state_publisher"/>
<depend package="rospy"/>
- <depend package="std_msgs"/>
+ <depend package="nav_msgs"/>
</package>
Modified: pkg/trunk/demos/arm_gazebo/scripts/grasp_preprogrammed.py
===================================================================
--- pkg/trunk/demos/arm_gazebo/scripts/grasp_preprogrammed.py 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/demos/arm_gazebo/scripts/grasp_preprogrammed.py 2009-08-09 02:24:51 UTC (rev 21206)
@@ -49,7 +49,7 @@
from robot_msgs.msg import *
from std_msgs.msg import *
from pr2_mechanism_controllers.msg import *
-from geometry_msgs.msg import PoseWithRatesStamped
+from nav_msgs.msg import Odometry
CMD_POS_1 = 0.0
@@ -80,7 +80,7 @@
pub_r_wrist_flex = rospy.Publisher("r_wrist_flex_controller/set_command", Float64)
pub_r_wrist_roll = rospy.Publisher("r_wrist_roll_controller/set_command", Float64)
pub_r_gripper = rospy.Publisher("r_gripper_controller/set_command", Float64)
- rospy.Subscriber("r_gripper_palm_pose_ground_truth", PoseWithRatesStamped, p3dReceived)
+ rospy.Subscriber("r_gripper_palm_pose_ground_truth", Odometry, p3dReceived)
rospy.init_node(NAME, anonymous=True)
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp 2009-08-09 02:24:51 UTC (rev 21206)
@@ -47,7 +47,7 @@
#include "geometry_msgs/Transform.h"
#include "nav_msgs/Odometry.h"
-#include "geometry_msgs/PoseWithRatesStamped.h"
+#include "nav_msgs/Odometry.h"
#include <tf/tf.h>
#include <tf/transform_broadcaster.h>
@@ -75,7 +75,7 @@
param("~base_id", base_id_, 1) ;
advertise<nav_msgs::Odometry>("localizedpose", 1);
- advertise<geometry_msgs::PoseWithRatesStamped>("base_pose_ground_truth", 1) ;
+ advertise<nav_msgs::Odometry>("base_pose_ground_truth", 1) ;
m_tfServer = new tf::TransformBroadcaster();
@@ -125,14 +125,14 @@
publish("localizedpose", m_currentPos) ;
// Build Ground Truth Message
- geometry_msgs::PoseWithRatesStamped m_pose_with_rates ;
- m_pose_with_rates.header = snapshot_.header ;
- m_pose_with_rates.pose_with_rates.pose.position.x = body.pose.translation.x ;
- m_pose_with_rates.pose_with_rates.pose.position.y = body.pose.translation.y ;
- m_pose_with_rates.pose_with_rates.pose.position.z = body.pose.translation.z ;
- m_pose_with_rates.pose_with_rates.pose.orientation = body.pose.rotation ;
+ nav_msgs::Odometry m_ground_truth ;
+ m_ground_truth.header = snapshot_.header ;
+ m_ground_truth.pose_with_covariance.pose.position.x = body.pose.translation.x ;
+ m_ground_truth.pose_with_covariance.pose.position.y = body.pose.translation.y ;
+ m_ground_truth.pose_with_covariance.pose.position.z = body.pose.translation.z ;
+ m_ground_truth.pose_with_covariance.pose.orientation = body.pose.rotation ;
- publish("base_pose_ground_truth", m_pose_with_rates) ;
+ publish("base_pose_ground_truth", m_ground_truth) ;
publish_success_count_++ ;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_p3d.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_p3d.h 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_p3d.h 2009-08-09 02:24:51 UTC (rev 21206)
@@ -34,7 +34,7 @@
#include <ros/ros.h>
#include "boost/thread/mutex.hpp"
-#include <geometry_msgs/PoseWithRatesStamped.h>
+#include <nav_msgs/Odometry.h>
namespace gazebo
{
@@ -44,7 +44,7 @@
\brief RosP3D controller.
- This controller requires to a model as its parent. The plugin broadcasts a body's pose and rates through ROS geometry_msgs::PoseWithRatesStamped message. In the example below, the plubin broadcasts pose and rate of a body named \b body_name over ROS topic name \b body_pose_groud_truth.
+ This controller requires to a model as its parent. The plugin broadcasts a body's pose and rates through ROS nav_msgs::Odometry message. In the example below, the plubin broadcasts pose and rate of a body named \b body_name over ROS topic name \b body_pose_groud_truth.
Example Usage:
\verbatim
@@ -69,7 +69,7 @@
\brief RosP3D controller
\li Starts a ROS node if none exists.
- \li This controller simulates a 6 dof position and rate sensor, publishes geometry_msgs::PoseWithRatesStamped.msg ROS topic.
+ \li This controller simulates a 6 dof position and rate sensor, publishes nav_msgs::Odometry.msg ROS topic.
\li Example Usage:
\verbatim
<model:physical name="some_fancy_model">
@@ -122,7 +122,7 @@
private: ros::Publisher pub_;
/// \brief ros message
- private: geometry_msgs::PoseWithRatesStamped poseMsg;
+ private: nav_msgs::Odometry poseMsg;
/// \brief topic name
private: std::string topicName;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_sim_iface.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_sim_iface.h 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_sim_iface.h 2009-08-09 02:24:51 UTC (rev 21206)
@@ -19,7 +19,7 @@
*
*/
/*
- * Desc: A dynamic controller plugin that publishes ROS PoseWithRatesStamped topic for generic simiface interface. Puts body at the specified Pose (rate) etc. Only pose implemented for now.
+ * Desc: A dynamic controller plugin that publishes ROS Odometry topic for generic simiface interface. Puts body at the specified Pose (rate) etc. Only pose implemented for now.
* Author: John Hsu
* Date: 24 Sept 2008
* SVN: $Id$
@@ -31,7 +31,7 @@
#include "boost/thread/mutex.hpp"
#include <gazebo/Controller.hh>
#include <gazebo/Param.hh>
-#include <geometry_msgs/PoseWithRatesStamped.h>
+#include <nav_msgs/Odometry.h>
namespace gazebo
{
@@ -90,8 +90,8 @@
/// \brief Finalize the controller, unadvertise topics
protected: virtual void FiniChild();
- /// \brief call back when a PoseWithRatesStamped message is published
- private: void UpdateObjectPose(const geometry_msgs::PoseWithRatesStampedConstPtr& poseMsg);
+ /// \brief call back when a Odometry message is published
+private: void UpdateObjectPose(const nav_msgs::Odometry::ConstPtr& poseMsg);
/// \brief A pointer to the parent entity
private: Entity *myParent;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp 2009-08-09 02:24:51 UTC (rev 21206)
@@ -84,7 +84,7 @@
ROS_DEBUG("==== topic name for RosP3D ======== %s", this->topicName.c_str());
if (this->topicName != "")
- this->pub_ = this->rosnode_->advertise<geometry_msgs::PoseWithRatesStamped>(this->topicName,10);
+ this->pub_ = this->rosnode_->advertise<nav_msgs::Odometry>(this->topicName,10);
}
////////////////////////////////////////////////////////////////////////////////
@@ -149,31 +149,23 @@
// pose is given in inertial frame for Gazebo, transform to the designated frame name
- this->poseMsg.pose_with_rates.pose.position.x = pos.x;
- this->poseMsg.pose_with_rates.pose.position.y = pos.y;
- this->poseMsg.pose_with_rates.pose.position.z = pos.z;
+ this->poseMsg.pose_with_covariance.pose.position.x = pos.x;
+ this->poseMsg.pose_with_covariance.pose.position.y = pos.y;
+ this->poseMsg.pose_with_covariance.pose.position.z = pos.z;
- this->poseMsg.pose_with_rates.pose.orientation.x = rot.x;
- this->poseMsg.pose_with_rates.pose.orientation.y = rot.y;
- this->poseMsg.pose_with_rates.pose.orientation.z = rot.z;
- this->poseMsg.pose_with_rates.pose.orientation.w = rot.u;
+ this->poseMsg.pose_with_covariance.pose.orientation.x = rot.x;
+ this->poseMsg.pose_with_covariance.pose.orientation.y = rot.y;
+ this->poseMsg.pose_with_covariance.pose.orientation.z = rot.z;
+ this->poseMsg.pose_with_covariance.pose.orientation.w = rot.u;
- this->poseMsg.pose_with_rates.velocity.linear.x = vpos.x + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.pose_with_rates.velocity.linear.y = vpos.y + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.pose_with_rates.velocity.linear.z = vpos.z + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist_with_covariance.twist.linear.x = vpos.x + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist_with_covariance.twist.linear.y = vpos.y + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist_with_covariance.twist.linear.z = vpos.z + this->GaussianKernel(0,this->gaussianNoise) ;
// pass euler anglular rates
- this->poseMsg.pose_with_rates.velocity.angular.x = veul.x + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.pose_with_rates.velocity.angular.y = veul.y + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.pose_with_rates.velocity.angular.z = veul.z + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist_with_covariance.twist.angular.x = veul.x + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist_with_covariance.twist.angular.y = veul.y + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist_with_covariance.twist.angular.z = veul.z + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.pose_with_rates.acceleration.linear.x = this->apos.x + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.pose_with_rates.acceleration.linear.y = this->apos.y + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.pose_with_rates.acceleration.linear.z = this->apos.z + this->GaussianKernel(0,this->gaussianNoise) ;
- // pass euler anglular rates
- this->poseMsg.pose_with_rates.acceleration.angular.x = this->aeul.x + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.pose_with_rates.acceleration.angular.y = this->aeul.y + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.pose_with_rates.acceleration.angular.z = this->aeul.z + this->GaussianKernel(0,this->gaussianNoise) ;
-
// publish to ros
this->pub_.publish(this->poseMsg);
}
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_sim_iface.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_sim_iface.cpp 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_sim_iface.cpp 2009-08-09 02:24:51 UTC (rev 21206)
@@ -25,7 +25,7 @@
Date: 24 Sept 2008
SVN info: $Id$
@htmlinclude manifest.html
- @b RosSimIface plugin reads ROS PoseWithRatesStamped messages
+ @b RosSimIface plugin reads ROS Odometry messages
*/
#include <algorithm>
@@ -123,14 +123,14 @@
////////////////////////////////////////////////////////////////////////////////
// Update the controller
-void RosSimIface::UpdateObjectPose(const geometry_msgs::PoseWithRatesStampedConstPtr& poseMsg)
+void RosSimIface::UpdateObjectPose(const nav_msgs::Odometry::ConstPtr& poseMsg)
{
this->lock.lock();
Model* model = gazebo::World::Instance()->GetModelByName(this->modelName);
- Vector3 pos(poseMsg->pose_with_rates.pose.position.x,poseMsg->pose_with_rates.pose.position.y,poseMsg->pose_with_rates.pose.position.z);
- Quatern rot(poseMsg->pose_with_rates.pose.orientation.w,poseMsg->pose_with_rates.pose.orientation.x,poseMsg->pose_with_rates.pose.orientation.y,poseMsg->pose_with_rates.pose.orientation.z);
+ Vector3 pos(poseMsg->pose_with_covariance.pose.position.x,poseMsg->pose_with_covariance.pose.position.y,poseMsg->pose_with_covariance.pose.position.z);
+ Quatern rot(poseMsg->pose_with_covariance.pose.orientation.w,poseMsg->pose_with_covariance.pose.orientation.x,poseMsg->pose_with_covariance.pose.orientation.y,poseMsg->pose_with_covariance.pose.orientation.z);
Pose3d modelPose(pos,rot);
model->SetPose(modelPose);
Modified: pkg/trunk/nav/teleop_base/manifest.xml
===================================================================
--- pkg/trunk/nav/teleop_base/manifest.xml 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/nav/teleop_base/manifest.xml 2009-08-09 02:24:51 UTC (rev 21206)
@@ -6,6 +6,7 @@
<depend package="roscpp"/>
<depend package="rospy"/>
<depend package="std_msgs"/>
+ <depend package="nav_msgs"/>
<depend package="geometry_msgs"/>
<depend package="tf" />
<depend package="control_toolbox" />
Modified: pkg/trunk/nav/teleop_base/src/ground_truth_controller.cpp
===================================================================
--- pkg/trunk/nav/teleop_base/src/ground_truth_controller.cpp 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/nav/teleop_base/src/ground_truth_controller.cpp 2009-08-09 02:24:51 UTC (rev 21206)
@@ -35,7 +35,7 @@
#include <ros/node.h>
#include <ros/time.h>
-#include <geometry_msgs/PoseWithRatesStamped.h>
+#include <nav_msgs/Odometry.h>
#include <geometry_msgs/Twist.h>
#include "control_toolbox/base_position_pid.h"
#include "tf/transform_datatypes.h"
@@ -48,7 +48,7 @@
class GroundTruthController : public ros::Node
{
public:
- geometry_msgs::PoseWithRatesStamped m_ground_truth_ ; //!< Message on which we receive ground truth info
+ nav_msgs::Odometry m_ground_truth_ ; //!< Message on which we receive ground truth info
control_toolbox::BasePositionPid base_position_pid_ ; //!< Does the PID math for controlling the robot
tf::Vector3 xyt_target_ ; //!< The ground truth pose we want to acheive
bool first_time_ ;
@@ -117,7 +117,7 @@
tf::Transform ground_truth_pose ;
- tf::poseMsgToTF(m_ground_truth_.pose_with_rates.pose, ground_truth_pose) ;
+ tf::poseMsgToTF(m_ground_truth_.pose_with_covariance.pose, ground_truth_pose) ;
//! \todo Compute yaw angle in a more stable way
double yaw,pitch,roll ;
Deleted: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithRatesStamped.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithRatesStamped.msg 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseWithRatesStamped.msg 2009-08-09 02:24:51 UTC (rev 21206)
@@ -1,2 +0,0 @@
-Header header
-PoseWithRates pose_with_rates
Modified: pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
===================================================================
--- pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-09 02:24:51 UTC (rev 21206)
@@ -56,7 +56,7 @@
@section topic ROS topics
Subscribes to (name/type):
-- @b "base_pose_ground_truth" geometry_msgs/PoseWithRatesStamped : robot's odometric pose. Only the position information is used (velocity is ignored).
+- @b "base_pose_ground_truth" nav_msgs/Odometry : robot's odometric pose. Only the position information is used (velocity is ignored).
Publishes to (name / type):
- @b "amcl_pose" geometry_msgs/PoseWithCovarianceStamped : robot's estimated pose in the map, with covariance
@@ -73,7 +73,7 @@
#include <ros/node.h>
#include <ros/time.h>
-#include <geometry_msgs/PoseWithRatesStamped.h>
+#include <nav_msgs/Odometry.h>
#include <geometry_msgs/PoseArray.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
@@ -103,7 +103,7 @@
m_particleCloud.header.stamp = ros::Time::now();
m_particleCloud.header.frame_id = "/map";
m_particleCloud.set_poses_size(1);
- notifier = new tf::MessageNotifier<geometry_msgs::PoseWithRatesStamped>(m_tfListener, this,
+ notifier = new tf::MessageNotifier<nav_msgs::Odometry>(m_tfListener, this,
boost::bind(&FakeOdomNode::update, this, _1),
"",//empty topic it will be manually stuffed
odom_frame_id_, 100);
@@ -133,13 +133,13 @@
private:
tf::TransformBroadcaster *m_tfServer;
tf::TransformListener *m_tfListener;
- tf::MessageNotifier<geometry_msgs::PoseWithRatesStamped>* notifier;
+ tf::MessageNotifier<nav_msgs::Odometry>* notifier;
ros::Time m_lastUpdate;
double m_maxPublishFrequency;
bool m_base_pos_received;
- geometry_msgs::PoseWithRatesStamped m_basePosMsg;
+ nav_msgs::Odometry m_basePosMsg;
geometry_msgs::PoseArray m_particleCloud;
geometry_msgs::PoseWithCovarianceStamped m_currentPos;
@@ -149,20 +149,20 @@
void basePosReceived()
{
m_basePosMsg.header.frame_id = "base_footprint"; //hack to make the notifier do what I want (changed back later)
- boost::shared_ptr<geometry_msgs::PoseWithRatesStamped> message(new geometry_msgs::PoseWithRatesStamped);
+ boost::shared_ptr<nav_msgs::Odometry> message(new nav_msgs::Odometry);
*message = m_basePosMsg;
notifier->enqueueMessage(message);
// update();
}
public:
- void update(const tf::MessageNotifier<geometry_msgs::PoseWithRatesStamped>::MessagePtr & message){
- tf::Transform txi(tf::Quaternion(message->pose_with_rates.pose.orientation.x,
- message->pose_with_rates.pose.orientation.y,
- message->pose_with_rates.pose.orientation.z,
- message->pose_with_rates.pose.orientation.w),
- tf::Point(message->pose_with_rates.pose.position.x,
- message->pose_with_rates.pose.position.y,
- 0.0*message->pose_with_rates.pose.position.z )); // zero height for base_footprint
+ void update(const tf::MessageNotifier<nav_msgs::Odometry>::MessagePtr & message){
+ tf::Transform txi(tf::Quaternion(message->pose_with_covariance.pose.orientation.x,
+ message->pose_with_covariance.pose.orientation.y,
+ message->pose_with_covariance.pose.orientation.z,
+ message->pose_with_covariance.pose.orientation.w),
+ tf::Point(message->pose_with_covariance.pose.position.x,
+ message->pose_with_covariance.pose.position.y,
+ 0.0*message->pose_with_covariance.pose.position.z )); // zero height for base_footprint
double x = txi.getOrigin().x();
double y = txi.getOrigin().y();
Modified: pkg/trunk/stacks/simulators/stage/src/stageros.cpp
===================================================================
--- pkg/trunk/stacks/simulators/stage/src/stageros.cpp 2009-08-09 02:23:53 UTC (rev 21205)
+++ pkg/trunk/stacks/simulators/stage/src/stageros.cpp 2009-08-09 02:24:51 UTC (rev 21206)
@@ -36,7 +36,7 @@
#include "boost/thread/mutex.hpp"
#include <sensor_msgs/LaserScan.h>
#include <nav_msgs/Odometry.h>
-#include <geometry_msgs/PoseWithRatesStamped.h>
+#include <nav_msgs/Odometry.h>
#include <geometry_msgs/Twist.h>
#include <roslib/Time.h>
@@ -56,7 +56,7 @@
geometry_msgs::Twist *velMsgs;
sensor_msgs::LaserScan *laserMsgs;
nav_msgs::Odometry *odomMsgs;
- geometry_msgs::PoseWithRatesStamped *groundTruthMsgs;
+ nav_msgs::Odometry *groundTruthMsgs;
roslib::Time timeMsg;
// A mutex to lock access to fields that are used in message callbacks
@@ -175,7 +175,7 @@
this->velMsgs = new geometry_msgs::Twist[numRobots];
this->laserMsgs = new sensor_msgs::LaserScan[numRobots];
this->odomMsgs = new nav_msgs::Odometry[numRobots];
- this->groundTruthMsgs = new geometry_msgs::PoseWithRatesStamped[numRobots];
+ this->groundTruthMsgs = new nav_msgs::Odometry[numRobots];
}
@@ -208,8 +208,8 @@
}
advertise<sensor_msgs::LaserScan>(mapName(BASE_SCAN,r), 10);
advertise<nav_msgs::Odometry>(mapName(ODOM,r), 10);
- advertise<geometry_msgs::PoseWithRatesStamped>(
- mapName(BASE_POSE_GROUND_TRUTH,r), 10);
+ advertise<nav_msgs::Odometry>(
+ mapName(BASE_POSE_GROUND_TRUTH,r), 10);
subscribe(mapName(CMD_VEL,r), velMsgs[r], &StageNode::cmdvelReceived, 10);
}
advertise<roslib::Time>("/time",10);
@@ -315,13 +315,13 @@
tf::Transform gt(tf::Quaternion(gpose.a-M_PI/2.0, 0, 0),
tf::Point(gpose.y, -gpose.x, 0.0));
- this->groundTruthMsgs[r].pose_with_rates.pose.position.x = gt.getOrigin().x();
- this->groundTruthMsgs[r].pose_with_rates.pose.position.y = gt.getOrigin().y();
- this->groundTruthMsgs[r].pose_with_rates.pose.position.z = gt.getOrigin().z();
- this->groundTruthMsgs[r].pose_with_rates.pose.orientation.x = gt.getRotation().x();
- this->groundTruthMsgs[r].pose_with_rates.pose.orientation.y = gt.getRotation().y();
- this->groundTruthMsgs[r].pose_with_rates.pose.orientation.z = gt.getRotation().z();
- this->groundTruthMsgs[r].pose_with_rates.pose.orientation.w = gt.getRotation().w();
+ this->groundTruthMsgs[r].pose_with_covariance.pose.position.x = gt.getOrigin().x();
+ this->groundTruthMsgs[r].pose_with_covariance.pose.position.y = gt.getOrigin().y();
+ this->groundTruthMsgs[r].pose_with_covariance.pose.position.z = gt.getOrigin().z();
+ this->groundTruthMsgs[r].pose_with_covariance.pose.orientation.x = gt.getRotation().x();
+ this->groundTruthMsgs[r].pose_with_covariance.pose.orientation.y = gt.getRotation().y();
+ this->groundTruthMsgs[r].pose_with_covariance.pose.orientation.z = gt.getRotation().z();
+ this->groundTruthMsgs[r].pose_with_covariance.pose.orientation.w = gt.getRotation().w();
this->groundTruthMsgs[r].header.frame_id = mapName("odom", r);
this->groundTruthMsgs[r].header.stamp = sim_time;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-08-09 04:31:46
|
Revision: 21220
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21220&view=rev
Author: tfoote
Date: 2009-08-09 04:31:35 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
moving FillImage.h to fill_image.h for Jeremy
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_camera.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_prosilica.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp
pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp
pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
pkg/trunk/vision/jpeg/src/decoder.cpp
pkg/trunk/vision/recognition_lambertian/src/publish_scene.cpp
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_camera.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_camera.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_camera.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -45,7 +45,7 @@
#include <gazebo/MonoCameraSensor.hh>
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/FillImage.h"
+#include "sensor_msgs/fill_image.h"
using namespace gazebo;
GZ_REGISTER_DYNAMIC_CONTROLLER("ros_camera", RosCamera);
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_prosilica.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_prosilica.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_prosilica.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -46,7 +46,7 @@
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
-#include <sensor_msgs/FillImage.h>
+#include <sensor_msgs/fill_image.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include <opencv_latest/CvBridge.h>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -42,7 +42,7 @@
#include <gazebo/Body.hh>
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/FillImage.h"
+#include "sensor_msgs/fill_image.h"
using namespace gazebo;
Modified: pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -38,7 +38,7 @@
#include "ros/node.h"
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/FillImage.h"
+#include "sensor_msgs/fill_image.h"
#include "sensor_msgs/CameraInfo.h"
#include "sensor_msgs/StereoInfo.h"
#include "sensor_msgs/PointCloud.h"
Modified: pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -43,7 +43,7 @@
#include <ros/node.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
-#include <sensor_msgs/FillImage.h>
+#include <sensor_msgs/fill_image.h>
#include <dynamic_reconfigure/SensorLevels.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include <diagnostic_updater/update_functions.h>
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -1,7 +1,7 @@
#include "ros/node.h"
#include "sensor_msgs/Image.h"
#include "sensor_msgs/CameraInfo.h"
-#include "sensor_msgs/FillImage.h"
+#include "sensor_msgs/fill_image.h"
#include "prosilica_cam/PolledImage.h"
#include "prosilica_cam/CameraInfo.h"
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -37,7 +37,7 @@
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
-#include <sensor_msgs/FillImage.h>
+#include <sensor_msgs/fill_image.h>
#include <opencv_latest/CvBridge.h>
#include <camera_calibration/pinhole.h>
#include <image_publisher/image_publisher.h>
Deleted: pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h 2009-08-09 04:31:35 UTC (rev 21220)
@@ -1,69 +0,0 @@
-/*********************************************************************
-* Software License Agreement (BSD License)
-*
-* Copyright (c) 2008, Willow Garage, Inc.
-* All rights reserved.
-*
-* Redistribution and use in source and binary forms, with or without
-* modification, are permitted provided that the following conditions
-* are met:
-*
-* * Redistributions of source code must retain the above copyright
-* notice, this list of conditions and the following disclaimer.
-* * Redistributions in binary form must reproduce the above
-* copyright notice, this list of conditions and the following
-* disclaimer in the documentation and/or other materials provided
-* with the distribution.
-* * Neither the name of the Willow Garage nor the names of its
-* contributors may be used to endorse or promote products derived
-* from this software without specific prior written permission.
-*
-* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-* POSSIBILITY OF SUCH DAMAGE.
-*********************************************************************/
-
-#ifndef FILLIMAGE_HH
-#define FILLIMAGE_HH
-
-#include "sensor_msgs/Image.h"
-
-namespace sensor_msgs
-{
-
- bool fillImage(Image& image,
- uint32_t type_arg,
- uint32_t rows_arg,
- uint32_t cols_arg,
- uint32_t step_arg,
- void* data_arg)
- {
- image.type = type_arg;
- image.height = rows_arg;
- image.width = cols_arg;
- image.step = step_arg;
- size_t st0 = (step_arg * rows_arg);
- image.data.resize(st0);
- memcpy((char*)(&image.data[0]), (char*)(data_arg), st0);
-
- image.is_bigendian = 0;
- return true;
- }
-
- void clearImage(Image& image)
- {
- image.data.resize(0);
- }
-}
-
-
-#endif
Copied: pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h (from rev 21165, pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h)
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h (rev 0)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h 2009-08-09 04:31:35 UTC (rev 21220)
@@ -0,0 +1,69 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+#ifndef FILLIMAGE_HH
+#define FILLIMAGE_HH
+
+#include "sensor_msgs/Image.h"
+
+namespace sensor_msgs
+{
+
+ bool fillImage(Image& image,
+ uint32_t type_arg,
+ uint32_t rows_arg,
+ uint32_t cols_arg,
+ uint32_t step_arg,
+ void* data_arg)
+ {
+ image.type = type_arg;
+ image.height = rows_arg;
+ image.width = cols_arg;
+ image.step = step_arg;
+ size_t st0 = (step_arg * rows_arg);
+ image.data.resize(st0);
+ memcpy((char*)(&image.data[0]), (char*)(data_arg), st0);
+
+ image.is_bigendian = 0;
+ return true;
+ }
+
+ void clearImage(Image& image)
+ {
+ image.data.resize(0);
+ }
+}
+
+
+#endif
Modified: pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
===================================================================
--- pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h 2009-08-09 04:31:35 UTC (rev 21220)
@@ -36,7 +36,7 @@
#define CAM_BRIDGE_HH
#include "sensor_msgs/RawStereo.h"
-#include "sensor_msgs/FillImage.h"
+#include "sensor_msgs/fill_image.h"
#include "image.h"
namespace cam_bridge
Modified: pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp
===================================================================
--- pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -38,7 +38,7 @@
#include "cam_bridge.h"
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/FillImage.h"
+#include "sensor_msgs/fill_image.h"
#include "sensor_msgs/CameraInfo.h"
#include <boost/thread.hpp>
Modified: pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
===================================================================
--- pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -41,7 +41,7 @@
#include "cam_bridge.h"
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/FillImage.h"
+#include "sensor_msgs/fill_image.h"
#include "sensor_msgs/CameraInfo.h"
#include "sensor_msgs/StereoInfo.h"
#include "sensor_msgs/PointCloud.h"
Modified: pkg/trunk/vision/jpeg/src/decoder.cpp
===================================================================
--- pkg/trunk/vision/jpeg/src/decoder.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/vision/jpeg/src/decoder.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -33,7 +33,7 @@
*********************************************************************/
#include <sensor_msgs/Image.h>
-#include <sensor_msgs/FillImage.h>
+#include <sensor_msgs/fill_image.h>
#include <sensor_msgs/CompressedImage.h>
#include <ros/ros.h>
Modified: pkg/trunk/vision/recognition_lambertian/src/publish_scene.cpp
===================================================================
--- pkg/trunk/vision/recognition_lambertian/src/publish_scene.cpp 2009-08-09 04:20:46 UTC (rev 21219)
+++ pkg/trunk/vision/recognition_lambertian/src/publish_scene.cpp 2009-08-09 04:31:35 UTC (rev 21220)
@@ -52,7 +52,7 @@
#include <sensor_msgs/DisparityInfo.h>
#include <opencv_latest/CvBridge.h>
-#include <sensor_msgs/FillImage.h>
+#include <sensor_msgs/fill_image.h>
#include <std_msgs/String.h>
#include <point_cloud_mapping/cloud_io.h>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2009-08-09 05:13:22
|
Revision: 21224
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21224&view=rev
Author: jleibs
Date: 2009-08-09 05:13:11 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
Adding in a placeholder robot_msgs package to make the migration tests continue to work.
Modified Paths:
--------------
pkg/trunk/deprecated/deprecated_msgs/migration_rules/migration_rules.py
pkg/trunk/stacks/common_msgs/test_common_msgs/test/test_common_msgs_migration.py
Added Paths:
-----------
pkg/trunk/deprecated/robot_msgs/
pkg/trunk/deprecated/robot_msgs/CMakeLists.txt
pkg/trunk/deprecated/robot_msgs/Makefile
pkg/trunk/deprecated/robot_msgs/mainpage.dox
pkg/trunk/deprecated/robot_msgs/manifest.xml
Modified: pkg/trunk/deprecated/deprecated_msgs/migration_rules/migration_rules.py
===================================================================
--- pkg/trunk/deprecated/deprecated_msgs/migration_rules/migration_rules.py 2009-08-09 04:55:26 UTC (rev 21223)
+++ pkg/trunk/deprecated/deprecated_msgs/migration_rules/migration_rules.py 2009-08-09 05:13:11 UTC (rev 21224)
@@ -86,7 +86,7 @@
("Header","Header"),
("Pose", "geometry_msgs/Pose")]
- valid = False
+ valid = True
def update(self, old_msg, new_msg):
self.migrate(old_msg.header, new_msg.header)
Added: pkg/trunk/deprecated/robot_msgs/CMakeLists.txt
===================================================================
--- pkg/trunk/deprecated/robot_msgs/CMakeLists.txt (rev 0)
+++ pkg/trunk/deprecated/robot_msgs/CMakeLists.txt 2009-08-09 05:13:11 UTC (rev 21224)
@@ -0,0 +1,30 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+# Set the build type. Options are:
+# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage
+# Debug : w/ debug symbols, w/o optimization
+# Release : w/o debug symbols, w/ optimization
+# RelWithDebInfo : w/ debug symbols, w/ optimization
+# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries
+#set(ROS_BUILD_TYPE RelWithDebInfo)
+
+rospack(robot_msgs)
+
+#set the default path for built executables to the "bin" directory
+set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set the default path for built libraries to the "lib" directory
+set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+
+#uncomment if you have defined messages
+#genmsg()
+#uncomment if you have defined services
+#gensrv()
+
+#common commands for building c++ executables and libraries
+#rospack_add_library(${PROJECT_NAME} src/example.cpp)
+#target_link_libraries(${PROJECT_NAME} another_library)
+#rospack_add_boost_directories()
+#rospack_link_boost(${PROJECT_NAME} thread)
+#rospack_add_executable(example examples/example.cpp)
+#target_link_libraries(example ${PROJECT_NAME})
Added: pkg/trunk/deprecated/robot_msgs/Makefile
===================================================================
--- pkg/trunk/deprecated/robot_msgs/Makefile (rev 0)
+++ pkg/trunk/deprecated/robot_msgs/Makefile 2009-08-09 05:13:11 UTC (rev 21224)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
Added: pkg/trunk/deprecated/robot_msgs/mainpage.dox
===================================================================
--- pkg/trunk/deprecated/robot_msgs/mainpage.dox (rev 0)
+++ pkg/trunk/deprecated/robot_msgs/mainpage.dox 2009-08-09 05:13:11 UTC (rev 21224)
@@ -0,0 +1,119 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b robot_msgs is ...
+
+<!--
+In addition to providing an overview of your package,
+this is the section where the specification and design/architecture
+should be detailed. While the original specification may be done on the
+wiki, it should be transferred here once your package starts to take shape.
+You can then link to this documentation page from the Wiki.
+-->
+
+
+\section codeapi Code API
+
+<!--
+Provide links to specific auto-generated API documentation within your
+package that is of particular interest to a reader. Doxygen will
+document pretty much every part of your code, so do your best here to
+point the reader to the actual API.
+
+If your codebase is fairly large or has different sets of APIs, you
+should use the doxygen 'group' tag to keep these APIs together. For
+example, the roscpp documentation has 'libros' group.
+-->
+
+\section rosapi ROS API
+
+<!--
+Names are very important in ROS because they can be remapped on the
+command-line, so it is VERY IMPORTANT THAT YOU LIST NAMES AS THEY
+APPEAR IN THE CODE. You should list names of every topic, service and
+parameter used in your code. There is a template below that you can
+use to document each node separately.
+
+List of nodes:
+- \b node_name1
+- \b node_name2
+-->
+
+<!-- START: copy from here to 'END' for each node
+
+<hr>
+
+\subsection node_name node_name
+
+node_name does (provide a basic description of your node)
+
+\subsubsection Usage
+\verbatim
+$ node_type1 [standard ROS args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ node_type1
+\endverbatim
+
+
+\subsubsection topics ROS topics
+
+Subscribes to:
+- \b "in": [std_msgs/FooType] description of in
+
+Publishes to:
+- \b "out": [std_msgs/FooType] description of out
+
+
+\subsubsection parameters ROS parameters
+
+Reads the following parameters from the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+- \b "~my_param" : \b [string] description of my_param
+
+Sets the following parameters on the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+
+
+\subsubsection services ROS services
+- \b "foo_service": [std_srvs/FooType] description of foo_service
+
+
+END: copy for each node -->
+
+
+<!-- START: Uncomment if you have any command-line tools
+
+\section commandline Command-line tools
+
+This section is a catch-all for any additional tools that your package
+provides or uses that may be of use to the reader. For example:
+
+- tools/scripts (e.g. rospack, roscd)
+- roslaunch .launch files
+- xmlparam files
+
+\subsection script_name script_name
+
+Description of what this script/file does.
+
+\subsubsection Usage
+\verbatim
+$ ./script_name [args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ ./script_name foo bar
+\endverbatim
+
+END: Command-Line Tools Section -->
+
+*/
\ No newline at end of file
Added: pkg/trunk/deprecated/robot_msgs/manifest.xml
===================================================================
--- pkg/trunk/deprecated/robot_msgs/manifest.xml (rev 0)
+++ pkg/trunk/deprecated/robot_msgs/manifest.xml 2009-08-09 05:13:11 UTC (rev 21224)
@@ -0,0 +1,13 @@
+<package>
+ <description brief="robot_msgs">
+
+ This is a placeholder package that needs to exist until ken fixes a bug in python generate dynamic.
+
+ </description>
+ <author>Jeremy Leibs</author>
+ <license>BSD</license>
+ <review status="deprecated" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/robot_msgs</url>
+</package>
+
+
Modified: pkg/trunk/stacks/common_msgs/test_common_msgs/test/test_common_msgs_migration.py
===================================================================
--- pkg/trunk/stacks/common_msgs/test_common_msgs/test/test_common_msgs_migration.py 2009-08-09 04:55:26 UTC (rev 21223)
+++ pkg/trunk/stacks/common_msgs/test_common_msgs/test/test_common_msgs_migration.py 2009-08-09 05:13:11 UTC (rev 21224)
@@ -50,6 +50,36 @@
import rospy
+import math
+
+def quaternion_from_euler(x, y, z):
+ x /= 2.0
+ y /= 2.0
+ z /= 2.0
+ ci = math.cos(x)
+ si = math.sin(x)
+ cj = math.cos(y)
+ sj = math.sin(y)
+ ck = math.cos(z)
+ sk = math.sin(z)
+ cc = ci*ck
+ cs = ci*sk
+ sc = si*ck
+ ss = si*sk
+
+ quaternion = [0.0,0.0,0.0,0.0]
+
+ quaternion[0] = cj*sc - sj*cs
+ quaternion[1] = cj*ss + sj*cc
+ quaternion[2] = cj*cs - sj*sc
+ quaternion[3] = cj*cc + sj*ss
+
+ return quaternion
+
+
+
+identity6x6 = [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0]
+
class TestCommonMsgsMigration(unittest.TestCase):
@@ -86,7 +116,6 @@
# (*) RobotBase2DOdom.saved
-
########### RobotBase2DOdom ###############
def get_old_robot_base_2d_odom(self):
@@ -95,7 +124,7 @@
robot_base_2d_odom = robot_base_2d_odom_classes['deprecated_msgs/RobotBase2DOdom']
pose_2d_float32 = robot_base_2d_odom_classes['deprecated_msgs/Pose2DFloat32']
- return robot_base_2d_odom(None, pose_2d_float32(0,0,0), pose_2d_float32(0,0,0), 0, 0)
+ return robot_base_2d_odom(None, pose_2d_float32(3.33, 2.22, 1.11), pose_2d_float32(.1,.2,.3), 0, 1)
def get_new_robot_base_2d_odom(self):
from nav_msgs.msg import Odometry
@@ -107,8 +136,8 @@
from geometry_msgs.msg import Twist
from geometry_msgs.msg import Vector3
- p = PoseWithCovariance(Pose(Point(1.23, 4.56, 7.89), Quaternion(0,0,0,1)), [0.0]*36)
- t = TwistWithCovariance(Twist(Vector3(1.23, 4.56, 7.89), Vector3(9.87, 6.54, 3.21)), [0.0]*36)
+ p = PoseWithCovariance(Pose(Point(3.33, 2.22, 0), apply(Quaternion,quaternion_from_euler(0,0,1.11))), identity6x6)
+ t = TwistWithCovariance(Twist(Vector3(.1, .2, 0), Vector3(0, 0, .3)), identity6x6)
return Odometry(None, p, t)
@@ -609,7 +638,7 @@
point = pose_with_covariance_classes['robot_msgs/Point']
quaternion = pose_with_covariance_classes['robot_msgs/Quaternion']
- return pose_with_covariance(None, pose(point(1.23, 4.56, 7.89), quaternion(0,0,0,1)), [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0])
+ return pose_with_covariance(None, pose(point(1.23, 4.56, 7.89), quaternion(0,0,0,1)), identity6x6)
def get_new_pose_with_covariance(self):
from geometry_msgs.msg import PoseWithCovarianceStamped
@@ -617,7 +646,7 @@
from geometry_msgs.msg import Point
from geometry_msgs.msg import Quaternion
- return PoseWithCovarianceStamped(None, Pose(Point(1.23, 4.56, 7.89), Quaternion(0,0,0,1)), [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0] + 6*[0] + [1.0])
+ return PoseWithCovarianceStamped(None, Pose(Point(1.23, 4.56, 7.89), Quaternion(0,0,0,1)), identity6x6)
def test_pose_with_covariance(self):
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <sf...@us...> - 2009-08-09 23:12:52
|
Revision: 21274
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21274&view=rev
Author: sfkwc
Date: 2009-08-09 23:12:43 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
svn ignores
Property Changed:
----------------
pkg/trunk/deprecated/deprecated_msgs/msg/
pkg/trunk/deprecated/deprecated_srvs/srv/
pkg/trunk/highlevel/plugs/plugs_core/msg/
pkg/trunk/motion_planning/motion_planning_msgs/srv/
pkg/trunk/openrave_planning/openraveros/msg/
pkg/trunk/openrave_planning/openraveros/srv/
pkg/trunk/sandbox/actionlib/msg/
pkg/trunk/sandbox/camera_calibration/msg/
pkg/trunk/sandbox/experimental_controllers/msg/
pkg/trunk/sandbox/manipulation_srvs/srv/
pkg/trunk/sandbox/mapping_msgs/msg/
pkg/trunk/sandbox/tf_node/msg/
pkg/trunk/sandbox/tf_node/srv/
pkg/trunk/stacks/camera_drivers/prosilica_cam/srv/
pkg/trunk/stacks/common_msgs/geometry_msgs/
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/
pkg/trunk/stacks/common_msgs/nav_msgs/srv/
pkg/trunk/stacks/common_msgs/sensor_msgs/src/
pkg/trunk/stacks/driver_common/driver_base/msg/
pkg/trunk/stacks/driver_common/driver_base/srv/
pkg/trunk/stacks/driver_common/dynamic_reconfigure/msg/
pkg/trunk/stacks/navigation/base_local_planner/msg/
pkg/trunk/stacks/navigation/costmap_2d/msg/
pkg/trunk/stacks/navigation/move_base/msg/
pkg/trunk/stacks/navigation/nav_robot_actions/msg/
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/srv/
pkg/trunk/stacks/trex/trex_pr2/srv/
pkg/trunk/stacks/trex/trex_ros/msg/
pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/msg/
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/srv/
pkg/trunk/stacks/world_models/topological_map/msg/
pkg/trunk/stacks/world_models/topological_map/srv/
Property changes on: pkg/trunk/deprecated/deprecated_msgs/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/deprecated/deprecated_srvs/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/highlevel/plugs/plugs_core/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/motion_planning/motion_planning_msgs/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/openrave_planning/openraveros/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/openrave_planning/openraveros/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/sandbox/actionlib/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/sandbox/camera_calibration/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/sandbox/experimental_controllers/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/sandbox/manipulation_srvs/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/sandbox/mapping_msgs/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/sandbox/tf_node/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/sandbox/tf_node/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/camera_drivers/prosilica_cam/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/common_msgs/geometry_msgs
___________________________________________________________________
Added: svn:ignore
+ .build_version
src
bin
Property changes on: pkg/trunk/stacks/common_msgs/geometry_msgs/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
oct
lisp
Property changes on: pkg/trunk/stacks/common_msgs/nav_msgs/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
oct
lisp
Property changes on: pkg/trunk/stacks/common_msgs/sensor_msgs/src
___________________________________________________________________
Added: svn:ignore
+ sensor_msgs
Property changes on: pkg/trunk/stacks/driver_common/driver_base/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/driver_common/driver_base/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/driver_common/dynamic_reconfigure/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/navigation/base_local_planner/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/navigation/costmap_2d/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/navigation/move_base/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/navigation/nav_robot_actions/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/trex/trex_pr2/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/trex/trex_ros/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/visual_feature_detectors/outlet_detection/srv
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/world_models/topological_map/msg
___________________________________________________________________
Added: svn:ignore
+ java
cpp
lisp
oct
Property changes on: pkg/trunk/stacks/world_models/topological_map/srv
___________________________________________________________________
Modified: svn:ignore
- oct
lisp
+ java
cpp
lisp
oct
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <sf...@us...> - 2009-08-09 23:29:12
|
Revision: 21277
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21277&view=rev
Author: sfkwc
Date: 2009-08-09 23:29:03 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
svn ignores
Property Changed:
----------------
pkg/trunk/3rdparty/ijg_libjpeg/
pkg/trunk/audio/backup_safetysound/
pkg/trunk/demos/test_2dnav_gazebo/
pkg/trunk/deprecated/deprecated_msgs/
pkg/trunk/deprecated/deprecated_srvs/
pkg/trunk/deprecated/misc_utils/
pkg/trunk/deprecated/resource_locator/
pkg/trunk/deprecated/robot_msgs/
pkg/trunk/drivers/simulator/test_gazebo_plugin/
pkg/trunk/drivers/simulator/test_pr2_collision_gazebo/
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/
pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/
pkg/trunk/highlevel/doors/doors_core/
pkg/trunk/highlevel/plugs/plugs_core/
pkg/trunk/highlevel/safety/safety_core/
pkg/trunk/openrave_planning/openraveros/
pkg/trunk/openrave_planning/orrosplanning/
pkg/trunk/pr2/pr2_computer_monitor/
pkg/trunk/pr2/teleop/teleop_arm_keyboard/
pkg/trunk/pr2/teleop/teleop_pr2/
pkg/trunk/robot_descriptions/ikea_objects/
pkg/trunk/sandbox/actionlib/
pkg/trunk/sandbox/camera_calibration/
pkg/trunk/sandbox/experimental_controllers/
pkg/trunk/sandbox/gazebo_tools/
pkg/trunk/sandbox/ikea_ogre/
pkg/trunk/sandbox/image_publisher/
pkg/trunk/sandbox/m3_simulator/
pkg/trunk/sandbox/manipulation_srvs/
pkg/trunk/sandbox/mapping_msgs/
pkg/trunk/sandbox/pluginlib/
pkg/trunk/sandbox/robot_model/
pkg/trunk/sandbox/tf_conversions/
pkg/trunk/sandbox/tf_node/
pkg/trunk/sandbox/topic_synchronizer2/
pkg/trunk/stacks/camera_drivers/dcam/
pkg/trunk/stacks/camera_drivers/forearm_cam/
pkg/trunk/stacks/camera_drivers/prosilica_cam/
pkg/trunk/stacks/common/laser_scan/
pkg/trunk/stacks/geometry/tf/
pkg/trunk/stacks/hardware_test/diagnostic_test/
pkg/trunk/stacks/hardware_test/diagnostic_updater/
pkg/trunk/stacks/hardware_test/self_test/
pkg/trunk/stacks/joystick_drivers/joy/
pkg/trunk/stacks/motion_planning/sbpl/
pkg/trunk/stacks/navigation/amcl/
pkg/trunk/stacks/navigation/base_local_planner/
pkg/trunk/stacks/navigation/costmap_2d/
pkg/trunk/stacks/navigation/map_server/
pkg/trunk/stacks/navigation/move_base/
pkg/trunk/stacks/navigation/nav_core/
pkg/trunk/stacks/navigation/nav_robot_actions/
pkg/trunk/stacks/navigation/navfn/
pkg/trunk/stacks/navigation/voxel_grid/
pkg/trunk/stacks/opencv/image_view/
pkg/trunk/stacks/opencv/opencv_tests/
pkg/trunk/stacks/pr2/pr2_ogre/
pkg/trunk/stacks/stereo/stereo_image_proc/
pkg/trunk/stacks/stereo/stereo_utils/
pkg/trunk/stacks/visual_feature_detectors/calonder_descriptor/
pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/
pkg/trunk/stacks/visual_feature_detectors/fast_detector/
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/
pkg/trunk/stacks/visual_feature_detectors/star_detector/
pkg/trunk/stacks/world_models/topological_map/
pkg/trunk/util/geometric_shapes/
pkg/trunk/util/or_robot_self_filter/
pkg/trunk/util/robot_self_filter/
Property changes on: pkg/trunk/3rdparty/ijg_libjpeg
___________________________________________________________________
Modified: svn:ignore
- jpeg-6b
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/audio/backup_safetysound
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/demos/test_2dnav_gazebo
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/deprecated/deprecated_msgs
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/deprecated/deprecated_srvs
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/deprecated/misc_utils
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/deprecated/resource_locator
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/deprecated/robot_msgs
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/drivers/simulator/test_gazebo_plugin
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/drivers/simulator/test_pr2_collision_gazebo
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/highlevel/doors/doors_core
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/highlevel/plugs/plugs_core
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/highlevel/safety/safety_core
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/openrave_planning/openraveros
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/openrave_planning/orrosplanning
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/pr2/pr2_computer_monitor
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/pr2/teleop/teleop_arm_keyboard
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/pr2/teleop/teleop_pr2
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/robot_descriptions/ikea_objects
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/actionlib
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/camera_calibration
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/experimental_controllers
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/gazebo_tools
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/ikea_ogre
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/image_publisher
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/m3_simulator
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/manipulation_srvs
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/mapping_msgs
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/pluginlib
___________________________________________________________________
Modified: svn:ignore
- .rosgcov_files
bin
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/robot_model
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/tf_conversions
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/tf_node
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/sandbox/topic_synchronizer2
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/camera_drivers/dcam
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/camera_drivers/forearm_cam
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/camera_drivers/prosilica_cam
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/common/laser_scan
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/geometry/tf
___________________________________________________________________
Modified: svn:ignore
- simpletest
tf_unittest
tf_unittest_future
cache_unittest
testListener
testBroadcaster
test_notifier
bullet_unittest
lib
build
btTest
transform_sender
frames.gv
frames.ps
frames.pdf
.build-version
.rosgcov_files
tf_monitor
bin
change_notifier
tf_echo
+ .build_version
simpletest
tf_unittest
tf_unittest_future
cache_unittest
testListener
testBroadcaster
test_notifier
bullet_unittest
lib
build
btTest
transform_sender
frames.gv
frames.ps
frames.pdf
.build-version
.rosgcov_files
tf_monitor
bin
change_notifier
tf_echo
swig
Property changes on: pkg/trunk/stacks/hardware_test/diagnostic_test
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/hardware_test/diagnostic_updater
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/hardware_test/self_test
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/joystick_drivers/joy
___________________________________________________________________
Modified: svn:ignore
- joy
src
+ .build_version
.rosgcov_files
bin
joy
src
Property changes on: pkg/trunk/stacks/motion_planning/sbpl
___________________________________________________________________
Modified: svn:ignore
- bin
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/navigation/amcl
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/navigation/base_local_planner
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/navigation/costmap_2d
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/navigation/map_server
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/navigation/move_base
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/navigation/nav_core
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/navigation/nav_robot_actions
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/navigation/navfn
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/navigation/voxel_grid
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/opencv/image_view
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/opencv/opencv_tests
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/pr2/pr2_ogre
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/stereo/stereo_image_proc
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/stereo/stereo_utils
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/visual_feature_detectors/calonder_descriptor
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/visual_feature_detectors/fast_detector
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/visual_feature_detectors/outlet_detection
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/visual_feature_detectors/star_detector
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/stacks/world_models/topological_map
___________________________________________________________________
Modified: svn:ignore
- bg_driver
.build-version
ros_bottleneck_graph
bg_driver
debug.txt
gmon.out
bin
launch.xml
ros_topological_planner
ros_topological_map
tm_driver
rosconfig.cmake
+ bg_driver
.build_version
.rosgcov_files
ros_bottleneck_graph
bg_driver
debug.txt
gmon.out
bin
launch.xml
ros_topological_planner
ros_topological_map
tm_driver
rosconfig.cmake
Property changes on: pkg/trunk/util/geometric_shapes
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/util/or_robot_self_filter
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
Property changes on: pkg/trunk/util/robot_self_filter
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <sf...@us...> - 2009-08-10 00:02:43
|
Revision: 21278
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21278&view=rev
Author: sfkwc
Date: 2009-08-10 00:02:33 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
#2250 getting rid of _with_covariance in Odometry fields
Modified Paths:
--------------
pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp
pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py
pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/old/scripts/approachtable.py
pkg/trunk/demos/test_2dnav_gazebo/set_goal.py
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_diffdrive.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_sim_iface.cpp
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomw_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomx_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxy_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxyw_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomy_gt.py
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_vw_gt.py
pkg/trunk/nav/teleop_base/src/ground_truth_controller.cpp
pkg/trunk/sandbox/teleop_anti_collision/src/anti_collision_base_controller.cpp
pkg/trunk/stacks/common_msgs/nav_msgs/msg/Odometry.msg
pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/stacks/navigation/base_local_planner/src/trajectory_planner_ros.cpp
pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
pkg/trunk/stacks/simulators/stage/src/stageros.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/robot_base2d_pose_display.cpp
pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp
pkg/trunk/util/logsetta/odom/odom_extract.cpp
Modified: pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp 2009-08-10 00:02:33 UTC (rev 21278)
@@ -72,12 +72,12 @@
{
_odom_mutex.lock();
if (!_odom_active){
- _odom_begin = tf::getYaw(_odom.pose_with_covariance.pose.orientation);
- _odom_end = tf::getYaw(_odom.pose_with_covariance.pose.orientation);
+ _odom_begin = tf::getYaw(_odom.pose.pose.orientation);
+ _odom_end = tf::getYaw(_odom.pose.pose.orientation);
_odom_active = true;
}
else{
- double tmp = tf::getYaw(_odom.pose_with_covariance.pose.orientation);
+ double tmp = tf::getYaw(_odom.pose.pose.orientation);
AngleOverflowCorrect(tmp, _odom_end);
_odom_end = tmp;
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp 2009-08-10 00:02:33 UTC (rev 21278)
@@ -155,17 +155,17 @@
{
msg.header.frame_id = odom_frame_;
msg.header.stamp.fromSec(current_time_);
- msg.pose_with_covariance.pose.position.x = odom_.x;
- msg.pose_with_covariance.pose.position.y = odom_.y;
- msg.pose_with_covariance.pose.position.z = 0.0;
+ msg.pose.pose.position.x = odom_.x;
+ msg.pose.pose.position.y = odom_.y;
+ msg.pose.pose.position.z = 0.0;
tf::Quaternion quat_trans = tf::Quaternion(odom_.z, 0.0, 0.0);
- msg.pose_with_covariance.pose.orientation.x = quat_trans.x();
- msg.pose_with_covariance.pose.orientation.y = quat_trans.y();
- msg.pose_with_covariance.pose.orientation.z = quat_trans.z();
- msg.pose_with_covariance.pose.orientation.w = quat_trans.w();
+ msg.pose.pose.orientation.x = quat_trans.x();
+ msg.pose.pose.orientation.y = quat_trans.y();
+ msg.pose.pose.orientation.z = quat_trans.z();
+ msg.pose.pose.orientation.w = quat_trans.w();
- msg.twist_with_covariance.twist = odom_vel_;
+ msg.twist.twist = odom_vel_;
#warning A full covariance should be published instead of the residual, this code will not work properly with the ekf until this is changed
//@todo TODO: change from residual to covariance
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_odom.cpp 2009-08-10 00:02:33 UTC (rev 21278)
@@ -162,9 +162,9 @@
if(run_time_set && delta_time.toSec() > run_time)
break;
- odom_log_file << tb.odom.pose_with_covariance.pose.position.x << " " << tb.odom.pose_with_covariance.pose.position.y << " " << tf::getYaw(tb.odom.pose_with_covariance.pose.orientation) << " " << tb.odom.twist_with_covariance.twist.linear.x << " " << tb.odom.twist_with_covariance.twist.linear.y << " " << tb.odom.twist_with_covariance.twist.angulat.z << " " << tb.odom.header.stamp.sec + tb.odom.header.stamp.nsec/1.0e9 << std::endl;
+ odom_log_file << tb.odom.pose.pose.position.x << " " << tb.odom.pose.pose.position.y << " " << tf::getYaw(tb.odom.pose.pose.orientation) << " " << tb.odom.twist.twist.linear.x << " " << tb.odom.twist.twist.linear.y << " " << tb.odom.twist.twist.angulat.z << " " << tb.odom.header.stamp.sec + tb.odom.header.stamp.nsec/1.0e9 << std::endl;
- cout << endl << "odometry:: " << endl << "velocity:" << endl << " x:" << tb.odom.twist_with_covariance.twist.linear.x << endl << " y:" << tb.odom.twist_with_covariance.twist.linear.y << endl << " omega:" << tb.odom.twist_with_covariance.twist.angular.z << std::endl;
+ cout << endl << "odometry:: " << endl << "velocity:" << endl << " x:" << tb.odom.twist.twist.linear.x << endl << " y:" << tb.odom.twist.twist.linear.y << endl << " omega:" << tb.odom.twist.twist.angular.z << std::endl;
node->publish("cmd_vel",cmd);
sleep_time.sleep();
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_run_base_controller.cpp 2009-08-10 00:02:33 UTC (rev 21278)
@@ -172,9 +172,9 @@
if(run_time_set && delta_time.toSec() > run_time)
break;
// ang_rates = GetAsEuler(tb.ground_truth.vel.ang_vel);
- ground_truth_angles = GetAsEuler(tb.ground_truth.pose_with_covariance.pose.orientation);
- cout << "g:: " << tb.ground_truth.twist_with_covariance.twist.linear.x << " " << tb.ground_truth.twist_with_covariance.twist.linear.y << " " << tb.ground_truth.twist_with_covariance.twist.angular.z << " " << tb.ground_truth.pose_with_covariance.pose.position.x << " " << tb.ground_truth.pose_with_covariance.pose.position.y << " " << ground_truth_angles.z << " " << tb.ground_truth.header.stamp.sec + tb.ground_truth.header.stamp.nsec/1.0e9 << std::endl;
- cout << "o:: " << tb.odom.twist_with_covariance.twist.linear.x << " " << tb.odom.twist_with_covariance.twist.linear.y << " " << tb.odom.twist_with_covariance.twist.angular.z << " " << tb.odom.pose_with_covariance.pose.position.x << " " << tb.odom.pose_with_covariance.pose.position.y << " " << tf::getYaw(tb.odom.pose_with_covariance.pose.orientation) << " " << tb.odom.header.stamp.sec + tb.odom.header.stamp.nsec/1.0e9 << std::endl;
+ ground_truth_angles = GetAsEuler(tb.ground_truth.pose.pose.orientation);
+ cout << "g:: " << tb.ground_truth.twist.twist.linear.x << " " << tb.ground_truth.twist.twist.linear.y << " " << tb.ground_truth.twist.twist.angular.z << " " << tb.ground_truth.pose.pose.position.x << " " << tb.ground_truth.pose.pose.position.y << " " << ground_truth_angles.z << " " << tb.ground_truth.header.stamp.sec + tb.ground_truth.header.stamp.nsec/1.0e9 << std::endl;
+ cout << "o:: " << tb.odom.twist.twist.linear.x << " " << tb.odom.twist.twist.linear.y << " " << tb.odom.twist.twist.angular.z << " " << tb.odom.pose.pose.position.x << " " << tb.odom.pose.pose.position.y << " " << tf::getYaw(tb.odom.pose.pose.orientation) << " " << tb.odom.header.stamp.sec + tb.odom.header.stamp.nsec/1.0e9 << std::endl;
// cout << delta_time.toSec() << " " << run_time << endl;
node->publish("cmd_vel",cmd);
sleep_time.sleep();
Modified: pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py
===================================================================
--- pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/demos/door_demos_gazebo/scripts/initialize_nav.py 2009-08-10 00:02:33 UTC (rev 21278)
@@ -154,14 +154,14 @@
# initialize odom
if self.odom_initialized == False or self.p3d_initialized == False:
self.odom_initialized = True
- self.odom_xi = odom.pose_with_covariance.pose.position.x
- self.odom_yi = odom.pose_with_covariance.pose.position.y
- self.odom_qi = quaternionMsgToList(odom.pose_with_covariance.pose.orientation)
+ self.odom_xi = odom.pose.pose.position.x
+ self.odom_yi = odom.pose.pose.position.y
+ self.odom_qi = quaternionMsgToList(odom.pose.pose.orientation)
else:
# update odom
- self.odom_x = odom.pose_with_covariance.pose.position.x
- self.odom_y = odom.pose_with_covariance.pose.position.y
- self.odom_q = quaternionMsgToList(odom.pose_with_covariance.pose.orientation)
+ self.odom_x = odom.pose.pose.position.x
+ self.odom_y = odom.pose.pose.position.y
+ self.odom_q = quaternionMsgToList(odom.pose.pose.orientation)
def p3dInput(self, p3d):
#self.printBaseP3D(p3d)
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-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/old/scripts/approachtable.py 2009-08-10 00:02:33 UTC (rev 21278)
@@ -68,9 +68,9 @@
def tfCallback(self,msg):
if (msg.transforms[0].header.frame_id == self.global_frame and
self.odom_pose != None):
- self.robot_position = Point((self.odom_pose.pose_with_covariance.pose.position.x -
+ self.robot_position = Point((self.odom_pose.pose.pose.position.x -
msg.transforms[0].transform.translation.x),
- (self.odom_pose.pose_with_covariance.pose.position.y -
+ (self.odom_pose.pose.pose.position.y -
msg.transforms[0].transform.translation.y),
0.0)
Modified: pkg/trunk/demos/test_2dnav_gazebo/set_goal.py
===================================================================
--- pkg/trunk/demos/test_2dnav_gazebo/set_goal.py 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/demos/test_2dnav_gazebo/set_goal.py 2009-08-10 00:02:33 UTC (rev 21278)
@@ -154,14 +154,14 @@
# initialize odom
if self.odom_initialized == False or self.p3d_initialized == False:
self.odom_initialized = True
- self.odom_xi = odom.pose_with_covariance.pose.position.x
- self.odom_yi = odom.pose_with_covariance.pose.position.y
- self.odom_qi = quaternionMsgToList(odom.pose_with_covariance.orientation)
+ self.odom_xi = odom.pose.pose.position.x
+ self.odom_yi = odom.pose.pose.position.y
+ self.odom_qi = quaternionMsgToList(odom.pose.orientation)
else:
# update odom
self.odom_x = odom.pos.x
self.odom_y = odom.pos.y
- self.odom_q = quaternionMsgToList(odom.pose_with_covariance.orientation)
+ self.odom_q = quaternionMsgToList(odom.pose.orientation)
def p3dInput(self, p3d):
#self.printBaseP3D(p3d)
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp 2009-08-10 00:02:33 UTC (rev 21278)
@@ -114,12 +114,12 @@
m_currentPos.header = snapshot_.header;
m_currentPos.header.frame_id = "map";
- m_currentPos.pose_with_covariance.pose.position.x = body.pose.translation.x;
- m_currentPos.pose_with_covariance.pose.position.y = body.pose.translation.y;
+ m_currentPos.pose.pose.position.x = body.pose.translation.x;
+ m_currentPos.pose.pose.position.y = body.pose.translation.y;
double yaw,pitch,roll;
mytf.getBasis().getEulerZYX(yaw,pitch,roll);
- m_currentPos.pose_with_covariance.pose.orientation= tf::createQuaternionMsgFromYaw(yaw);
+ m_currentPos.pose.pose.orientation= tf::createQuaternionMsgFromYaw(yaw);
if (publish_localized_pose_)
publish("localizedpose", m_currentPos) ;
@@ -127,10 +127,10 @@
// Build Ground Truth Message
nav_msgs::Odometry m_ground_truth ;
m_ground_truth.header = snapshot_.header ;
- m_ground_truth.pose_with_covariance.pose.position.x = body.pose.translation.x ;
- m_ground_truth.pose_with_covariance.pose.position.y = body.pose.translation.y ;
- m_ground_truth.pose_with_covariance.pose.position.z = body.pose.translation.z ;
- m_ground_truth.pose_with_covariance.pose.orientation = body.pose.rotation ;
+ m_ground_truth.pose.pose.position.x = body.pose.translation.x ;
+ m_ground_truth.pose.pose.position.y = body.pose.translation.y ;
+ m_ground_truth.pose.pose.position.z = body.pose.translation.z ;
+ m_ground_truth.pose.pose.orientation = body.pose.rotation ;
publish("base_pose_ground_truth", m_ground_truth) ;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_diffdrive.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_diffdrive.cpp 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_diffdrive.cpp 2009-08-10 00:02:33 UTC (rev 21278)
@@ -125,12 +125,12 @@
tfb.sendTransform(tmp_tf_stamped);
- odom.pose_with_covariance.pose.position.x = this->posIface->data->pose.pos.x;
- odom.pose_with_covariance.pose.position.y = this->posIface->data->pose.pos.y;
- odom.pose_with_covariance.pose.orientation = tf::createQuaternionMsgFromYaw(this->posIface->data->pose.yaw);
- odom.twist_with_covariance.twist.linear.x = this->posIface->data->velocity.pos.x;
- odom.twist_with_covariance.twist.linear.y = this->posIface->data->velocity.pos.y;
- odom.twist_with_covariance.twist.angular.z = this->posIface->data->velocity.yaw;
+ odom.pose.pose.position.x = this->posIface->data->pose.pos.x;
+ odom.pose.pose.position.y = this->posIface->data->pose.pos.y;
+ odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(this->posIface->data->pose.yaw);
+ odom.twist.twist.linear.x = this->posIface->data->velocity.pos.x;
+ odom.twist.twist.linear.y = this->posIface->data->velocity.pos.y;
+ odom.twist.twist.angular.z = this->posIface->data->velocity.yaw;
odom.header.frame_id = "odom";
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_p3d.cpp 2009-08-10 00:02:33 UTC (rev 21278)
@@ -149,22 +149,22 @@
// pose is given in inertial frame for Gazebo, transform to the designated frame name
- this->poseMsg.pose_with_covariance.pose.position.x = pos.x;
- this->poseMsg.pose_with_covariance.pose.position.y = pos.y;
- this->poseMsg.pose_with_covariance.pose.position.z = pos.z;
+ this->poseMsg.pose.pose.position.x = pos.x;
+ this->poseMsg.pose.pose.position.y = pos.y;
+ this->poseMsg.pose.pose.position.z = pos.z;
- this->poseMsg.pose_with_covariance.pose.orientation.x = rot.x;
- this->poseMsg.pose_with_covariance.pose.orientation.y = rot.y;
- this->poseMsg.pose_with_covariance.pose.orientation.z = rot.z;
- this->poseMsg.pose_with_covariance.pose.orientation.w = rot.u;
+ this->poseMsg.pose.pose.orientation.x = rot.x;
+ this->poseMsg.pose.pose.orientation.y = rot.y;
+ this->poseMsg.pose.pose.orientation.z = rot.z;
+ this->poseMsg.pose.pose.orientation.w = rot.u;
- this->poseMsg.twist_with_covariance.twist.linear.x = vpos.x + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.twist_with_covariance.twist.linear.y = vpos.y + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.twist_with_covariance.twist.linear.z = vpos.z + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist.twist.linear.x = vpos.x + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist.twist.linear.y = vpos.y + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist.twist.linear.z = vpos.z + this->GaussianKernel(0,this->gaussianNoise) ;
// pass euler anglular rates
- this->poseMsg.twist_with_covariance.twist.angular.x = veul.x + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.twist_with_covariance.twist.angular.y = veul.y + this->GaussianKernel(0,this->gaussianNoise) ;
- this->poseMsg.twist_with_covariance.twist.angular.z = veul.z + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist.twist.angular.x = veul.x + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist.twist.angular.y = veul.y + this->GaussianKernel(0,this->gaussianNoise) ;
+ this->poseMsg.twist.twist.angular.z = veul.z + this->GaussianKernel(0,this->gaussianNoise) ;
// publish to ros
this->pub_.publish(this->poseMsg);
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_sim_iface.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_sim_iface.cpp 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_sim_iface.cpp 2009-08-10 00:02:33 UTC (rev 21278)
@@ -129,8 +129,8 @@
this->lock.lock();
Model* model = gazebo::World::Instance()->GetModelByName(this->modelName);
- Vector3 pos(poseMsg->pose_with_covariance.pose.position.x,poseMsg->pose_with_covariance.pose.position.y,poseMsg->pose_with_covariance.pose.position.z);
- Quatern rot(poseMsg->pose_with_covariance.pose.orientation.w,poseMsg->pose_with_covariance.pose.orientation.x,poseMsg->pose_with_covariance.pose.orientation.y,poseMsg->pose_with_covariance.pose.orientation.z);
+ Vector3 pos(poseMsg->pose.pose.position.x,poseMsg->pose.pose.position.y,poseMsg->pose.pose.position.z);
+ Quatern rot(poseMsg->pose.pose.orientation.w,poseMsg->pose.pose.orientation.x,poseMsg->pose.pose.orientation.y,poseMsg->pose.pose.orientation.z);
Pose3d modelPose(pos,rot);
model->SetPose(modelPose);
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomw_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomw_gt.py 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomw_gt.py 2009-08-10 00:02:33 UTC (rev 21278)
@@ -154,16 +154,16 @@
return self.normalize_angle(angle_diff)
def printBaseOdom(self, odom):
- orientation = odom.pose_with_covariance.orientation
+ orientation = odom.pose.orientation
q = Q(orientation.x, orientation.y, orientation.z, orientation.w)
q.normalize()
print "odom received"
- print "odom pos " + "x: " + str(odom.pose_with_covariance.pose.position.x)
- print "odom pos " + "y: " + str(odom.pose_with_covariance.pose.position.y)
+ print "odom pos " + "x: " + str(odom.pose.pose.position.x)
+ print "odom pos " + "y: " + str(odom.pose.pose.position.y)
print "odom pos " + "t: " + str(q.getEuler().z)
- print "odom vel " + "x: " + str(odom.twist_with_covariance.twist.linear.x)
- print "odom vel " + "y: " + str(odom.twist_with_covariance.twist.linear.y)
- print "odom vel " + "t: " + str(odom.twist_with_covariance.twist.angular.z)
+ print "odom vel " + "x: " + str(odom.twist.twist.linear.x)
+ print "odom vel " + "y: " + str(odom.twist.twist.linear.y)
+ print "odom vel " + "t: " + str(odom.twist.twist.angular.z)
def printBaseP3D(self, p3d):
print "base pose ground truth received"
@@ -185,16 +185,16 @@
def odomInput(self, odom):
#self.printBaseOdom(odom)
- orientation = odom.pose_with_covariance.orientation
+ orientation = odom.pose.orientation
q = Q(orientation.x, orientation.y, orientation.z, orientation.w)
q.normalize()
if self.odom_initialized == False:
self.odom_initialized = True
- self.odom_xi = odom.pose_with_covariance.pose.position.x
- self.odom_yi = odom.pose_with_covariance.pose.position.y
+ self.odom_xi = odom.pose.pose.position.x
+ self.odom_yi = odom.pose.pose.position.y
self.odom_ei = q.getEuler()
- self.odom_x = odom.pose_with_covariance.pose.position.x - self.odom_xi
- self.odom_y = odom.pose_with_covariance.pose.position.y - self.odom_yi
+ self.odom_x = odom.pose.pose.position.x - self.odom_xi
+ self.odom_y = odom.pose.pose.position.y - self.odom_yi
self.odom_e.shortest_euler_distance(self.odom_ei, q.getEuler())
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomx_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomx_gt.py 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomx_gt.py 2009-08-10 00:02:33 UTC (rev 21278)
@@ -120,16 +120,16 @@
def printBaseOdom(self, odom):
- orientation = odom.pose_with_covariance.orientation
+ orientation = odom.pose.orientation
q = Q(orientation.x, orientation.y, orientation.z, orientation.w)
q.normalize()
print "odom received"
- print "odom pos " + "x: " + str(odom.pose_with_covariance.pose.position.x)
- print "odom pos " + "y: " + str(odom.pose_with_covariance.pose.position.y)
+ print "odom pos " + "x: " + str(odom.pose.pose.position.x)
+ print "odom pos " + "y: " + str(odom.pose.pose.position.y)
print "odom pos " + "t: " + str(q.getEuler().z)
- print "odom vel " + "x: " + str(odom.twist_with_covariance.twist.linear.x)
- print "odom vel " + "y: " + str(odom.twist_with_covariance.twist.linear.y)
- print "odom vel " + "t: " + str(odom.twist_with_covariance.twist.angular.z)
+ print "odom vel " + "x: " + str(odom.twist.twist.linear.x)
+ print "odom vel " + "y: " + str(odom.twist.twist.linear.y)
+ print "odom vel " + "t: " + str(odom.twist.twist.angular.z)
def printBaseP3D(self, p3d):
print "base pose ground truth received"
@@ -149,16 +149,16 @@
def odomInput(self, odom):
#self.printBaseOdom(odom)
- orientation = odom.pose_with_covariance.orientation
+ orientation = odom.pose.orientation
q = Q(orientation.x, orientation.y, orientation.z, orientation.w)
q.normalize()
if self.odom_initialized == False:
self.odom_initialized = True
- self.odom_xi = odom.pose_with_covariance.pose.position.x
- self.odom_yi = odom.pose_with_covariance.pose.position.y
+ self.odom_xi = odom.pose.pose.position.x
+ self.odom_yi = odom.pose.pose.position.y
self.odom_ti = q.getEuler().z
- self.odom_x = odom.pose_with_covariance.pose.position.x - self.odom_xi
- self.odom_y = odom.pose_with_covariance.pose.position.y - self.odom_yi
+ self.odom_x = odom.pose.pose.position.x - self.odom_xi
+ self.odom_y = odom.pose.pose.position.y - self.odom_yi
self.odom_t = q.getEuler().z - self.odom_ti
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxy_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxy_gt.py 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxy_gt.py 2009-08-10 00:02:33 UTC (rev 21278)
@@ -119,16 +119,16 @@
def printBaseOdom(self, odom):
- orientation = odom.pose_with_covariance.orientation
+ orientation = odom.pose.orientation
q = Q(orientation.x, orientation.y, orientation.z, orientation.w)
q.normalize()
print "odom received"
- print "odom pos " + "x: " + str(odom.pose_with_covariance.pose.position.x)
- print "odom pos " + "y: " + str(odom.pose_with_covariance.pose.position.y)
+ print "odom pos " + "x: " + str(odom.pose.pose.position.x)
+ print "odom pos " + "y: " + str(odom.pose.pose.position.y)
print "odom pos " + "t: " + str(q.getEuler().z)
- print "odom vel " + "x: " + str(odom.twist_with_covariance.twist.linear.x)
- print "odom vel " + "y: " + str(odom.twist_with_covariance.twist.linear.y)
- print "odom vel " + "t: " + str(odom.twist_with_covariance.twist.angular.z)
+ print "odom vel " + "x: " + str(odom.twist.twist.linear.x)
+ print "odom vel " + "y: " + str(odom.twist.twist.linear.y)
+ print "odom vel " + "t: " + str(odom.twist.twist.angular.z)
def printBaseP3D(self, p3d):
print "base pose ground truth received"
@@ -148,16 +148,16 @@
def odomInput(self, odom):
#self.printBaseOdom(odom)
- orientation = odom.pose_with_covariance.orientation
+ orientation = odom.pose.orientation
q = Q(orientation.x, orientation.y, orientation.z, orientation.w)
q.normalize()
if self.odom_initialized == False:
self.odom_initialized = True
- self.odom_xi = odom.pose_with_covariance.pose.position.x
- self.odom_yi = odom.pose_with_covariance.pose.position.y
+ self.odom_xi = odom.pose.pose.position.x
+ self.odom_yi = odom.pose.pose.position.y
self.odom_ti = q.getEuler().z
- self.odom_x = odom.pose_with_covariance.pose.position.x - self.odom_xi
- self.odom_y = odom.pose_with_covariance.pose.position.y - self.odom_yi
+ self.odom_x = odom.pose.pose.position.x - self.odom_xi
+ self.odom_y = odom.pose.pose.position.y - self.odom_yi
self.odom_t = q.getEuler().z - self.odom_ti
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxyw_gt.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxyw_gt.py 2009-08-09 23:29:03 UTC (rev 21277)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_base_odomxyw_gt.py 2009-08-10 00:02:33 UTC (rev 21278)
@@ -154,16 +154,16 @@
return self.normalize_angle(angle_diff)
def printBaseOdom(self, odom):
- orientation = odom.pose_with_covariance.orientation
+ orientation = odom.pose.orientation
q = Q(orientation.x, orientation.y, orientation.z, orientation.w)
q.normalize()
print "odom received"
- print "odom pos " + "x: " + str(odom.pose_with_covariance.pose.position.x)
- print "odom pos " + "y: " + str(odom.pose_with_covariance.pose.position.y)
+ print "odom pos " + "x: " + str(odom.pose.pose.position.x)
+ print "odom pos " + "y: " + str(odom.pose.pose.position.y)
print "odom pos " + "t: " + str(q.getEuler().z)
- print "odom vel " + "x: " + str(odom.twist_with_covariance.twist.linear.x)
- print "odom vel " + "y: " + str(odom.twist_with_covariance.twist.linear.y)
- print "odom vel " + "t: " + str(odom.twist_with_covariance.twist.angular.z)
+ print "odom vel " + "x: " + str(odom.twist.twist.linear.x)
+ print "odom vel " + "y: " + str(odom.twist.twist.linear.y)
+ print "odom vel " + "t: " + str(odom.twist.twist.angular.z)
def printBaseP3D(self, p3d):
print "base pose ground truth received"
@@ -187,11 +187,11 @@
#self.printBaseOdom(odom)
if self.odom_initialized == False:
self.odom_initialized = True
- self.odom_xi = odom.pose_with_covariance.pose.position.x
- self.odom_...
[truncated message content] |
|
From: <sf...@us...> - 2009-08-10 04:27:04
|
Revision: 21303
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21303&view=rev
Author: sfkwc
Date: 2009-08-10 04:26:58 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
Deprecating robot_actions
Added Paths:
-----------
pkg/trunk/deprecated/robot_actions/
Removed Paths:
-------------
pkg/trunk/stacks/common/robot_actions/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <sf...@us...> - 2009-08-10 04:28:17
|
Revision: 21305
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21305&view=rev
Author: sfkwc
Date: 2009-08-10 04:28:05 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
#2305 deprecating python_actions
Added Paths:
-----------
pkg/trunk/deprecated/python_actions/
Removed Paths:
-------------
pkg/trunk/stacks/common/python_actions/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <sf...@us...> - 2009-08-10 04:33:05
|
Revision: 21306
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21306&view=rev
Author: sfkwc
Date: 2009-08-10 04:32:51 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
#2302 moving actionlib to common
Added Paths:
-----------
pkg/trunk/stacks/common/actionlib/
Removed Paths:
-------------
pkg/trunk/sandbox/actionlib/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|