|
From: <tf...@us...> - 2008-10-24 23:57:44
|
Revision: 5771
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=5771&view=rev
Author: tfoote
Date: 2008-10-24 23:57:40 +0000 (Fri, 24 Oct 2008)
Log Message:
-----------
executing PointCloudFloat32 to PointCloud and Point3DFloat32 to Point32
Modified Paths:
--------------
pkg/trunk/deprecated/exec_trex/ROSNode.cc
pkg/trunk/deprecated/exec_trex/test/test.wpc.0.py
pkg/trunk/deprecated/exec_trex/test/test.wpc.1.py
pkg/trunk/deprecated/overhead_grasp_behavior/src/overhead_grasp.cc
pkg/trunk/deprecated/planning_world_viewer/src/planning_world_viewer.cpp
pkg/trunk/deprecated/rosControllers/include/rosControllers/RosJoint.h
pkg/trunk/deprecated/rosControllers/include/rosControllers/RosJointController.h
pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp
pkg/trunk/drivers/imu/imu_node/msg/ImuData.msg
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/grab_cloud_data.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_snapshotter.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/srv/BuildCloud.srv
pkg/trunk/drivers/robot/pr2/tilting_laser/src/tilting_laser/tilting_laser.cpp
pkg/trunk/drivers/robot/sensor_cart/src/sensor_recorder.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Block_Laser.hh
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc
pkg/trunk/grasp_module/grasp_learner/src/scan_voxelizer.cpp
pkg/trunk/grasp_module/grasp_module/msg/object_msg.msg
pkg/trunk/grasp_module/grasp_module/srv/object_detector_srv.srv
pkg/trunk/grasp_module/object_detector/src/objectDetector.cpp
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/test.wpc.0.py
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/test.wpc.1.py
pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
pkg/trunk/manip/arm_trajectory/arm_trajectory.cc
pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h
pkg/trunk/nav/sbpl_2dnav/src/sbpl_2dnav.cpp
pkg/trunk/robot_msgs/msg/Pose3DEulerFloat32.msg
pkg/trunk/simulators/simulator_integration_tests/world_3d_map_gazebo_tests/testcloud.py
pkg/trunk/util/laser_scan_utils/include/laser_scan_utils/laser_scan.h
pkg/trunk/util/laser_scan_utils/src/laser_scan.cc
pkg/trunk/util/rosTF/include/rosTF/rosTF.h
pkg/trunk/util/rosTF/src/rosTF.cpp
pkg/trunk/util/tf/mainpage.dox
pkg/trunk/vision/calib_converter/src/calib_converter.cpp
pkg/trunk/vision/dorylus/include/dorylus_node.h
pkg/trunk/vision/dorylus/src/dorylus_node.cpp
pkg/trunk/vision/scan_utils/include/dataTypes.h
pkg/trunk/vision/scan_utils/include/listen_node/scanListenNode.h
pkg/trunk/vision/scan_utils/include/smartScan.h
pkg/trunk/vision/scan_utils/msg/OctreeMsg.msg
pkg/trunk/vision/scan_utils/src/cloudToOctree/cloudToOctree.cpp
pkg/trunk/vision/scan_utils/src/dataTypes.cpp
pkg/trunk/vision/scan_utils/src/listen_node/scanListenNode.cpp
pkg/trunk/vision/scan_utils/src/smartScan.cpp
pkg/trunk/vision/spacetime_stereo/sts_dynamic.cpp
pkg/trunk/vision/spacetime_stereo/sts_node.cpp
pkg/trunk/visualization/cloud_viewer/src/cloud_node/cloud_node.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/laser_scan_visualizer.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/laser_scan_visualizer.h
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualizers/point_cloud_visualizer.h
pkg/trunk/visualization/scene_labeler/include/scene_labeler.h
pkg/trunk/visualization/scene_labeler/include/scene_labeler_stereo.h
pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler.cpp
pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp
pkg/trunk/visualization/scene_labeler/src/smallv_transformer/smallv_transformer.cpp
pkg/trunk/world_models/costmap_2d/include/costmap_2d/costmap_2d.h
pkg/trunk/world_models/costmap_2d/src/costmap_2d.cpp
pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp
pkg/trunk/world_models/costmap_2d/src/test/benchmark.cc
pkg/trunk/world_models/costmap_2d/src/test/module-tests.cc
pkg/trunk/world_models/fake_world_3d_map/src/fake_world_3d_map.cpp
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Modified: pkg/trunk/deprecated/exec_trex/ROSNode.cc
===================================================================
--- pkg/trunk/deprecated/exec_trex/ROSNode.cc 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/deprecated/exec_trex/ROSNode.cc 2008-10-24 23:57:40 UTC (rev 5771)
@@ -872,11 +872,11 @@
// Assemble a point cloud, in the laser's frame
- std_msgs::PointCloudFloat32 local_cloud;
+ std_msgs::PointCloud local_cloud;
projector_.projectLaser(*it, local_cloud, laser_maxrange);
// Convert to a point cloud in the map frame
- std_msgs::PointCloudFloat32 global_cloud;
+ std_msgs::PointCloud global_cloud;
try
{
Modified: pkg/trunk/deprecated/exec_trex/test/test.wpc.0.py
===================================================================
--- pkg/trunk/deprecated/exec_trex/test/test.wpc.0.py 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/deprecated/exec_trex/test/test.wpc.0.py 2008-10-24 23:57:40 UTC (rev 5771)
@@ -68,7 +68,7 @@
self.success = True
def test_wpc(self):
- rospy.TopicSub("groundtruthposition", Point3DFloat32, self.positionInput)
+ rospy.TopicSub("groundtruthposition", Point32, self.positionInput)
self.test.advertiseInitalPose2d(NAME)
rospy.ready(NAME, anonymous=True)
time.sleep(2.0)
Modified: pkg/trunk/deprecated/exec_trex/test/test.wpc.1.py
===================================================================
--- pkg/trunk/deprecated/exec_trex/test/test.wpc.1.py 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/deprecated/exec_trex/test/test.wpc.1.py 2008-10-24 23:57:40 UTC (rev 5771)
@@ -68,7 +68,7 @@
self.success = True
def test_wpc(self):
- rospy.TopicSub("groundtruthposition", Point3DFloat32, self.positionInput)
+ rospy.TopicSub("groundtruthposition", Point32, self.positionInput)
self.test.advertiseInitalPose2d(NAME)
rospy.ready(NAME, anonymous=True)
time.sleep(2.0)
Modified: pkg/trunk/deprecated/overhead_grasp_behavior/src/overhead_grasp.cc
===================================================================
--- pkg/trunk/deprecated/overhead_grasp_behavior/src/overhead_grasp.cc 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/deprecated/overhead_grasp_behavior/src/overhead_grasp.cc 2008-10-24 23:57:40 UTC (rev 5771)
@@ -48,7 +48,7 @@
@section topic ROS topics
Subscribes to (name/type):
- - @b "object_position" / @b std_msgs::Point3DFloat32 : 3d Pose of the object. This is the cheat laser pointer interface.
+ - @b "object_position" / @b std_msgs::Point32 : 3d Pose of the object. This is the cheat laser pointer interface.
- @b "rightarm_tooltip_cartesian" / @b pr2_msgs::EndEffectorState : current cartesian pose of the end effector.
Publishes to (name/type):
@@ -91,7 +91,7 @@
#include <pr2_kinematic_controllers/Float64Int32.h>
-#include <std_msgs/Point3DFloat32.h>
+#include <std_msgs/Point32.h>
#include <std_msgs/Float64.h>
#include <std_msgs/PR2Arm.h>
#include <unistd.h>
@@ -109,7 +109,7 @@
public:
// coordinates of arm's origin in gazebo/arm coordinate frame (the axes of both frames are parallel)
Vector gazebo_to_arm_vector;
- std_msgs::Point3DFloat32 objectPosMsg;
+ std_msgs::Point32 objectPosMsg;
pr2_msgs::EndEffectorState rightEndEffectorMsg;
Frame right_tooltip_frame;
Vector objectPosition;
Modified: pkg/trunk/deprecated/planning_world_viewer/src/planning_world_viewer.cpp
===================================================================
--- pkg/trunk/deprecated/planning_world_viewer/src/planning_world_viewer.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/deprecated/planning_world_viewer/src/planning_world_viewer.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -65,7 +65,7 @@
Additional subscriptions due to inheritance from NodeCollisionModel:
- @b localizedpose/RobotBase2DOdom : localized position of the robot base
-- @b world_3d_map/PointCloudFloat32 : point cloud with data describing the 3D environment
+- @b world_3d_map/PointCloud : point cloud with data describing the 3D environment
Publishes to (name/type):
- None
Modified: pkg/trunk/deprecated/rosControllers/include/rosControllers/RosJoint.h
===================================================================
--- pkg/trunk/deprecated/rosControllers/include/rosControllers/RosJoint.h 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/deprecated/rosControllers/include/rosControllers/RosJoint.h 2008-10-24 23:57:40 UTC (rev 5771)
@@ -31,8 +31,8 @@
// roscpp - laser
#include <std_msgs/LaserScan.h>
// roscpp - laser image (point cloud)
-#include <std_msgs/PointCloudFloat32.h>
-#include <std_msgs/Point3DFloat32.h>
+#include <std_msgs/PointCloud.h>
+#include <std_msgs/Point32.h>
#include <std_msgs/ChannelFloat32.h>
// roscpp - used for shutter message right now
#include <std_msgs/Empty.h>
Modified: pkg/trunk/deprecated/rosControllers/include/rosControllers/RosJointController.h
===================================================================
--- pkg/trunk/deprecated/rosControllers/include/rosControllers/RosJointController.h 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/deprecated/rosControllers/include/rosControllers/RosJointController.h 2008-10-24 23:57:40 UTC (rev 5771)
@@ -32,8 +32,8 @@
// roscpp - laser
#include <std_msgs/LaserScan.h>
// roscpp - laser image (point cloud)
-#include <std_msgs/PointCloudFloat32.h>
-#include <std_msgs/Point3DFloat32.h>
+#include <std_msgs/PointCloud.h>
+#include <std_msgs/Point32.h>
#include <std_msgs/ChannelFloat32.h>
// roscpp - used for shutter message right now
#include <std_msgs/Empty.h>
Modified: pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp
===================================================================
--- pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -37,7 +37,7 @@
#include "ros/node.h"
#include "std_msgs/Image.h"
#include "std_msgs/ImageArray.h"
-#include "std_msgs/PointCloudFloat32.h"
+#include "std_msgs/PointCloud.h"
#include "std_msgs/Empty.h"
#include "std_msgs/String.h"
@@ -78,7 +78,7 @@
public:
std_msgs::ImageArray img_;
- std_msgs::PointCloudFloat32 cloud_;
+ std_msgs::PointCloud cloud_;
ros::Time next_time_;
@@ -386,7 +386,7 @@
{
advertise<std_msgs::String>(cd.name + string("/cal_params"), 1);
advertise<std_msgs::ImageArray>(cd.name + string("/images"), 1);
- advertise<std_msgs::PointCloudFloat32>(cd.name + string("/cloud"), 1);
+ advertise<std_msgs::PointCloud>(cd.name + string("/cloud"), 1);
} else {
advertise<std_msgs::Image>(cd.name + string("/image"), 1);
advertise<std_msgs::Image>(cd.name + string("/images"), 1);
Modified: pkg/trunk/drivers/imu/imu_node/msg/ImuData.msg
===================================================================
--- pkg/trunk/drivers/imu/imu_node/msg/ImuData.msg 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/imu/imu_node/msg/ImuData.msg 2008-10-24 23:57:40 UTC (rev 5771)
@@ -1,3 +1,3 @@
Header header
-std_msgs/Point3DFloat32 accel
-std_msgs/Point3DFloat32 angrate
+std_msgs/Point32 accel
+std_msgs/Point32 angrate
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/grab_cloud_data.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/grab_cloud_data.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/grab_cloud_data.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -40,7 +40,7 @@
#include "point_cloud_assembler/BuildCloud.h"
// Messages
-#include "std_msgs/PointCloudFloat32.h"
+#include "std_msgs/PointCloud.h"
using namespace std_msgs ;
@@ -59,7 +59,7 @@
GrabCloudData() : ros::node("grab_cloud_data")
{
- advertise<PointCloudFloat32> ("full_cloud", 1) ;
+ advertise<PointCloud> ("full_cloud", 1) ;
}
~GrabCloudData()
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -66,7 +66,7 @@
#include "ros/node.h"
#include "rosTF/rosTF.h"
#include "std_msgs/LaserScan.h"
-#include "std_msgs/PointCloudFloat32.h"
+#include "std_msgs/PointCloud.h"
#include <deque>
@@ -141,8 +141,8 @@
unsigned int cloud_count = 0 ; // Store the number of points in the current cloud
- PointCloudFloat32 projector_cloud ; // Stores the current scan after being projected into the laser frame
- PointCloudFloat32 target_frame_cloud ; // Stores the current scan in the target frame
+ PointCloud projector_cloud ; // Stores the current scan after being projected into the laser frame
+ PointCloud target_frame_cloud ; // Stores the current scan in the target frame
unsigned int i = 0 ;
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_snapshotter.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_snapshotter.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_snapshotter.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -38,7 +38,7 @@
#include "point_cloud_assembler/BuildCloud.h"
// Messages
-#include "std_msgs/PointCloudFloat32.h"
+#include "std_msgs/PointCloud.h"
#include "pr2_mechanism_controllers/LaserScannerSignal.h"
using namespace std_msgs ;
@@ -62,7 +62,7 @@
{
prev_signal_.header.stamp.fromNSec(0) ;
- advertise<PointCloudFloat32> ("full_cloud", 1) ;
+ advertise<PointCloud> ("full_cloud", 1) ;
subscribe("laser_scanner_signal", cur_signal_, &PointCloudSnapshotter::scannerSignalCallback, 40) ;
}
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/srv/BuildCloud.srv
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/srv/BuildCloud.srv 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/srv/BuildCloud.srv 2008-10-24 23:57:40 UTC (rev 5771)
@@ -2,4 +2,4 @@
time end
string target_frame_id
---
-std_msgs/PointCloudFloat32 cloud
\ No newline at end of file
+std_msgs/PointCloud cloud
\ No newline at end of file
Modified: pkg/trunk/drivers/robot/pr2/tilting_laser/src/tilting_laser/tilting_laser.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/tilting_laser/src/tilting_laser/tilting_laser.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/robot/pr2/tilting_laser/src/tilting_laser/tilting_laser.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -78,9 +78,9 @@
- @b "mot"/<a href="../../std_msgs/html/classstd__msgs_1_1Actuator.html">Actuator</a> : encoder data from the tilting stage
Publishes to (name / type):
-- @b "cloud"/<a href="../../std_msgs/html/classstd__msgs_1_1PointCloudFloat32.html">PointCloudFloat32</a> : Incremental cloud data. Each scan from the laser is converted into a PointCloud.
+- @b "cloud"/<a href="../../std_msgs/html/classstd__msgs_1_1PointCloud.html">PointCloud</a> : Incremental cloud data. Each scan from the laser is converted into a PointCloud.
- @b "shutter"/<a href="../../std_msgs/html/classstd__msgs_1_1Empty.html">Empty</a> : An empty message is sent to indicate a full sweep has occured
-- @b "full_cloud"/<a href="../../std_msgs/html/classstd__msgs_1_1PointCloudFloat32.html">PointCloudFloat32</a> : A full point cloud containing all of the points between the last two shutters
+- @b "full_cloud"/<a href="../../std_msgs/html/classstd__msgs_1_1PointCloud.html">PointCloud</a> : A full point cloud containing all of the points between the last two shutters
- @b "laser_image"/<a href="../../std_msgs/html/classstd__msgs_1_1LaserImage.html">LaserImage</a> : A representation of the full point cloud as a pair of pseudo-images
- @b "image"/<a href="../../std_msgs/html/classstd__msgs_1_1Image.html">Image</a> : The intensity image from the LaserImage
- @b "mot_cmd"/<a href="../../std_msgs/html/classstd__msgs_1_1Actuator.html">Actuator</a> : The commanded position of the tilting stage
@@ -102,7 +102,7 @@
#include "rosTF/rosTF.h"
#include "std_msgs/Empty.h"
#include "std_msgs/LaserScan.h"
-#include "std_msgs/PointCloudFloat32.h"
+#include "std_msgs/PointCloud.h"
#include "std_msgs/LaserImage.h"
#include "std_msgs/Actuator.h"
@@ -120,7 +120,7 @@
rosTFClient tf;
laser_scan::LaserProjection projector;
- PointCloudFloat32 cloud;
+ PointCloud cloud;
Empty shutter;
Actuator cmd;
@@ -128,7 +128,7 @@
Actuator encoder;
LaserImage image;
- PointCloudFloat32 full_cloud;
+ PointCloud full_cloud;
int full_cloud_cnt;
int num_scans;
@@ -155,9 +155,9 @@
Tilting_Laser() : ros::node("tilting_laser"), tf(*this), full_cloud_cnt(0), sizes_ready(false), img_ind(-1), img_dir(1),last_ang(1000000), rate_err_down(0.0), rate_err_up(0.0), accum_angle(0.0), scan_received(false), count(0)
{
- advertise<PointCloudFloat32>("cloud", 1);
+ advertise<PointCloud>("cloud", 1);
advertise<Empty>("shutter", 1);
- advertise<PointCloudFloat32>("full_cloud", 1);
+ advertise<PointCloud>("full_cloud", 1);
advertise<LaserImage>("laser_image", 1);
advertise<Image>("image", 1);
advertise<Actuator>("mot_cmd", 100);
@@ -276,7 +276,7 @@
int cnt = 0;
- std_msgs::PointCloudFloat32 temp_cloud;
+ std_msgs::PointCloud temp_cloud;
projector.projectLaser(scans, temp_cloud);
cloud = tf.transformPointCloud("FRAMEID_TILT_BASE", temp_cloud);
Modified: pkg/trunk/drivers/robot/sensor_cart/src/sensor_recorder.cpp
===================================================================
--- pkg/trunk/drivers/robot/sensor_cart/src/sensor_recorder.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/robot/sensor_cart/src/sensor_recorder.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -5,7 +5,7 @@
#include "opencv/highgui.h"
#include "ros/node.h"
#include "std_msgs/LaserImage.h"
-#include "std_msgs/PointCloudFloat32.h"
+#include "std_msgs/PointCloud.h"
#include "image_utils/cv_bridge.h"
#include <sys/stat.h>
@@ -19,11 +19,11 @@
public:
LaserImage laser_img;
Image cam_img;
- PointCloudFloat32 cloud;
+ PointCloud cloud;
LaserImage laser_img_sv;
Image cam_img_sv;
- PointCloudFloat32 cloud_sv;
+ PointCloud cloud_sv;
CvBridge<Image> cam_bridge;
CvBridge<Image> laser_int_bridge;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox 2008-10-24 23:57:40 UTC (rev 5771)
@@ -292,7 +292,7 @@
<tr><td> \b base_scan </td> <td> std_msgs::LaserScan.msg </td> <td> Ros_Laser.hh </td> <td> Laser scans from Hokuyo at the base. </td> </tr>
<tr><td> \b tilt_scan </td> <td> std_msgs::LaserScan.msg </td> <td> Ros_Laser.hh </td> <td> Laser scans from tilting Hokuyo. </td> </tr>
- <tr><td> \b full_cloud </td> <td> std_msgs::PointCloudFloat32.msg </td> <td> Ros_Block_Laser.hh </td> <td> Simulated point clouds data from stereo camera. </td> </tr>
+ <tr><td> \b full_cloud </td> <td> std_msgs::PointCloud.msg </td> <td> Ros_Block_Laser.hh </td> <td> Simulated point clouds data from stereo camera. </td> </tr>
<tr><td> \b battery_state </td> <td> robot_msgs::BatteryStzte </td> <td> gazebo_battery.h </td> <td> Simulated battery state. </td> </tr>
<tr><td> \b diagnostic </td> <td> robot_msgs::DiagnosticMessage </td> <td> gazebo_battery.h </td> <td> Simulated battery diagnostic messages. </td> </tr>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Block_Laser.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Block_Laser.hh 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Block_Laser.hh 2008-10-24 23:57:40 UTC (rev 5771)
@@ -32,7 +32,7 @@
#include <ros/node.h>
#include <std_msgs/LaserScan.h>
-#include <std_msgs/PointCloudFloat32.h>
+#include <std_msgs/PointCloud.h>
namespace gazebo
{
@@ -90,7 +90,7 @@
\brief ROS laser block simulation.
\li Starts a ROS node if none exists.
\li This controller simulates a block of laser range detections.
- Resulting point cloud (std_msgs::PointCloudFloat32.msg) is published as a ROS topic.
+ Resulting point cloud (std_msgs::PointCloud.msg) is published as a ROS topic.
\li Example Usage:
\verbatim
<model:physical name="ray_model">
@@ -162,7 +162,7 @@
private: ros::node *rosnode;
/// \brief ros message
- private: std_msgs::PointCloudFloat32 cloudMsg;
+ private: std_msgs::PointCloud cloudMsg;
/// \brief topic name
private: std::string topicName;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc 2008-10-24 23:57:40 UTC (rev 5771)
@@ -81,7 +81,7 @@
{
this->topicName = node->GetString("topicName","default_ros_laser",0); //read from xml file
std::cout << "================= " << this->topicName << std::endl;
- rosnode->advertise<std_msgs::PointCloudFloat32>(this->topicName,10);
+ rosnode->advertise<std_msgs::PointCloud>(this->topicName,10);
this->frameName = node->GetString("frameName","default_ros_laser",0); //read from xml file
this->gaussianNoise = node->GetDouble("gaussianNoise",0.0,0); //read from xml file
Modified: pkg/trunk/grasp_module/grasp_learner/src/scan_voxelizer.cpp
===================================================================
--- pkg/trunk/grasp_module/grasp_learner/src/scan_voxelizer.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/grasp_module/grasp_learner/src/scan_voxelizer.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -6,7 +6,7 @@
#include "grasp_learner_types.h"
#include "grasp_learner/OctreeLearningMsg.h"
-#include "std_msgs/Point3DFloat32.h"
+#include "std_msgs/Point32.h"
#include <fstream>
#include <vector>
Modified: pkg/trunk/grasp_module/grasp_module/msg/object_msg.msg
===================================================================
--- pkg/trunk/grasp_module/grasp_module/msg/object_msg.msg 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/grasp_module/grasp_module/msg/object_msg.msg 2008-10-24 23:57:40 UTC (rev 5771)
@@ -1,4 +1,4 @@
-std_msgs/Point3DFloat32 centroid
-std_msgs/Point3DFloat32 axis1
-std_msgs/Point3DFloat32 axis2
-std_msgs/Point3DFloat32 axis3
\ No newline at end of file
+std_msgs/Point32 centroid
+std_msgs/Point32 axis1
+std_msgs/Point32 axis2
+std_msgs/Point32 axis3
\ No newline at end of file
Modified: pkg/trunk/grasp_module/grasp_module/srv/object_detector_srv.srv
===================================================================
--- pkg/trunk/grasp_module/grasp_module/srv/object_detector_srv.srv 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/grasp_module/grasp_module/srv/object_detector_srv.srv 2008-10-24 23:57:40 UTC (rev 5771)
@@ -1,4 +1,4 @@
-std_msgs/PointCloudFloat32 cloud
+std_msgs/PointCloud cloud
float32 connectedThreshold
int32 minComponentSize
float32 grazingThreshold
Modified: pkg/trunk/grasp_module/object_detector/src/objectDetector.cpp
===================================================================
--- pkg/trunk/grasp_module/object_detector/src/objectDetector.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/grasp_module/object_detector/src/objectDetector.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -95,7 +95,7 @@
if (mRemThresh != 0) {
//find table
fprintf(stderr,"Finding table...");
- std_msgs::Point3DFloat32 planePoint, planeNormal;
+ std_msgs::Point32 planePoint, planeNormal;
float fitValue = scan->ransacPlane(planePoint, planeNormal);
fprintf(stderr," done.\n");
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -1,6 +1,6 @@
#include "ros/node.h"
-#include "std_msgs/Point3DFloat32.h"
+#include "std_msgs/Point32.h"
#include <rosTF/rosTF.h>
using std::string;
@@ -10,11 +10,11 @@
*/
class GroundTruthTransform : public ros::node {
public:
- std_msgs::Point3DFloat32 msg;
+ std_msgs::Point32 msg;
rosTFClient tf;
GroundTruthTransform() : ros::node("GroundTruthTransform"), tf(*this, false) {
- advertise<std_msgs::Point3DFloat32>("groundtruthposition");
+ advertise<std_msgs::Point32>("groundtruthposition");
}
void speak() {
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/test.wpc.0.py
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/test.wpc.0.py 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/test.wpc.0.py 2008-10-24 23:57:40 UTC (rev 5771)
@@ -68,7 +68,7 @@
self.success = True
def test_wpc(self):
- rospy.TopicSub("groundtruthposition", Point3DFloat32, self.positionInput)
+ rospy.TopicSub("groundtruthposition", Point32, self.positionInput)
self.test.advertiseInitalPose2d(NAME)
rospy.ready(NAME, anonymous=True)
time.sleep(2.0)
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/test.wpc.1.py
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/test.wpc.1.py 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/test.wpc.1.py 2008-10-24 23:57:40 UTC (rev 5771)
@@ -67,7 +67,7 @@
self.success = True
def test_wpc(self):
- rospy.TopicSub("groundtruthposition", Point3DFloat32, self.positionInput)
+ rospy.TopicSub("groundtruthposition", Point32, self.positionInput)
self.test.advertiseInitalPose2d(NAME)
rospy.ready(NAME, anonymous=True)
time.sleep(2.0)
Modified: pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2008-10-24 23:57:40 UTC (rev 5771)
@@ -144,7 +144,7 @@
/**
* @brief Helper method to update the costmap and conduct other book-keeping
*/
- void updateDynamicObstacles(double ts, const std_msgs::PointCloudFloat32& cloud);
+ void updateDynamicObstacles(double ts, const std_msgs::PointCloud& cloud);
/**
* @brief Issue zero velocity commands
@@ -175,7 +175,7 @@
std_msgs::LaserScan laserScanMsg_; /**< Filled by subscriber with new laser scans */
- std_msgs::PointCloudFloat32 pointCloudMsg_; /**< Filled by subscriber with point clouds */
+ std_msgs::PointCloud pointCloudMsg_; /**< Filled by subscriber with point clouds */
std_msgs::RobotBase2DOdom odomMsg_; /**< Odometry in the odom frame picked up by subscription */
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -35,7 +35,7 @@
#include <MoveBase.hh>
#include <std_msgs/BaseVel.h>
-#include <std_msgs/PointCloudFloat32.h>
+#include <std_msgs/PointCloud.h>
#include <std_msgs/Pose2DFloat32.h>
#include <std_msgs/Polyline2D.h>
#include <std_srvs/StaticMap.h>
@@ -281,11 +281,11 @@
}
// Assemble a point cloud, in the laser's frame
- std_msgs::PointCloudFloat32 local_cloud;
+ std_msgs::PointCloud local_cloud;
projector_.projectLaser(laserScanMsg_, local_cloud, laserMaxRange_);
// Convert to a point cloud in the map frame
- std_msgs::PointCloudFloat32 global_cloud;
+ std_msgs::PointCloud global_cloud;
try
{
@@ -642,7 +642,7 @@
stopRobot();
}
- void MoveBase::updateDynamicObstacles(double ts, const std_msgs::PointCloudFloat32& cloud){
+ void MoveBase::updateDynamicObstacles(double ts, const std_msgs::PointCloud& cloud){
//Avoids laser race conditions.
if (!isInitialized()) {
return;
Modified: pkg/trunk/manip/arm_trajectory/arm_trajectory.cc
===================================================================
--- pkg/trunk/manip/arm_trajectory/arm_trajectory.cc 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/manip/arm_trajectory/arm_trajectory.cc 2008-10-24 23:57:40 UTC (rev 5771)
@@ -64,7 +64,7 @@
void SendTrajectory();
// for the point cloud data
- ringBuffer<std_msgs::Point3DFloat32> *trajectory_p;
+ ringBuffer<std_msgs::Point32> *trajectory_p;
ringBuffer<std_msgs::Float32> *trajectory_v;
// keep count for full cloud
@@ -85,7 +85,7 @@
srand(time(NULL));
// Initialize ring buffer for point cloud data
- this->trajectory_p = new ringBuffer<std_msgs::Point3DFloat32>();
+ this->trajectory_p = new ringBuffer<std_msgs::Point32>();
this->trajectory_v = new ringBuffer<std_msgs::Float32 >();
// FIXME: move this to Advertise/Subscribe Models
@@ -156,7 +156,7 @@
{
this->lock.lock();
- std_msgs::Point3DFloat32 tmp_trajectory_p;
+ std_msgs::Point32 tmp_trajectory_p;
std_msgs::Float32 tmp_trajectory_v;
/***************************************************************/
@@ -173,7 +173,7 @@
tmp_trajectory_v.data = 1.0;
// push pcd point into structure
- this->trajectory_p->add((std_msgs::Point3DFloat32)tmp_trajectory_p);
+ this->trajectory_p->add((std_msgs::Point32)tmp_trajectory_p);
this->trajectory_v->add( tmp_trajectory_v);
}
Modified: pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/motion_planning/kinematic_planning/src/kinematic_planning.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -105,7 +105,7 @@
Additional subscriptions due to inheritance from NodeCollisionModel:
- @b localizedpose/RobotBase2DOdom : localized position of the robot base
-- @b world_3d_map/PointCloudFloat32 : point cloud with data describing the 3D environment
+- @b world_3d_map/PointCloud : point cloud with data describing the 3D environment
Publishes to (name/type):
- @b planning_statistics/String : a messsage with statistics about computed motion plans
Modified: pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -65,7 +65,7 @@
Additional subscriptions due to inheritance from NodeCollisionModel:
- @b localizedpose/RobotBase2DOdom : localized position of the robot base
-- @b world_3d_map/PointCloudFloat32 : point cloud with data describing the 3D environment
+- @b world_3d_map/PointCloud : point cloud with data describing the 3D environment
Publishes to (name/type):
- None
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h 2008-10-24 23:57:40 UTC (rev 5771)
@@ -35,7 +35,7 @@
/** \author Ioan Sucan */
#include <planning_node_util/knode.h>
-#include <std_msgs/PointCloudFloat32.h>
+#include <std_msgs/PointCloud.h>
#include <collision_space/environmentODE.h>
/** Main namespace */
@@ -52,7 +52,7 @@
@section topic ROS topics
Subscribes to (name/type):
- - @b world_3d_map/PointCloudFloat32 : point cloud with data describing the 3D environment
+ - @b world_3d_map/PointCloud : point cloud with data describing the 3D environment
Additional subscriptions due to inheritance from NodeRobotModel:
- @b localizedpose/RobotBase2DOdom : localized position of the robot base
@@ -139,7 +139,7 @@
protected:
- std_msgs::PointCloudFloat32 m_worldCloud;
+ std_msgs::PointCloud m_worldCloud;
collision_space::EnvironmentModel *m_collisionSpace;
double m_sphereSize;
Modified: pkg/trunk/nav/sbpl_2dnav/src/sbpl_2dnav.cpp
===================================================================
--- pkg/trunk/nav/sbpl_2dnav/src/sbpl_2dnav.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/nav/sbpl_2dnav/src/sbpl_2dnav.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -40,7 +40,7 @@
// For transform support
#include <rosTF/rosTF.h>
-#include <std_msgs/PointCloudFloat32.h>
+#include <std_msgs/PointCloud.h>
#include <std_msgs/Planner2DGoal.h>
#include <pr2_msgs/OccDiff.h>
#include <std_srvs/StaticMap.h>
Modified: pkg/trunk/robot_msgs/msg/Pose3DEulerFloat32.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/Pose3DEulerFloat32.msg 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/robot_msgs/msg/Pose3DEulerFloat32.msg 2008-10-24 23:57:40 UTC (rev 5771)
@@ -1,3 +1,3 @@
Header header
-std_msgs/Point3DFloat32 position
+std_msgs/Point32 position
std_msgs/EulerAnglesFloat32 orientation
Modified: pkg/trunk/simulators/simulator_integration_tests/world_3d_map_gazebo_tests/testcloud.py
===================================================================
--- pkg/trunk/simulators/simulator_integration_tests/world_3d_map_gazebo_tests/testcloud.py 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/simulators/simulator_integration_tests/world_3d_map_gazebo_tests/testcloud.py 2008-10-24 23:57:40 UTC (rev 5771)
@@ -72,7 +72,7 @@
def test_cloud(self):
print "LNK\n"
- rospy.TopicSub("world_3d_map", PointCloudFloat32, self.pointInput)
+ rospy.TopicSub("world_3d_map", PointCloud, self.pointInput)
rospy.ready(NAME, anonymous=True)
timeout_t = time.time() + 30.0 #30 seconds
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
Modified: pkg/trunk/util/laser_scan_utils/include/laser_scan_utils/laser_scan.h
===================================================================
--- pkg/trunk/util/laser_scan_utils/include/laser_scan_utils/laser_scan.h 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/util/laser_scan_utils/include/laser_scan_utils/laser_scan.h 2008-10-24 23:57:40 UTC (rev 5771)
@@ -39,8 +39,8 @@
#include <newmat10/newmatap.h>
#include "std_msgs/LaserScan.h"
-#include "std_msgs/PointCloudFloat32.h"
#include "std_msgs/PointCloud.h"
+#include "std_msgs/PointCloud.h"
/* \mainpage
* This is a class for laser scan utilities.
@@ -68,8 +68,6 @@
* \param preservative Default: false If true all points in scan will be projected, including out of range values. Otherwise they will not be added to the cloud.
*/
void projectLaser(const std_msgs::LaserScan& scan_in, std_msgs::PointCloud & cloud_out, double range_cutoff=-1.0, bool preservative = false);
- ///\todo depricated remove soon
- void projectLaser(const std_msgs::LaserScan& scan_in, std_msgs::PointCloudFloat32 & cloud_out, double range_cutoff=-1.0, bool preservative = false)__attribute__((deprecated));
/** \brief Return the unit vectors for this configuration
Modified: pkg/trunk/util/laser_scan_utils/src/laser_scan.cc
===================================================================
--- pkg/trunk/util/laser_scan_utils/src/laser_scan.cc 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/util/laser_scan_utils/src/laser_scan.cc 2008-10-24 23:57:40 UTC (rev 5771)
@@ -97,72 +97,7 @@
cloud_out.chan[0].set_vals_size(count);
};
- void LaserProjection::projectLaser(const std_msgs::LaserScan& scan_in, std_msgs::PointCloudFloat32 & cloud_out, double range_cutoff, bool preservative)
- {
- NEWMAT::Matrix ranges(2, scan_in.get_ranges_size());
- double * matPointer = ranges.Store();
- // Fill the ranges matrix
- for (unsigned int index = 0; index < scan_in.get_ranges_size(); index++)
- {
- matPointer[index] = (double) scan_in.ranges[index];
- matPointer[index+scan_in.get_ranges_size()] = (double) scan_in.ranges[index];
- }
-
- //Do the projection
- NEWMAT::Matrix output = NEWMAT::SP(ranges, getUnitVectors(scan_in.angle_min, scan_in.angle_max, scan_in.angle_increment));
-
-
- //Stuff the output cloud
- cloud_out.header = scan_in.header;
- cloud_out.set_pts_size(scan_in.get_ranges_size());
- if (scan_in.get_intensities_size() > 0)
- {
- cloud_out.set_chan_size(1);
- cloud_out.chan[0].name ="intensities";
- cloud_out.chan[0].set_vals_size(scan_in.get_intensities_size());
- }
-
- double* outputMat = output.Store();
-
- if (range_cutoff < 0)
- range_cutoff = scan_in.range_max;
- else
- range_cutoff = std::min(range_cutoff, (double)scan_in.range_max);
-
- unsigned int count = 0;
- for (unsigned int index = 0; index< scan_in.get_ranges_size(); index++)
- {
- if (!preservative){ //Default behaviour will throw out invalid data
- if ((matPointer[index] < range_cutoff) &&
- (matPointer[index] > scan_in.range_min)) //only valid
- {
- cloud_out.pts[count].x = outputMat[index];
- cloud_out.pts[count].y = outputMat[index + scan_in.get_ranges_size()];
- cloud_out.pts[count].z = 0.0;
- if (scan_in.get_intensities_size() >= index) /// \todo optimize and catch length difference better
- cloud_out.chan[0].vals[count] = scan_in.intensities[index];
- count++;
- }
- }
- else { //Keep all points
- cloud_out.pts[count].x = outputMat[index];
- cloud_out.pts[count].y = outputMat[index + scan_in.get_ranges_size()];
- cloud_out.pts[count].z = 0.0;
- if (scan_in.get_intensities_size() >= index) /// \todo optimize and catch length difference better
- cloud_out.chan[0].vals[count] = scan_in.intensities[index];
- count++;
- }
-
- }
-
- //downsize if necessary
- cloud_out.set_pts_size(count);
- if (scan_in.intensities.size() > 0)
- cloud_out.chan[0].set_vals_size(count);
-
- };
-
NEWMAT::Matrix& LaserProjection::getUnitVectors(float angle_min, float angle_max, float angle_increment)
{
//construct string for lookup in the map
Modified: pkg/trunk/util/rosTF/include/rosTF/rosTF.h
===================================================================
--- pkg/trunk/util/rosTF/include/rosTF/rosTF.h 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/util/rosTF/include/rosTF/rosTF.h 2008-10-24 23:57:40 UTC (rev 5771)
@@ -44,7 +44,7 @@
#include "ros/node.h"
#include "rosTF/TransformArray.h"
#include "libTF/libTF.h"
-#include "std_msgs/PointCloudFloat32.h"
+#include "std_msgs/PointCloud.h"
#include "laser_scan_utils/laser_scan.h"
@@ -61,14 +61,14 @@
//Destructor
~rosTFClient();
- // PointCloudFloat32 transformPointCloud(unsigned int target_frame, const PointCloudFloat32 & cloudIn); // todo switch after ticket:232
- std_msgs::PointCloudFloat32 transformPointCloud(const std::string& target_frame, const std_msgs::PointCloudFloat32 & cloudIn);
- std_msgs::PointCloudFloat32 transformPointCloud(unsigned int target_frame, const std_msgs::PointCloudFloat32 & cloudIn);
- void transformPointCloud(const std::string & target_frame, std_msgs::PointCloudFloat32 & cloudOut, const std_msgs::PointCloudFloat32 & cloudIn) __attribute__((deprecated));
- void transformPointCloud(unsigned int target_frame, std_msgs::PointCloudFloat32 & cloudOut, const std_msgs::PointCloudFloat32 & cloudIn) __attribute__((deprecated));
+ // PointCloud transformPointCloud(unsigned int target_frame, const PointCloud & cloudIn); // todo switch after ticket:232
+ std_msgs::PointCloud transformPointCloud(const std::string& target_frame, const std_msgs::PointCloud & cloudIn);
+ std_msgs::PointCloud transformPointCloud(unsigned int target_frame, const std_msgs::PointCloud & cloudIn);
+ void transformPointCloud(const std::string & target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::PointCloud & cloudIn) __attribute__((deprecated));
+ void transformPointCloud(unsigned int target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::PointCloud & cloudIn) __attribute__((deprecated));
- void transformLaserScanToPointCloud(const std::string& target_frame, std_msgs::PointCloudFloat32 & cloudOut, const std_msgs::LaserScan & scanIn) __attribute__((deprecated));
- void transformLaserScanToPointCloud(unsigned int target_frame, std_msgs::PointCloudFloat32 & cloudOut, const std_msgs::LaserScan & scanIn) __attribute__((deprecated));
+ void transformLaserScanToPointCloud(const std::string& target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::LaserScan & scanIn) __attribute__((deprecated));
+ void transformLaserScanToPointCloud(unsigned int target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::LaserScan & scanIn) __attribute__((deprecated));
/** @brief Call back function for receiving on ROS */
void receiveArray();
Modified: pkg/trunk/util/rosTF/src/rosTF.cpp
===================================================================
--- pkg/trunk/util/rosTF/src/rosTF.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/util/rosTF/src/rosTF.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -51,7 +51,7 @@
};
-void rosTFClient::transformPointCloud(const std::string & target_frame, std_msgs::PointCloudFloat32 & cloudOut, const std_msgs::PointCloudFloat32 & cloudIn)
+void rosTFClient::transformPointCloud(const std::string & target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::PointCloud & cloudIn)
{
NEWMAT::Matrix transform = TransformReference::getMatrix(target_frame, cloudIn.header.frame_id, cloudIn.header.stamp.sec * 1000000000ULL + cloudIn.header.stamp.nsec);
@@ -93,16 +93,16 @@
};
}
-std_msgs::PointCloudFloat32 rosTFClient::transformPointCloud(const std::string & target_frame, const std_msgs::PointCloudFloat32 & cloudIn)
+std_msgs::PointCloud rosTFClient::transformPointCloud(const std::string & target_frame, const std_msgs::PointCloud & cloudIn)
{
- std_msgs::PointCloudFloat32 cloudOut;
+ std_msgs::PointCloud cloudOut;
transformPointCloud(target_frame, cloudOut, cloudIn);
return cloudOut;
};
-void rosTFClient::transformLaserScanToPointCloud(const std::string & target_frame, std_msgs::PointCloudFloat32 & cloudOut, const std_msgs::LaserScan & scanIn)
+void rosTFClient::transformLaserScanToPointCloud(const std::string & target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::LaserScan & scanIn)
{
cloudOut.header = scanIn.header;
cloudOut.header.frame_id = target_frame;
@@ -120,7 +120,7 @@
pointIn.frame = scanIn.header.frame_id;
///\todo this can be optimized
- std_msgs::PointCloudFloat32 intermediate; //optimize out
+ std_msgs::PointCloud intermediate; //optimize out
projector_.projectLaser(scanIn, intermediate, -1.0, true);
unsigned int count = 0;
Modified: pkg/trunk/util/tf/mainpage.dox
===================================================================
--- pkg/trunk/util/tf/mainpage.dox 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/util/tf/mainpage.dox 2008-10-24 23:57:40 UTC (rev 5771)
@@ -34,7 +34,7 @@
- Analogous ROS messages in std_msgs
-- One special message supported PointCloudFloat32 (Everything else defaults to 64 bit.)
+- One special message supported PointCloud (Everything else defaults to 64 bit.)
- Time represented by ros::Time and ros::Duration in ros/time.h in roscpp
Modified: pkg/trunk/vision/calib_converter/src/calib_converter.cpp
===================================================================
--- pkg/trunk/vision/calib_converter/src/calib_converter.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/vision/calib_converter/src/calib_converter.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -5,7 +5,7 @@
#include "opencv/cv.h"
#include "opencv/highgui.h"
#include "std_msgs/ImageArray.h"
-#include "std_msgs/PointCloudFloat32.h"
+#include "std_msgs/PointCloud.h"
#include "std_msgs/String.h"
#include "image_utils/cv_bridge.h"
#include <time.h>
@@ -61,7 +61,7 @@
map<string, imgData> images;
std_msgs::ImageArray image_msg;
std_msgs::String calparams;
- std_msgs::PointCloudFloat32 cloud;
+ std_msgs::PointCloud cloud;
string fullname;
calib_converter(string bag) : fullname(bag)
@@ -84,7 +84,7 @@
lp.open(fullname, ros::Time(0));
lp.addHandler<std_msgs::ImageArray>(string("videre/images"), ©Msg<std_msgs::ImageArray>, (void*)(&image_msg), true);
lp.addHandler<std_msgs::String>(string("videre/cal_params"), ©Msg<std_msgs::String>, (void*)(&calparams), true);
- lp.addHandler<std_msgs::PointCloudFloat32>(string("full_cloud"), ©Msg<std_msgs::PointCloudFloat32>, (void*)(&cloud), true);
+ lp.addHandler<std_msgs::PointCloud>(string("full_cloud"), ©Msg<std_msgs::PointCloud>, (void*)(&cloud), true);
while(lp.nextMsg());
Modified: pkg/trunk/vision/dorylus/include/dorylus_node.h
===================================================================
--- pkg/trunk/vision/dorylus/include/dorylus_node.h 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/vision/dorylus/include/dorylus_node.h 2008-10-24 23:57:40 UTC (rev 5771)
@@ -1,5 +1,5 @@
-#include <std_msgs/PointCloudFloat32.h>
-#include <std_msgs/Point3DFloat32.h>
+#include <std_msgs/PointCloud.h>
+#include <std_msgs/Point32.h>
#include <std_msgs/VisualizationMarker.h>
#include <ros/node.h>
#include <iostream>
Modified: pkg/trunk/vision/dorylus/src/dorylus_node.cpp
===================================================================
--- pkg/trunk/vision/dorylus/src/dorylus_node.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/vision/dorylus/src/dorylus_node.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -32,7 +32,7 @@
Dorylus d_;
std_msgs::String cal_params_msg_;
- std_msgs::PointCloudFloat32 ptcld_msg_;
+ std_msgs::PointCloud ptcld_msg_;
SmartScan ss_;
std_msgs::ImageArray images_msg_;
IplImage *img_, *vis_;
@@ -174,7 +174,7 @@
if(randId==-1)
randId = rand() % ss_.size();
- std_msgs::Point3DFloat32 pt = ss_.getPoint(randId);
+ std_msgs::Point32 pt = ss_.getPoint(randId);
float x = pt.x;
float y = pt.y;
float z = pt.z;
Modified: pkg/trunk/vision/scan_utils/include/dataTypes.h
===================================================================
--- pkg/trunk/vision/scan_utils/include/dataTypes.h 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/vision/scan_utils/include/dataTypes.h 2008-10-24 23:57:40 UTC (rev 5771)
@@ -32,14 +32,14 @@
#ifndef _datatypes_h_
#define _datatypes_h_
-#include <std_msgs/Point3DFloat32.h> //ROS native format for a point cloud
+#include <std_msgs/Point32.h> //ROS native format for a point cloud
#include <vector>
#include "assert.h"
namespace scan_utils{
/*! Convenience class for storing a Triangle as a list of three
- vertices stored each as a Point3DFloat32. Will probably be replaced
+ vertices stored each as a Point32. Will probably be replaced
at some point by a more elaborate ROS native data type.
Defines copy contructor and assignment operator, thus allowing
@@ -47,7 +47,7 @@
*/
class Triangle{
public:
- std_msgs::Point3DFloat32 p1,p2,p3;
+ std_msgs::Point32 p1,p2,p3;
Triangle() : p1(), p2(), p3(){}
Triangle(const Triangle &t) : p1(t.p1), p2(t.p2), p3(t.p3) {}
@@ -76,10 +76,10 @@
ROS-native math library
*/
- float norm(const std_msgs::Point3DFloat32 &f);
- std_msgs::Point3DFloat32 normalize(const std_msgs::Point3DFloat32 &f);
- float dot(const std_msgs::Point3DFloat32 &f1, const std_msgs::Point3DFloat32 &f2);
- std_msgs::Point3DFloat32 cross(const std_msgs::Point3DFloat32 &f1, const std_msgs::Point3DFloat32 &f2);
+ float norm(const std_msgs::Point32 &f);
+ std_msgs::Point32 normalize(const std_msgs::Point32 &f);
+ float dot(const std_msgs::Point32 &f1, const std_msgs::Point32 &f2);
+ std_msgs::Point32 cross(const std_msgs::Point32 &f1, const std_msgs::Point32 &f2);
/*! A 1D histogram.
*/
Modified: pkg/trunk/vision/scan_utils/include/listen_node/scanListenNode.h
===================================================================
--- pkg/trunk/vision/scan_utils/include/listen_node/scanListenNode.h 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/vision/scan_utils/include/listen_node/scanListenNode.h 2008-10-24 23:57:40 UTC (rev 5771)
@@ -35,7 +35,7 @@
#include <ros/node.h>
#include "rosthread/mutex.h"
-#include <std_msgs/PointCloudFloat32.h>
+#include <std_msgs/PointCloud.h>
#include <std_msgs/Empty.h>
/*! \file
@@ -55,8 +55,8 @@
class ScanListenNode : public ros::node
{
private:
- std_msgs::PointCloudFloat32 mNewCloud,mLastCloud;
- std_msgs::PointCloudFloat32 mNewLine,mCurrentCloud;
+ std_msgs::PointCloud mNewCloud,mLastCloud;
+ std_msgs::PointCloud mNewLine,mCurrentCloud;
std_msgs::Empty mEmptyMsg;
ros::thread::mutex mMutex;
@@ -65,7 +65,7 @@
void cloudCallback();
void shutterCallback();
- SmartScan* getScan(const std_msgs::PointCloudFloat32 &cloud);
+ SmartScan* getScan(const std_msgs::PointCloud &cloud);
public:
ScanListenNode();
Modified: pkg/trunk/vision/scan_utils/include/smartScan.h
===================================================================
--- pkg/trunk/vision/scan_utils/include/smartScan.h 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/vision/scan_utils/include/smartScan.h 2008-10-24 23:57:40 UTC (rev 5771)
@@ -32,8 +32,8 @@
#ifndef _smartscan_h_
#define _smartscan_h_
-#include <std_msgs/Point3DFloat32.h> //ROS native format for a point cloud
-#include <std_msgs/PointCloudFloat32.h>
+#include <std_msgs/Point32.h> //ROS native format for a point cloud
+#include <std_msgs/PointCloud.h>
#include <dataTypes.h> //my own data types defined in this library; probably just placeholder
//until ROS gets similar types
@@ -98,8 +98,8 @@
*/
class SmartScan {
private:
- //! "Native" data: an array of 3D vertices stored as ROS Point3DFloat32
- std_msgs::Point3DFloat32 *mNativePoints;
+ //! "Native" data: an array of 3D vertices stored as ROS Point32
+ std_msgs::Point32 *mNativePoints;
//! The number of vertices in the cloud
int mNumPoints;
//! The location of the scanner itself. Defaults to (0,0,0).
@@ -126,11 +126,11 @@
void clearData();
//! Apply the inner transform to a point
- std_msgs::Point3DFloat32 transformPoint(const std_msgs::Point3DFloat32 &p,
+ std_msgs::Point32 transformPoint(const std_msgs::Point32 &p,
libTF::TransformReference &tr) const;
//! Return the singular vectors of a Newmat matrix sorted in decreasing order of singular values
- void singularVectors(NEWMAT::Matrix *M, int n, std_msgs::Point3DFloat32 &sv1,
- std_msgs::Point3DFloat32 &sv2, std_msgs::Point3DFloat32 &sv3);
+ void singularVectors(NEWMAT::Matrix *M, int n, std_msgs::Point32 &sv1,
+ std_msgs::Point32 &sv2, std_msgs::Point32 &sv3);
public:
//! Empty constructor for a new point cloud that does not hold any data
SmartScan();
@@ -138,7 +138,7 @@
~SmartScan();
//! Set the native data of the point cloud
- void setPoints(int numPoints, const std_msgs::Point3DFloat32 *points);
+ void setPoints(int numPoints, const std_msgs::Point32 *points);
//! Set the native data as an array of floats; no ROS data type needed
void setPoints(int numPoints, const float *points);
//! Set scanner position and orientation
@@ -148,10 +148,10 @@
void getScanner(float &px, float &py, float &pz, float &dx, float &dy, float &dz,
float &ux, float &uy, float &uz);
- //! Set the data from a ROS PointCloudFloat32 message.
- void setFromRosCloud(const std_msgs::PointCloudFloat32 &cloud);
- //! Returns a PointCloudFloat32 ros msg.
- std_msgs::PointCloudFloat32 getPointCloud() const;
+ //! Set the data from a ROS PointCloud message.
+ void setFromRosCloud(const std_msgs::PointCloud &cloud);
+ //! Returns a PointCloud ros msg.
+ std_msgs::PointCloud getPointCloud() const;
//! Clears all the data inside this scan
void clear();
@@ -164,7 +164,7 @@
//! Returns the number of points in the cloud
inline int size() const {return mNumPoints;}
//! Returns the i-th point in the cloud.
- inline std_msgs::Point3DFloat32 getPoint(int i) const{
+ inline std_msgs::Point32 getPoint(int i) const{
assert( i>=0 && i<mNumPoints);
return mNativePoints[i];
}
@@ -193,9 +193,9 @@
//! Crops the point cloud to a 3D bounding box
void crop(float x, float y, float z, float dx, float dy, float dz);
//! Returns all the points in the scan that are within a given sphere
- std::vector<std_msgs::Point3DFloat32> *getPointsWithinRadius(float x, float y, float z, float radius);
+ std::vector<std_msgs::Point32> *getPointsWithinRadius(float x, float y, float z, float radius);
//! Returns all the points in the scan that are within a given sphere in ros pointcloud format.
- std_msgs::PointCloudFloat32 *getPointsWithinRadiusPointCloud(float x, float y, float z, float radius);
+ std_msgs::PointCloud *getPointsWithinRadiusPointCloud(float x, float y, float z, float radius);
//! Removes outliers - points that have few neighbors
void removeOutliers(float radius, int nbrs);
//! Removes points whose normals are perpendicular to the direction of the scanner
@@ -203,19 +203,19 @@
//! Returns the transform that registers this point cloud (computed using ICP).
float* ICPTo(SmartScan *target);
//! Finds the dominant plane in the point cloud by histograming point normals
- float normalHistogramPlane(std_msgs::Point3DFloat32 &planePoint, std_msgs::Point3DFloat32 &planeNormal,
+ float normalHistogramPlane(std_msgs::Point32 &planePoint, std_msgs::Point32 &planeNormal,
float radius = 0.01, int nbrs = 5);
//! Finds the dominant plane in the point cloud using RANSAC
- float ransacPlane(std_msgs::Point3DFloat32 &planePoint, std_msgs::Point3DFloat32 &planeNormal,
+ float ransacPlane(std_msgs::Point32 &planePoint, std_msgs::Point32 &planeNormal,
int iterations = 500, float distThresh = 0.02);
//! Removes all points that are close to a given plane
- void removePlane(const std_msgs::Point3DFloat32 &planePoint,
- const std_msgs::Point3DFloat32 &planeNormal, float thresh = 0.02);
+ void removePlane(const std_msgs::Point32 &planePoint,
+ const std_msgs::Point32 &planeNormal, float thresh = 0.02);
//! Computes the normal of a point by looking at its neighbors
- std_msgs::Point3DFloat32 computePointNormal(int id, float radius = 0.01, int nbrs = 5);
+ std_msgs::Point32 computePointNormal(int id, float radius = 0.01, int nbrs = 5);
//! Computes the normal of a point by looking at its neighbors
- std_msgs::Point3DFloat32 computePointNormal(float x, float y, float z, float radius = 0.01, int nbrs = 5);
+ std_msgs::Point32 computePointNormal(float x, float y, float z, float radius = 0.01, int nbrs = 5);
//! Returns the connected components in this scan, each in its own SmartScan
std::vector<SmartScan*> *connectedComponents(float thresh, int minPts = 0);
Modified: pkg/trunk/vision/scan_utils/msg/OctreeMsg.msg
===================================================================
--- pkg/trunk/vision/scan_utils/msg/OctreeMsg.msg 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/vision/scan_utils/msg/OctreeMsg.msg 2008-10-24 23:57:40 UTC (rev 5771)
@@ -1,5 +1,5 @@
-std_msgs/Point3DFloat32 center
-std_msgs/Point3DFloat32 size
+std_msgs/Point32 center
+std_msgs/Point32 size
byte[] empty_value
char uses_timestamps
int32 max_depth
Modified: pkg/trunk/vision/scan_utils/src/cloudToOctree/cloudToOctree.cpp
===================================================================
--- pkg/trunk/vision/scan_utils/src/cloudToOctree/cloudToOctree.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/vision/scan_utils/src/cloudToOctree/cloudToOctree.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -32,7 +32,7 @@
#include <ros/node.h>
#include "rosthread/mutex.h"
-#include <std_msgs/PointCloudFloat32.h>
+#include <std_msgs/PointCloud.h>
#include <octree.h>
#include <scan_utils/OctreeMsg.h>
@@ -55,7 +55,7 @@
{
private:
Octree<char> *mOctree;
- std_msgs::PointCloudFloat32 mNewCloud;
+ std_msgs::PointCloud mNewCloud;
void fullCloudCallback();
public:
CloudToOctree(float cellSize);
Modified: pkg/trunk/vision/scan_utils/src/dataTypes.cpp
===================================================================
--- pkg/trunk/vision/scan_utils/src/dataTypes.cpp 2008-10-24 23:56:43 UTC (rev 5770)
+++ pkg/trunk/vision/scan_utils/src/dataTypes.cpp 2008-10-24 23:57:40 UTC (rev 5771)
@@ -33,29 +33,29 @@
namespace scan_utils {
-float norm(const std_msgs::Point3DFloat32 &f)
+float norm(const std_msgs::Point32 &f)
{
return sqrt( f.x*f.x + f.y*f.y + f.z*f.z);
}
-std_msgs::Point3DFloat32 normalize(const std_msgs::Point3DFloat32 &f)
+std_msgs::Point32 normalize(const std_msgs::Point32 &f)
{
float n = scan_utils::norm(f);
- std_msgs::Point3DFloat32 p;
+ std_msgs::Point32 p;
p.x = f.x / n;
p.y = f.y / n;
p.z = f.z / n;
return p;
}
-float dot(const std_msgs::Point3DFloat32 &f1, const std_msgs::Point3DFloat32 &f2)
+float dot(const std_msgs::Point32 &f1, const std_msgs::Point32 &f2)
{
return f1.x*f2.x + f1.y*f2.y + f1.z*f2.z;
}
-std_msgs::Point3DFloat32 cross(const std_msgs::Point3DFloat32 &f1, const std_msgs::Point3DFloat32 &f2)
+std_msgs::Poin...
[truncated message content] |