|
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 (rev 21149)
@@ -117,11 +117,11 @@
geometry_msgs::PointStamped in;
in.header.frame_id = "/base_footprint";
in.header.stamp = cloud->header.stamp;
- in.data.x = in.data.y = in.data.z = 0;
+ in.point.x = in.point.y = in.point.z = 0;
geometry_msgs::PointStamped out;
tf_client_.transformPoint("/odom_combined", in, out);
- cout<<"Zero is at: "<<out.data.x<<","<<out.data.y<<endl;
- setGoal(x, y, atan2(y-out.data.y,x-out.data.x), cloud->header.stamp);
+ cout<<"Zero is at: "<<out.point.x<<","<<out.point.y<<endl;
+ setGoal(x, y, atan2(y-out.point.y,x-out.point.x), cloud->header.stamp);
}
bool receivedVoxels;
Modified: pkg/trunk/sandbox/point_cloud_tutorials/src/planar_fit.cpp
===================================================================
--- pkg/trunk/sandbox/point_cloud_tutorials/src/planar_fit.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/sandbox/point_cloud_tutorials/src/planar_fit.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -186,21 +186,21 @@
geometry_msgs::PointStamped viewpoint_laser;
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
{
tf.transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud);
- ROS_INFO ("Cloud view data in frame %s is: %g, %g, %g.", cloud_frame.c_str (),
- viewpoint_cloud.data.x, viewpoint_cloud.data.y, viewpoint_cloud.data.z);
+ ROS_INFO ("Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (),
+ viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z);
}
catch (...)
{
// Default to 0.05, 0, 0.942768 (base_link, ~base_footprint)
- viewpoint_cloud.data.x = 0.05; viewpoint_cloud.data.y = 0.0; viewpoint_cloud.data.z = 0.942768;
- ROS_WARN ("Could not transform a data from frame %s to frame %s! Defaulting to <%f, %f, %f>",
+ viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768;
+ ROS_WARN ("Could not transform a point from frame %s to frame %s! Defaulting to <%f, %f, %f>",
viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str (),
- viewpoint_cloud.data.x, viewpoint_cloud.data.y, viewpoint_cloud.data.z);
+ viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z);
}
}
Modified: pkg/trunk/sandbox/rf_detector/src/ObjectInPerspective.cpp
===================================================================
--- pkg/trunk/sandbox/rf_detector/src/ObjectInPerspective.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/sandbox/rf_detector/src/ObjectInPerspective.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -35,6 +35,7 @@
#include "ObjectInPerspective.h"
using namespace std;
+using namespace robot_msgs;
template<typename T>
static double dist2D(const T& a, const T& b)
@@ -172,7 +173,7 @@
void addTableFrame(geometry_msgs::PointStamped origin, const vector<double>& plane, tf::TransformListener& tf_, tf::TransformBroadcaster& broadcaster_)
{
- 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;
@@ -229,9 +230,9 @@
ps.header.stamp = cloud.header.stamp;
// compute location
- ps.data.x = 0;
- ps.data.z = 0.7;
- ps.data.y = -(plane_coeff[2]/plane_coeff[1])*ps.data.z;
+ ps.point.x = 0;
+ ps.point.z = 0.7;
+ ps.point.y = -(plane_coeff[2]/plane_coeff[1])*ps.point.z;
geometry_msgs::Point pp = project3DPointIntoImage(lcinfo, ps, tf_);
// get imaeg coordinate of the pts
@@ -513,9 +514,9 @@
geometry_msgs::PointStamped table_point;
table_point.header.frame_id = projected_objects.header.frame_id;
table_point.header.stamp = projected_objects.header.stamp;
- table_point.data.x = projected_objects.points[0].x;
- table_point.data.y = projected_objects.points[0].y;
- table_point.data.z = projected_objects.points[0].z;
+ table_point.point.x = projected_objects.points[0].x;
+ table_point.point.y = projected_objects.points[0].y;
+ table_point.point.z = projected_objects.points[0].z;
addTableFrame(table_point,plane, tf_, broadcaster_);
@@ -543,18 +544,18 @@
ps.header.stamp = objects_table_frame.header.stamp;
// compute location
- ps.data.x = clusters[i].x;
- ps.data.y = clusters[i].y;
- ps.data.z = clusters[i].z/2;
+ ps.point.x = clusters[i].x;
+ ps.point.y = clusters[i].y;
+ ps.point.z = clusters[i].z/2;
geometry_msgs::Point pp = project3DPointIntoImage(lcinfo, ps, tf_);
locations[i].x = int(pp.x);
locations[i].y = int(pp.y);
// compute scale
- ps.data.z = 0;
+ ps.point.z = 0;
geometry_msgs::Point pp1 = project3DPointIntoImage(lcinfo, ps, tf_); // compute obj bottom in image coordinate
- ps.data.z = clusters[i].z;
+ ps.point.z = clusters[i].z;
geometry_msgs::Point pp2 = project3DPointIntoImage(lcinfo, ps, tf_);
float dist = sqrt(dist2D(pp1,pp2));
@@ -581,17 +582,17 @@
tf_.transformPoint(cam_info.header.frame_id, point, image_point);
geometry_msgs::Point pp; // projected point
- pp.x = cam_info.P[0]*image_point.data.x+
- cam_info.P[1]*image_point.data.y+
- cam_info.P[2]*image_point.data.z+
+ pp.x = cam_info.P[0]*image_point.point.x+
+ cam_info.P[1]*image_point.point.y+
+ cam_info.P[2]*image_point.point.z+
cam_info.P[3];
- pp.y = cam_info.P[4]*image_point.data.x+
- cam_info.P[5]*image_point.data.y+
- cam_info.P[6]*image_point.data.z+
+ pp.y = cam_info.P[4]*image_point.point.x+
+ cam_info.P[5]*image_point.point.y+
+ cam_info.P[6]*image_point.point.z+
cam_info.P[7];
- pp.z = cam_info.P[8]*image_point.data.x+
- cam_info.P[9]*image_point.data.y+
- cam_info.P[10]*image_point.data.z+
+ pp.z = cam_info.P[8]*image_point.point.x+
+ cam_info.P[9]*image_point.point.y+
+ cam_info.P[10]*image_point.point.z+
cam_info.P[11];
pp.x /= pp.z;
Modified: pkg/trunk/sandbox/webteleop/src/server.py
===================================================================
--- pkg/trunk/sandbox/webteleop/src/server.py 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/sandbox/webteleop/src/server.py 2009-08-08 05:44:57 UTC (rev 21149)
@@ -269,14 +269,14 @@
point = geometry_msgs.msg.PointStamped()
point.header.stamp = self.last_message.header.stamp
point.header.frame_id = frameId
- point.data.x = self.last_message.points[i].x
- point.data.y = self.last_message.points[i].y
- point.data.z = self.last_message.points[i].z
+ point.point.x = self.last_message.points[i].x
+ point.point.y = self.last_message.points[i].y
+ point.point.z = self.last_message.points[i].z
point = tfclient.transformPoint("/map", point)
- msg += '{"x": "%f",' % point.data.x
- msg += '"y": "%f",' % point.data.y
- msg += '"z": "%f"},' % point.data.z
+ msg += '{"x": "%f",' % point.point.x
+ msg += '"y": "%f",' % point.point.y
+ msg += '"z": "%f"},' % point.point.z
msg += ']}'
Modified: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PointStamped.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PointStamped.msg 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PointStamped.msg 2009-08-08 05:44:57 UTC (rev 21149)
@@ -1,2 +1,2 @@
Header header
-Point data
+Point point
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:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-08 05:44:57 UTC (rev 21149)
@@ -160,10 +160,10 @@
/** \brief convert PointStamped msg to Stamped<Point> */
static inline void pointStampedMsgToTF(const geometry_msgs::PointStamped & msg, Stamped<Point>& bt)
-{pointMsgToTF(msg.data, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
+{pointMsgToTF(msg.point, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Point> to PointStamped msg*/
static inline void pointStampedTFToMsg(const Stamped<Point>& bt, geometry_msgs::PointStamped & msg)
-{pointTFToMsg(bt, msg.data); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+{pointTFToMsg(bt, msg.point); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Transform msg to Transform */
Modified: pkg/trunk/stacks/geometry/tf/test/python_debug_test.py
===================================================================
--- pkg/trunk/stacks/geometry/tf/test/python_debug_test.py 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/geometry/tf/test/python_debug_test.py 2009-08-08 05:44:57 UTC (rev 21149)
@@ -119,8 +119,8 @@
print "getting stamp"
output = pointstamped.stamp
print output
- print pointstamped.data
- print transform_stamped.transform * pointstamped.data
+ print pointstamped.point
+ print transform_stamped.transform * pointstamped.point
pose_only = bullet.Transform(transform_stamped.transform)
print "destructing pose_only", pose_only.this
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:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 05:44:57 UTC (rev 21149)
@@ -29,16 +29,16 @@
## Setup the point tests
self.tfpoint_stamped = tf.PointStamped()
- self.tfpoint_stamped.data.x = 0
- self.tfpoint_stamped.data.y = 0
- self.tfpoint_stamped.data.z = 0
+ self.tfpoint_stamped.point.x = 0
+ self.tfpoint_stamped.point.y = 0
+ self.tfpoint_stamped.point.z = 0
self.tfpoint_stamped.frame_id = "frame1"
self.tfpoint_stamped.stamp = roslib.rostime.Time(10,0)
self.msgpoint_stamped = robot_msgs.msg.PointStamped()
- self.msgpoint_stamped.data.x = 0
- self.msgpoint_stamped.data.y = 0
- self.msgpoint_stamped.data.z = 0
+ self.msgpoint_stamped.point.x = 0
+ self.msgpoint_stamped.point.y = 0
+ self.msgpoint_stamped.point.z = 0
self.msgpoint_stamped.header.frame_id = "frame1"
self.msgpoint_stamped.header.stamp = roslib.rostime.Time(10,0)
@@ -113,9 +113,9 @@
self.assertEquals(tf.point_stamped_msg_to_bt(self.msgpoint_stamped), tf.point_stamped_msg_to_bt(self.msgpoint_stamped), "point bt test correctness after conversion")
def test_to_msg_point(self):
- self.assertEquals(tf.point_bt_to_msg(self.tfpoint_stamped.data), self.msgpoint_stamped.data, "point tf to msg incorrect")
+ self.assertEquals(tf.point_bt_to_msg(self.tfpoint_stamped.point), self.msgpoint_stamped.point, "point tf to msg incorrect")
def test_to_tf_point(self):
- self.assertEquals(tf.point_msg_to_bt(self.msgpoint_stamped.data), self.tfpoint_stamped.data, "point stamped msg to tf incorrect")
+ self.assertEquals(tf.point_msg_to_bt(self.msgpoint_stamped.point), self.tfpoint_stamped.point, "point stamped msg to tf incorrect")
def test_stamped_to_msg_point(self):
self.assertEquals(tf.point_stamped_bt_to_msg(self.tfpoint_stamped), self.msgpoint_stamped, "point stamped tf to msg incorrect")
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/doors_detector.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/doors_detector.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/doors_detector.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -167,7 +167,7 @@
vector<int> indices_in_bounds (pointcloud.points.size ());
for (unsigned int i = 0; i < pointcloud.points.size (); i++)
{
- double dist = cloud_geometry::distances::pointToPointDistanceSqr (viewpoint_cloud_.data, pointcloud.points[i]);
+ double dist = cloud_geometry::distances::pointToPointDistanceSqr (viewpoint_cloud_.point, pointcloud.points[i]);
if (dist < maximum_search_radius_ && pointcloud.points[i].z > minimum_z_ && pointcloud.points[i].z < maximum_z_)
indices_in_bounds[nr_p++] = i;
}
@@ -191,7 +191,7 @@
leaves.resize (0); // dealloc memory used for the downsampling process
#if DEBUG_FAILURES
- sendMarker (viewpoint_cloud_.data.x, viewpoint_cloud_.data.y, viewpoint_cloud_.data.z, parameter_frame_, &node_, global_marker_id_, 0, 0, 0);
+ sendMarker (viewpoint_cloud_.point.x, viewpoint_cloud_.point.y, viewpoint_cloud_.point.z, parameter_frame_, &node_, global_marker_id_, 0, 0, 0);
#endif
// Create Kd-Tree and estimate the point normals in the original point cloud
estimatePointNormals (pointcloud, indices_in_bounds, cloud_down, k_search_, viewpoint_cloud_);
@@ -273,7 +273,7 @@
// ---[ If any of the points on the hull are near/outside the imposed "maximum search radius to viewpoint" limit, discard the candidate
for (int i = 0; i < (int)pmap_.polygons[cc].points.size (); i++)
{
- double dist = cloud_geometry::distances::pointToPointDistanceSqr (viewpoint_cloud_.data, pmap_.polygons[cc].points[i]);
+ double dist = cloud_geometry::distances::pointToPointDistanceSqr (viewpoint_cloud_.point, pmap_.polygons[cc].points[i]);
if (dist < maximum_search_radius_limit_)
continue;
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/geometric_helper.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/geometric_helper.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/geometric_helper.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -257,19 +257,19 @@
geometry_msgs::PointStamped viewpoint_laser;
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
{
tf->transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud);
- ROS_INFO ("Cloud view data in frame %s is: %g, %g, %g.", cloud_frame.c_str (),
- viewpoint_cloud.data.x, viewpoint_cloud.data.y, viewpoint_cloud.data.z);
+ ROS_INFO ("Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (),
+ viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z);
}
catch (tf::ConnectivityException)
{
- ROS_WARN ("Could not transform a data from frame %s to frame %s!", viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str ());
+ ROS_WARN ("Could not transform a point from frame %s to frame %s!", viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str ());
// Default to 0.05, 0, 0.942768
- viewpoint_cloud.data.x = 0.05; viewpoint_cloud.data.y = 0.0; viewpoint_cloud.data.z = 0.942768;
+ viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768;
}
}
@@ -425,9 +425,9 @@
cloud_geometry::nearest::computeCentroid (points, indices, centroid);
// Create a line direction from the viewpoint to the centroid
- centroid.x -= viewpoint->data.x;
- centroid.y -= viewpoint->data.y;
- centroid.z -= viewpoint->data.z;
+ centroid.x -= viewpoint->point.x;
+ centroid.y -= viewpoint->point.y;
+ centroid.z -= viewpoint->point.z;
// Compute the normal of this cluster
Eigen::Vector4d plane_parameters;
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -431,9 +431,9 @@
// Install the basis for a viewpoint -> point line
vector<double> viewpoint_pt_line (6);
- viewpoint_pt_line[0] = viewpoint_cloud.data.x;
- viewpoint_pt_line[1] = viewpoint_cloud.data.y;
- viewpoint_pt_line[2] = viewpoint_cloud.data.z;
+ viewpoint_pt_line[0] = viewpoint_cloud.point.x;
+ viewpoint_pt_line[1] = viewpoint_cloud.point.y;
+ viewpoint_pt_line[2] = viewpoint_cloud.point.z;
// Remove outliers around the door margin
geometry_msgs::Point32 tmp_p; // Used as a temporary point
@@ -455,9 +455,9 @@
continue;
// Check whether the line viewpoint->point intersects the polygon
- viewpoint_pt_line[3] = pointcloud.points.at (indices.at (i)).x - viewpoint_cloud.data.x;
- viewpoint_pt_line[4] = pointcloud.points.at (indices.at (i)).y - viewpoint_cloud.data.y;
- viewpoint_pt_line[5] = pointcloud.points.at (indices.at (i)).z - viewpoint_cloud.data.z;
+ viewpoint_pt_line[3] = pointcloud.points.at (indices.at (i)).x - viewpoint_cloud.point.x;
+ viewpoint_pt_line[4] = pointcloud.points.at (indices.at (i)).y - viewpoint_cloud.point.y;
+ viewpoint_pt_line[5] = pointcloud.points.at (indices.at (i)).z - viewpoint_cloud.point.z;
// Normalize direction
double n_norm = sqrt (viewpoint_pt_line[3] * viewpoint_pt_line[3] +
viewpoint_pt_line[4] * viewpoint_pt_line[4] +
@@ -501,9 +501,9 @@
#if 0
// Install the basis for a viewpoint -> point line
vector<double> viewpoint_pt_line (6);
- viewpoint_pt_line[0] = viewpoint_cloud.data.x;
- viewpoint_pt_line[1] = viewpoint_cloud.data.y;
- viewpoint_pt_line[2] = viewpoint_cloud.data.z;
+ viewpoint_pt_line[0] = viewpoint_cloud.point.x;
+ viewpoint_pt_line[1] = viewpoint_cloud.point.y;
+ viewpoint_pt_line[2] = viewpoint_cloud.point.z;
#endif
geometry_msgs::Point32 pt;
tmp_indices.resize (outliers.size ());
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -489,9 +489,9 @@
marker.id = 0;
marker.type = visualization_msgs::Marker::SPHERE;
marker.action = visualization_msgs::Marker::ADD;
- marker.pose.position.x = p.data.x;
- marker.pose.position.y = p.data.y;
- marker.pose.position.z = p.data.z;
+ marker.pose.position.x = p.point.x;
+ marker.pose.position.y = p.point.y;
+ marker.pose.position.z = p.point.z;
marker.pose.orientation.w = 1.0;
marker.scale.x = marker.scale.y = marker.scale.z = 0.1;
marker.color.g = 1.0;
@@ -634,16 +634,16 @@
geometry_msgs::PointStamped pin, pout;
pin.header.frame_id = cloud_->header.frame_id;
pin.header.stamp = cloud_->header.stamp;
- pin.data.x = xstats.mean;
- pin.data.y = ystats.mean;
- pin.data.z = zstats.mean;
+ pin.point.x = xstats.mean;
+ pin.point.y = ystats.mean;
+ pin.point.z = zstats.mean;
if (!tf_.canTransform("base_footprint", pin.header.frame_id, pin.header.stamp, ros::Duration(5.0))){
ROS_ERROR("Cannot transform from base_footprint to %s", pin.header.frame_id.c_str());
return false;
}
tf_.transformPoint("base_footprint", pin, pout);
- if(pout.data.z > max_height_ || pout.data.z < min_height_){
- printf("Height not within admissable range: %f\n", pout.data.z);
+ if(pout.point.z > max_height_ || pout.point.z < min_height_){
+ printf("Height not within admissable range: %f\n", pout.point.z);
return false;
}
@@ -789,9 +789,9 @@
handle_stereo.header.frame_id = cloud_->header.frame_id;
handle_stereo.header.stamp = cloud_->header.stamp;
- handle_stereo.data.x = xstats.mean;
- handle_stereo.data.y = ystats.mean;
- handle_stereo.data.z = zstats.mean;
+ handle_stereo.point.x = xstats.mean;
+ handle_stereo.point.y = ystats.mean;
+ handle_stereo.point.z = zstats.mean;
if (!tf_.canTransform(handle.header.frame_id, handle_stereo.header.frame_id,
handle_stereo.header.stamp, ros::Duration(5.0))){
@@ -895,9 +895,9 @@
resp.doors.resize(1);
resp.doors[0] = req.door;
resp.doors[0].header.stamp = handle.header.stamp; // set time stamp
- resp.doors[0].handle.x = handle.data.x;
- resp.doors[0].handle.y = handle.data.y;
- resp.doors[0].handle.z = handle.data.z;
+ resp.doors[0].handle.x = handle.point.x;
+ resp.doors[0].handle.y = handle.point.y;
+ resp.doors[0].handle.z = handle.point.z;
resp.doors[0].weight = 1;
}else{
resp.doors[0] = req.door;
Modified: pkg/trunk/stacks/semantic_mapping/plug_onbase_detector/include/plug_onbase_detector/plug_onbase_detector.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/plug_onbase_detector/include/plug_onbase_detector/plug_onbase_detector.h 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/semantic_mapping/plug_onbase_detector/include/plug_onbase_detector/plug_onbase_detector.h 2009-08-08 05:44:57 UTC (rev 21149)
@@ -450,19 +450,19 @@
geometry_msgs::PointStamped viewpoint_laser;
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
{
tf->transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud);
//ROS_INFO ("Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (),
- // viewpoint_cloud.data.x, viewpoint_cloud.data.y, viewpoint_cloud.data.z);
+ // viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z);
}
catch (tf::ConnectivityException)
{
ROS_WARN ("Could not transform a point from frame %s to frame %s!", viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str ());
// Default to 0.05, 0, 0.942768
- viewpoint_cloud.data.x = 0.05; viewpoint_cloud.data.y = 0.0; viewpoint_cloud.data.z = 0.942768;
+ viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768;
}
}
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h 2009-08-08 05:44:57 UTC (rev 21149)
@@ -236,9 +236,9 @@
{
// See if we need to flip any plane normals
float vp_m[3];
- vp_m[0] = viewpoint.data.x - point.x;
- vp_m[1] = viewpoint.data.y - point.y;
- vp_m[2] = viewpoint.data.z - point.z;
+ vp_m[0] = viewpoint.point.x - point.x;
+ vp_m[1] = viewpoint.point.y - point.y;
+ vp_m[2] = viewpoint.point.z - point.z;
// Dot product between the (viewpoint - point) and the plane normal
double cos_theta = (vp_m[0] * normal (0) + vp_m[1] * normal (1) + vp_m[2] * normal (2));
@@ -320,9 +320,9 @@
{
// See if we need to flip any plane normals
float vp_m[3];
- vp_m[0] = viewpoint.data.x - point.x;
- vp_m[1] = viewpoint.data.y - point.y;
- vp_m[2] = viewpoint.data.z - point.z;
+ vp_m[0] = viewpoint.point.x - point.x;
+ vp_m[1] = viewpoint.point.y - point.y;
+ vp_m[2] = viewpoint.point.z - point.z;
// Dot product between the (viewpoint - point) and the plane normal
double cos_theta = (vp_m[0] * normal[0] + vp_m[1] * normal[1] + vp_m[2] * normal[2]);
Modified: 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/cloud_io/tools/bag_to_pcd.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_io/tools/bag_to_pcd.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -85,7 +85,7 @@
return;
geometry_msgs::PointStamped pin, pout;
pin.header.frame_id = "laser_tilt_mount_link";
- pin.data.x = pin.data.y = pin.data.z = 0.0;
+ pin.point.x = pin.point.y = pin.point.z = 0.0;
try
{
@@ -96,7 +96,7 @@
ROS_ERROR ("TF::ConectivityException caught while trying to transform a point from frame %s into %s!", cloud->header.frame_id.c_str (), pin.header.frame_id.c_str ());
}
ROS_INFO ("Received %d data points in frame %s with %d channels (%s). Viewpoint is <%.3f, %.3f, %.3f>", (int)cloud->points.size (), cloud->header.frame_id.c_str (),
- (int)cloud->channels.size (), cloud_geometry::getAvailableChannels (cloud).c_str (), pout.data.x, pout.data.y, pout.data.z);
+ (int)cloud->channels.size (), cloud_geometry::getAvailableChannels (cloud).c_str (), pout.point.x, pout.point.y, pout.point.z);
double c_time = cloud->header.stamp.sec * 1e3 + cloud->header.stamp.nsec;
sprintf (fn_, "%.0f.pcd", c_time);
@@ -120,9 +120,9 @@
cloud_out.channels[cloud->channels.size () - 1].values.resize (cloud->points.size ());
for (unsigned int i = 0; i < cloud->points.size (); i++)
{
- cloud_out.channels[cloud->channels.size () - 3].values[i] = pout.data.x;
- cloud_out.channels[cloud->channels.size () - 2].values[i] = pout.data.y;
- cloud_out.channels[cloud->channels.size () - 1].values[i] = pout.data.z;
+ cloud_out.channels[cloud->channels.size () - 3].values[i] = pout.point.x;
+ cloud_out.channels[cloud->channels.size () - 2].values[i] = pout.point.y;
+ cloud_out.channels[cloud->channels.size () - 1].values[i] = pout.point.z;
}
}
cloud_io::savePCDFileASCII (fn_, cloud_out, 5);
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -177,21 +177,21 @@
geometry_msgs::PointStamped viewpoint_laser;
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
{
tf.transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud);
ROS_INFO ("Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (),
- viewpoint_cloud.data.x, viewpoint_cloud.data.y, viewpoint_cloud.data.z);
+ viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z);
}
catch (...)
{
// Default to 0.05, 0, 0.942768 (base_link, ~base_footprint)
- viewpoint_cloud.data.x = 0.05; viewpoint_cloud.data.y = 0.0; viewpoint_cloud.data.z = 0.942768;
+ viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768;
ROS_WARN ("Could not transform a point from frame %s to frame %s! Defaulting to <%f, %f, %f>",
viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str (),
- viewpoint_cloud.data.x, viewpoint_cloud.data.y, viewpoint_cloud.data.z);
+ viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z);
}
}
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation_in_proc.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation_in_proc.cpp 2009-08-08 05:44:47 UTC (rev 21148)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/normal_estimation_in_proc.cpp 2009-08-08 05:44:57 UTC (rev 21149)
@@ -114,21 +114,21 @@
geometry_msgs::PointStamped viewpoint_laser;
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
{
tf.transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud);
ROS_INFO ("Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (),
- viewpoint_cloud.data.x, viewpoint_cloud.data.y, viewpoint_cloud.data.z);
+ viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z);
}
catch (...)
{
// Default to 0.05, 0, 0.942768 (base_link, ~base_footprint)
- viewpoint_cloud.data.x = 0.05; viewpoint_cloud.data.y = 0.0; viewpoint_cloud.data.z...
[truncated message content] |