|
From: <vij...@us...> - 2009-09-01 18:51:39
|
Revision: 23590
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23590&view=rev
Author: vijaypradeep
Date: 2009-09-01 18:51:29 +0000 (Tue, 01 Sep 2009)
Log Message:
-----------
Adding msgs for laser calibration pipeline
Added Paths:
-----------
pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserObjectFeatures.msg
pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserPoint.msg
pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserSnapshot.msg
Removed Paths:
-------------
pkg/trunk/calibration_experimental/experimental_calibration_msgs/msg/DenseLaserSnapshot.msg
Deleted: pkg/trunk/calibration_experimental/experimental_calibration_msgs/msg/DenseLaserSnapshot.msg
===================================================================
--- pkg/trunk/calibration_experimental/experimental_calibration_msgs/msg/DenseLaserSnapshot.msg 2009-09-01 18:48:24 UTC (rev 23589)
+++ pkg/trunk/calibration_experimental/experimental_calibration_msgs/msg/DenseLaserSnapshot.msg 2009-09-01 18:51:29 UTC (rev 23590)
@@ -1,39 +0,0 @@
-# Provides all the state & sensor information for
-# a single sweep of laser attached to some mechanism.
-# Most likely, this 'mechanism' will be the tilting stage
-Header header
-
-# Store the laser intrinsics. This is very similar to the
-# intrinsics commonly stored in
-float32 angle_min # start angle of the scan [rad]
-float32 angle_max # end angle of the scan [rad]
-float32 angle_increment # angular distance between measurements [rad]
-float32 time_increment # time between measurements [seconds]
-float32 range_min # minimum range value [m]
-float32 range_max # maximum range value [m]
-
-# Define the size of the binary data
-uint32 readings_per_scan # (Width)
-uint32 num_scans # (Height)
-
-# 2D Arrays storing laser data.
-# We can think of each type data as being a single channel image.
-# Each row of the image has data from a single scan, and scans are
-# concatenated to form the entire 'image'.
-float32[] ranges # (Image data)
-float32[] intensities # (Image data)
-
-# Joint information
-# Store joint information associated with each scan
-uint32 joint_encoding
-float64[] joint_positions
-float64[] joint_velocities
-string[] joint_names
-uint32 POS_PER_PIXEL = 0
-uint32 POS_PER_ROW_START = 1
-uint32 POS_PER_ROW_START_AND_END = 2
-
-# 1D Data storing meta information for each scan/row
-# Currently in stable, time vectors are not serialized correctly
-time[] scan_start
-
Added: pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserObjectFeatures.msg
===================================================================
--- pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserObjectFeatures.msg (rev 0)
+++ pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserObjectFeatures.msg 2009-09-01 18:51:29 UTC (rev 23590)
@@ -0,0 +1,11 @@
+# Synchronized with sensor output
+Header header
+
+# Pixel locations of detected features
+DenseLaserPoint[] dense_laser_points
+
+# Defines geometry of detected features in some "object" coordinate frame
+geometry_msgs/Point[] object_points
+
+# False on detection failure or partial detection
+uint8 success
Added: pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserPoint.msg
===================================================================
--- pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserPoint.msg (rev 0)
+++ pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserPoint.msg 2009-09-01 18:51:29 UTC (rev 23590)
@@ -0,0 +1,3 @@
+# Stores the xy subpixel location of a point in a DenseLaserSnapshot
+float64 scan # Which scan line we detected the feature
+float64 ray # Which ray in the specified scan we detected the feature
Copied: pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserSnapshot.msg (from rev 23589, pkg/trunk/calibration_experimental/experimental_calibration_msgs/msg/DenseLaserSnapshot.msg)
===================================================================
--- pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserSnapshot.msg (rev 0)
+++ pkg/trunk/stacks/calibration/calibration_msgs/msg/DenseLaserSnapshot.msg 2009-09-01 18:51:29 UTC (rev 23590)
@@ -0,0 +1,28 @@
+# Provides all the state & sensor information for
+# a single sweep of laser attached to some mechanism.
+# Most likely, this will be used with PR2's tilting laser mechanism
+Header header
+
+# Store the laser intrinsics. This is very similar to the
+# intrinsics commonly stored in
+float32 angle_min # start angle of the scan [rad]
+float32 angle_max # end angle of the scan [rad]
+float32 angle_increment # angular distance between measurements [rad]
+float32 time_increment # time between measurements [seconds]
+float32 range_min # minimum range value [m]
+float32 range_max # maximum range value [m]
+
+# Define the size of the binary data
+uint32 readings_per_scan # (Width)
+uint32 num_scans # (Height)
+
+# 2D Arrays storing laser data.
+# We can think of each type data as being a single channel image.
+# Each row of the image has data from a single scan, and scans are
+# concatenated to form the entire 'image'.
+float32[] ranges # (Image data)
+float32[] intensities # (Image data)
+
+# 1D Data storing meta information for each scan/row
+geometry_msgs/PoseStamped[] start_pose
+geometry_msgs/PoseStamped[] end_pose
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|