|
From: <ehb...@us...> - 2009-08-05 18:20:27
|
Revision: 20799
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20799&view=rev
Author: ehberger
Date: 2009-08-05 18:20:13 +0000 (Wed, 05 Aug 2009)
Log Message:
-----------
Creating stack.xml for stacks that are missing them
Added Paths:
-----------
pkg/trunk/stacks/imu_drivers/stack.xml
pkg/trunk/stacks/joystick_drivers/stack.xml
pkg/trunk/stacks/laser_drivers/stack.xml
pkg/trunk/stacks/map_building/stack.xml
pkg/trunk/stacks/pr2/stack.xml
Added: pkg/trunk/stacks/imu_drivers/stack.xml
===================================================================
--- pkg/trunk/stacks/imu_drivers/stack.xml (rev 0)
+++ pkg/trunk/stacks/imu_drivers/stack.xml 2009-08-05 18:20:13 UTC (rev 20799)
@@ -0,0 +1,16 @@
+<stack name="imu_drivers" version="0.1.0">
+ <description brief="imu_drivers">
+
+ imu_drivers
+
+ </description>
+ <author>Blaise Gassend</author>
+ <license>BSD,LGPL</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/imu_drivers</url>
+ <depend stack="geometry"/> <!-- tf -->
+ <depend stack="hardware_test"/> <!-- self_test, diagnostic_updater -->
+ <depend stack="ros"/> <!-- roscpp, std_msgs, std_srvs, rosconsole -->
+ <depend stack="common_msgs"/> <!-- robot_srvs -->
+
+</stack>
Added: pkg/trunk/stacks/joystick_drivers/stack.xml
===================================================================
--- pkg/trunk/stacks/joystick_drivers/stack.xml (rev 0)
+++ pkg/trunk/stacks/joystick_drivers/stack.xml 2009-08-05 18:20:13 UTC (rev 20799)
@@ -0,0 +1,13 @@
+<stack name="joystick_drivers" version="0.1.0">
+ <description brief="joystick_drivers">
+
+ joystick_drivers
+
+ </description>
+ <author>Blaise Gassend</author>
+ <license>BSD</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/joystick_drivers</url>
+ <depend stack="ros"/> <!-- roscpp -->
+
+</stack>
Added: pkg/trunk/stacks/laser_drivers/stack.xml
===================================================================
--- pkg/trunk/stacks/laser_drivers/stack.xml (rev 0)
+++ pkg/trunk/stacks/laser_drivers/stack.xml 2009-08-05 18:20:13 UTC (rev 20799)
@@ -0,0 +1,15 @@
+<stack name="laser_drivers" version="0.1.0">
+ <description brief="laser_drivers">
+
+ laser_drivers
+
+ </description>
+ <author>Blaise Gassend</author>
+ <license>BSD,LGPL</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/laser_drivers</url>
+ <depend stack="hardware_test"/> <!-- self_test, diagnostic_updater -->
+ <depend stack="ros"/> <!-- roscpp, roscpp -->
+ <depend stack="common_msgs"/> <!-- sensor_msgs, sensor_msgs -->
+
+</stack>
Added: pkg/trunk/stacks/map_building/stack.xml
===================================================================
--- pkg/trunk/stacks/map_building/stack.xml (rev 0)
+++ pkg/trunk/stacks/map_building/stack.xml 2009-08-05 18:20:13 UTC (rev 20799)
@@ -0,0 +1,17 @@
+<stack name="map_building" version="0.1.0">
+ <description brief="map_building">
+
+ map_building
+
+ </description>
+ <author>Brian Gerkey</author>
+ <license>CreativeCommons-by-nc-sa-2.0</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/map_building</url>
+ <depend stack="geometry"/> <!-- tf -->
+ <depend stack="ros"/> <!-- roscpp, rosconsole, std_msgs -->
+ <depend stack="navigation"/> <!-- map_server -->
+ <depend stack="common"/> <!-- laser_scan -->
+ <depend stack="common_msgs"/> <!-- nav_msgs -->
+
+</stack>
Added: pkg/trunk/stacks/pr2/stack.xml
===================================================================
--- pkg/trunk/stacks/pr2/stack.xml (rev 0)
+++ pkg/trunk/stacks/pr2/stack.xml 2009-08-05 18:20:13 UTC (rev 20799)
@@ -0,0 +1,26 @@
+<stack name="pr2" version="0.1.0">
+ <description brief="pr2">
+
+ pr2
+
+ </description>
+ <author>Eric Berger</author>
+ <license>BSD</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/pr2</url>
+ <depend stack="util"/> <!-- realtime_tools -->
+ <depend stack="camera_drivers"/> <!-- dcam, prosilica_cam -->
+ <depend stack="calibration"/> <!-- joint_calibration_monitor -->
+ <depend stack="visualization_core"/> <!-- ogre_tools -->
+ <depend stack="drivers"/> <!-- forearm_cam -->
+ <depend stack="mechanism"/> <!-- mechanism_control, hardware_interface, mechanism_control, mechanism_model, convex_decomposition, ivcon, robot_state_publisher, mechanism_bringup, convex_decomposition, ivcon -->
+ <depend stack="controllers"/> <!-- robot_mechanism_controllers, pr2_mechanism_controllers, joint_qualification_controllers, dynamic_verification_controllers, pr2_mechanism_controllers, robot_mechanism_controllers -->
+ <depend stack="common"/> <!-- robot_actions, xacro -->
+ <depend stack="sound_drivers"/> <!-- sound_play -->
+ <depend stack="estimation"/> <!-- robot_pose_ekf -->
+ <depend stack="ros"/> <!-- std_msgs, roscpp, std_srvs, std_msgs, rxtools, rospy, roslib, std_srvs -->
+ <depend stack="common_msgs"/> <!-- robot_msgs, geometry_msgs, diagnostic_msgs -->
+ <depend stack="hardware_test"/> <!-- runtime_monitor -->
+ <depend stack="highlevel"/> <!-- door_msgs, plugs_msgs -->
+
+</stack>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <rob...@us...> - 2009-08-05 22:08:14
|
Revision: 20845
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20845&view=rev
Author: rob_wheeler
Date: 2009-08-05 22:07:38 +0000 (Wed, 05 Aug 2009)
Log Message:
-----------
Move PressureState and AccelerometerState messages to pr2_msgs.
Modified Paths:
--------------
pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/docsrc/doc.dox
pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/manifest.xml
pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/rectangle_viz.py
pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/sim_sensor.py
pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/sphere_viz.py
pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/src/fingertip_pressure/fingertip_panel.py
pkg/trunk/stacks/pr2_drivers/ethercat_hardware/CMakeLists.txt
pkg/trunk/stacks/pr2_drivers/ethercat_hardware/include/ethercat_hardware/wg0x.h
pkg/trunk/stacks/pr2_drivers/ethercat_hardware/manifest.xml
pkg/trunk/stacks/pr2_drivers/ethercat_hardware/src/wg0x.cpp
Added Paths:
-----------
pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/AccelerometerState.msg
pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/PressureState.msg
Removed Paths:
-------------
pkg/trunk/stacks/pr2_drivers/ethercat_hardware/msg/
pkg/trunk/stacks/pr2_drivers/ethercat_hardware/scripts/
Modified: pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/docsrc/doc.dox
===================================================================
--- pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/docsrc/doc.dox 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/docsrc/doc.dox 2009-08-05 22:07:38 UTC (rev 20845)
@@ -87,7 +87,7 @@
\subsubsection topics ROS topics
Subscribes to:
-- \b "/pressure/<gripper_motor_name>" "in": [ethercat_hardware/PressureState] Raw
+- \b "/pressure/<gripper_motor_name>" "in": [pr2_msgs/PressureState] Raw
data from the pressure sensor
- \b "/pressure/<gripper_motor_name>_info" "in": [fingertip_pressure/PressureInfo] Sensor calibration, geometry and tf frame.
Modified: pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/manifest.xml
===================================================================
--- pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/manifest.xml 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/manifest.xml 2009-08-05 22:07:38 UTC (rev 20845)
@@ -6,7 +6,7 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<url>http://pr.willowgarage.com</url>
-<depend package='ethercat_hardware'/>
+<depend package='pr2_msgs'/>
<depend package='rospy' />
<depend package='robot_msgs' />
<depend package='geometry_msgs' />
Modified: pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/rectangle_viz.py
===================================================================
--- pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/rectangle_viz.py 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/rectangle_viz.py 2009-08-05 22:07:38 UTC (rev 20845)
@@ -45,7 +45,7 @@
import threading
from fingertip_pressure.msg import PressureInfo, PressureInfoElement
-from ethercat_hardware.msg import PressureState
+from pr2_msgs.msg import PressureState
from visualization_msgs.msg import Marker
from robot_msgs.msg import Vector3
from fingertip_pressure.colormap import color
Modified: pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/sim_sensor.py
===================================================================
--- pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/sim_sensor.py 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/sim_sensor.py 2009-08-05 22:07:38 UTC (rev 20845)
@@ -44,7 +44,7 @@
from math import sin, cos
import threading
-from ethercat_hardware.msg import PressureState
+from pr2_msgs.msg import PressureState
class pressureSimulator:
def callback(self, pressurestate):
Modified: pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/sphere_viz.py
===================================================================
--- pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/sphere_viz.py 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/scripts/sphere_viz.py 2009-08-05 22:07:38 UTC (rev 20845)
@@ -45,7 +45,7 @@
import threading
from fingertip_pressure.msg import PressureInfo, PressureInfoElement
-from ethercat_hardware.msg import PressureState
+from pr2_msgs.msg import PressureState
from visualization_msgs.msg import Marker
from fingertip_pressure.colormap import color
from robot_msgs.msg import Vector3
Modified: pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/src/fingertip_pressure/fingertip_panel.py
===================================================================
--- pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/src/fingertip_pressure/fingertip_panel.py 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/src/fingertip_pressure/fingertip_panel.py 2009-08-05 22:07:38 UTC (rev 20845)
@@ -39,7 +39,7 @@
import sys
import rospy
-from ethercat_hardware.msg import PressureState
+from pr2_msgs.msg import PressureState
import math
from fingertip_pressure.colormap import color255
Modified: pkg/trunk/stacks/pr2_drivers/ethercat_hardware/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/pr2_drivers/ethercat_hardware/CMakeLists.txt 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/pr2_drivers/ethercat_hardware/CMakeLists.txt 2009-08-05 22:07:38 UTC (rev 20845)
@@ -1,8 +1,6 @@
cmake_minimum_required(VERSION 2.4.6)
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
rospack(ethercat_hardware)
-genmsg()
-gensrv()
rospack_add_boost_directories()
Modified: pkg/trunk/stacks/pr2_drivers/ethercat_hardware/include/ethercat_hardware/wg0x.h
===================================================================
--- pkg/trunk/stacks/pr2_drivers/ethercat_hardware/include/ethercat_hardware/wg0x.h 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/pr2_drivers/ethercat_hardware/include/ethercat_hardware/wg0x.h 2009-08-05 22:07:38 UTC (rev 20845)
@@ -38,8 +38,8 @@
#include <ethercat_hardware/ethercat_device.h>
#include <realtime_tools/realtime_publisher.h>
-#include <ethercat_hardware/PressureState.h>
-#include <ethercat_hardware/AccelerometerState.h>
+#include <pr2_msgs/PressureState.h>
+#include <pr2_msgs/AccelerometerState.h>
struct WG0XMbxHdr
{
@@ -353,8 +353,8 @@
bool use_ros_;
private:
uint32_t last_pressure_time_;
- realtime_tools::RealtimePublisher<ethercat_hardware::PressureState> *pressure_publisher_;
- realtime_tools::RealtimePublisher<ethercat_hardware::AccelerometerState> *accel_publisher_;
+ realtime_tools::RealtimePublisher<pr2_msgs::PressureState> *pressure_publisher_;
+ realtime_tools::RealtimePublisher<pr2_msgs::AccelerometerState> *accel_publisher_;
};
#endif /* WG0X_H */
Modified: pkg/trunk/stacks/pr2_drivers/ethercat_hardware/manifest.xml
===================================================================
--- pkg/trunk/stacks/pr2_drivers/ethercat_hardware/manifest.xml 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/pr2_drivers/ethercat_hardware/manifest.xml 2009-08-05 22:07:38 UTC (rev 20845)
@@ -6,6 +6,7 @@
<license>BSD</license>
<review status="unreviewed" notes="API review in progress (Rob)"/>
<url>http://pr.willowgarage.com</url>
+<depend package='pr2_msgs'/>
<depend package='hardware_interface'/>
<depend package='eml'/>
<depend package='tinyxml'/>
@@ -14,7 +15,7 @@
<depend package='realtime_tools' />
<depend package='diagnostic_msgs' />
<export>
- <cpp cflags="-I${prefix}/include -I${prefix}/msg/cpp" lflags="-L${prefix}/lib -lethercat_hardware -Wl,-rpath,${prefix}/lib -lloki"/>
+ <cpp cflags="-I${prefix}/include" lflags="-L${prefix}/lib -lethercat_hardware -Wl,-rpath,${prefix}/lib -lloki"/>
</export>
<repository>http://pr.willowgarage.com/repos</repository>
</package>
Modified: pkg/trunk/stacks/pr2_drivers/ethercat_hardware/src/wg0x.cpp
===================================================================
--- pkg/trunk/stacks/pr2_drivers/ethercat_hardware/src/wg0x.cpp 2009-08-05 22:03:20 UTC (rev 20844)
+++ pkg/trunk/stacks/pr2_drivers/ethercat_hardware/src/wg0x.cpp 2009-08-05 22:07:38 UTC (rev 20845)
@@ -222,14 +222,14 @@
string topic = "pressure";
if (!actuator->name_.empty())
topic = topic + "/" + string(actuator->name_);
- pressure_publisher_ = new realtime_tools::RealtimePublisher<ethercat_hardware::PressureState>(ros::NodeHandle(), topic, 1);
+ pressure_publisher_ = new realtime_tools::RealtimePublisher<pr2_msgs::PressureState>(ros::NodeHandle(), topic, 1);
if (fw_major_ >= 1)
{
topic = "/accelerometer/";
if (!actuator->name_.empty())
topic += actuator->name_;
- accel_publisher_ = new realtime_tools::RealtimePublisher<ethercat_hardware::AccelerometerState>(ros::NodeHandle(), topic, 1);
+ accel_publisher_ = new realtime_tools::RealtimePublisher<pr2_msgs::AccelerometerState>(ros::NodeHandle(), topic, 1);
}
}
Copied: pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/AccelerometerState.msg (from rev 20835, pkg/trunk/stacks/pr2_drivers/ethercat_hardware/msg/AccelerometerState.msg)
===================================================================
--- pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/AccelerometerState.msg (rev 0)
+++ pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/AccelerometerState.msg 2009-08-05 22:07:38 UTC (rev 20845)
@@ -0,0 +1,4 @@
+Header header
+float32[] x
+float32[] y
+float32[] z
Property changes on: pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/AccelerometerState.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/drivers/motor/ethercat_hardware/msg/AccelerometerState.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Copied: pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/PressureState.msg (from rev 20835, pkg/trunk/stacks/pr2_drivers/ethercat_hardware/msg/PressureState.msg)
===================================================================
--- pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/PressureState.msg (rev 0)
+++ pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/PressureState.msg 2009-08-05 22:07:38 UTC (rev 20845)
@@ -0,0 +1,3 @@
+Header header
+int16[] data0
+int16[] data1
Property changes on: pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/PressureState.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/drivers/motor/ethercat_hardware/msg/PressureState.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2009-08-06 16:33:17
|
Revision: 20906
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20906&view=rev
Author: gerkey
Date: 2009-08-06 16:33:04 +0000 (Thu, 06 Aug 2009)
Log Message:
-----------
Turned down chattiness of amcl tests and gmapping; also disabled gmapping tests
Modified Paths:
--------------
pkg/trunk/stacks/map_building/gmapping/CMakeLists.txt
pkg/trunk/stacks/map_building/gmapping/src/slam_gmapping.cpp
pkg/trunk/stacks/navigation/amcl/test/basic_localization.py
Modified: pkg/trunk/stacks/map_building/gmapping/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/map_building/gmapping/CMakeLists.txt 2009-08-06 15:56:28 UTC (rev 20905)
+++ pkg/trunk/stacks/map_building/gmapping/CMakeLists.txt 2009-08-06 16:33:04 UTC (rev 20906)
@@ -15,7 +15,8 @@
target_link_libraries(bin/slam_gmapping gridfastslam sensor_odometry sensor_range utils scanmatcher)
#rosbuild_add_executable(tftest src/tftest.cpp)
-#rosbuild_download_test_data(http://pr.willowgarage.com/data/gmapping/small_loop_prf.bag test/small_loop_prf.bag)
-rosbuild_download_test_data(http://pr.willowgarage.com/data/gmapping/basic_localization_stage.bag test/basic_localization_stage.bag)
-rosbuild_download_test_data(http://pr.willowgarage.com/data/gmapping/basic_localization_stage_groundtruth.pgm test/basic_localization_stage_groundtruth.pgm)
-rosbuild_add_rostest(test/basic_localization_stage.launch)
+# Need to make the tests more robust; currently the output map can differ
+# substantially between runs.
+#rosbuild_download_test_data(http://pr.willowgarage.com/data/gmapping/basic_localization_stage.bag test/basic_localization_stage.bag)
+#rosbuild_download_test_data(http://pr.willowgarage.com/data/gmapping/basic_localization_stage_groundtruth.pgm test/basic_localization_stage_groundtruth.pgm)
+#rosbuild_add_rostest(test/basic_localization_stage.launch)
Modified: pkg/trunk/stacks/map_building/gmapping/src/slam_gmapping.cpp
===================================================================
--- pkg/trunk/stacks/map_building/gmapping/src/slam_gmapping.cpp 2009-08-06 15:56:28 UTC (rev 20905)
+++ pkg/trunk/stacks/map_building/gmapping/src/slam_gmapping.cpp 2009-08-06 16:33:04 UTC (rev 20906)
@@ -38,7 +38,9 @@
{
// log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->setLevel(ros::console::g_level_lookup[ros::console::levels::Debug]);
- gsp_ = new GMapping::GridSlamProcessor(std::cerr);
+ // The library is pretty chatty
+ //gsp_ = new GMapping::GridSlamProcessor(std::cerr);
+ gsp_ = new GMapping::GridSlamProcessor();
ROS_ASSERT(gsp_);
tfB_ = new tf::TransformBroadcaster();
Modified: pkg/trunk/stacks/navigation/amcl/test/basic_localization.py
===================================================================
--- pkg/trunk/stacks/navigation/amcl/test/basic_localization.py 2009-08-06 15:56:28 UTC (rev 20905)
+++ pkg/trunk/stacks/navigation/amcl/test/basic_localization.py 2009-08-06 16:33:04 UTC (rev 20906)
@@ -26,9 +26,9 @@
for t in msg.transforms:
if t.parent_id == '/map':
self.tf = t.transform
- print 'Curr:\t %16.6f %16.6f' % (self.tf.translation.x, self.tf.translation.y)
- print 'Target:\t %16.6f %16.6f' % (self.target_x, self.target_y)
- print 'Diff:\t %16.6f %16.6f' % (abs(self.tf.translation.x-self.target_x),abs(self.tf.translation.y - self.target_y))
+ #print 'Curr:\t %16.6f %16.6f' % (self.tf.translation.x, self.tf.translation.y)
+ #print 'Target:\t %16.6f %16.6f' % (self.target_x, self.target_y)
+ #print 'Diff:\t %16.6f %16.6f' % (abs(self.tf.translation.x-self.target_x),abs(self.tf.translation.y - self.target_y))
def test_basic_localization(self):
global_localization = int(sys.argv[1])
@@ -40,22 +40,25 @@
target_time = float(sys.argv[7])
if global_localization == 1:
- print 'Waiting for service global_localization'
+ #print 'Waiting for service global_localization'
rospy.wait_for_service('global_localization')
global_localization = rospy.ServiceProxy('global_localization', Empty)
resp = global_localization()
rospy.init_node('test', anonymous=True)
while(rospy.rostime.get_time() == 0.0):
- print 'Waiting for initial time publication'
+ #print 'Waiting for initial time publication'
time.sleep(0.1)
start_time = rospy.rostime.get_time()
# TODO: This should be replace by a pytf listener
rospy.Subscriber('tf_message', tfMessage, self.tf_cb)
while (rospy.rostime.get_time() - start_time) < target_time:
- print 'Waiting for end time %.6f (current: %.6f)'%(target_time,(rospy.rostime.get_time() - start_time))
+ #print 'Waiting for end time %.6f (current: %.6f)'%(target_time,(rospy.rostime.get_time() - start_time))
time.sleep(0.1)
+ print 'Curr:\t %16.6f %16.6f' % (self.tf.translation.x, self.tf.translation.y)
+ print 'Target:\t %16.6f %16.6f' % (self.target_x, self.target_y)
+ print 'Diff:\t %16.6f %16.6f' % (abs(self.tf.translation.x-self.target_x),abs(self.tf.translation.y - self.target_y))
self.assertNotEquals(self.tf, None)
self.assertTrue(abs(self.tf.translation.x - self.target_x) <= tolerance_d)
self.assertTrue(abs(self.tf.translation.y - self.target_y) <= tolerance_d)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bla...@us...> - 2009-08-06 22:24:51
|
Revision: 20937
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20937&view=rev
Author: blaisegassend
Date: 2009-08-06 22:24:44 +0000 (Thu, 06 Aug 2009)
Log Message:
-----------
Moved pr2_power_board to the pr2_power_drivers stack
Added Paths:
-----------
pkg/trunk/stacks/pr2_power_drivers/
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/
Removed Paths:
-------------
pkg/trunk/stacks/pr2_drivers/pr2_power_board/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <stu...@us...> - 2009-08-07 02:52:19
|
Revision: 21000
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21000&view=rev
Author: stuglaser
Date: 2009-08-07 02:52:13 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
PRE now calibrates
Modified Paths:
--------------
pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py
pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch
pkg/trunk/stacks/pr2/pr2_default_controllers/pr2_calibration_controllers.yaml
Modified: pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py 2009-08-07 02:51:54 UTC (rev 20999)
+++ pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py 2009-08-07 02:52:13 UTC (rev 21000)
@@ -174,7 +174,7 @@
else:
casters = ['caster_fl', 'caster_fr', 'caster_bl', 'caster_br']
if '--alpha-head' in flags:
- head = ['head_pan_alpha2', 'head_tilt_alpha2']
+ head = ['head_pan_alpha2', 'head_tilt_alpha2b']
else:
head = ['head_pan', 'head_tilt']
Modified: pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch 2009-08-07 02:51:54 UTC (rev 20999)
+++ pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch 2009-08-07 02:52:13 UTC (rev 21000)
@@ -7,7 +7,7 @@
<!-- pr2_etherCAT -->
<node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i ecat0 -x /robot_description"/>
- <node pkg="mechanism_bringup" type="calibrate_pr2.py"
- args="$(find pr2_default_controllers)/calibration_controllers/pre_calibration_controller.xml"
- output="screen" />
+ <rosparam command="load" file="$(find pr2_default_controllers)/pr2_calibration_controllers.yaml" />
+ <rosparam command="load" file="$(find pr2_default_controllers)/pr2_joint_position_controllers.yaml" />
+ <node pkg="mechanism_bringup" type="calibrate_pr2.py" args="--alpha-head --alpha-casters" output="screen" />
</launch>
Modified: pkg/trunk/stacks/pr2/pr2_default_controllers/pr2_calibration_controllers.yaml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/pr2_calibration_controllers.yaml 2009-08-07 02:51:54 UTC (rev 20999)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/pr2_calibration_controllers.yaml 2009-08-07 02:52:13 UTC (rev 21000)
@@ -58,7 +58,7 @@
joint: r_upper_arm_roll_joint
actuator: r_upper_arm_roll_motor
transmission: r_upper_arm_roll_trans
- velocity: 1.0
+ velocity: 1.5
pid:
p: 6
i: 0.2
@@ -69,7 +69,7 @@
joint: l_upper_arm_roll_joint
actuator: l_upper_arm_roll_motor
transmission: l_upper_arm_roll_trans
- velocity: 1.0
+ velocity: 1.5
pid:
p: 6
i: 0.2
@@ -319,7 +319,7 @@
cal_head_tilt_alpha2b:
type: JointUDCalibrationController
joint: head_tilt_joint
- actuator: head_tilt_motor_alpha2b
+ actuator: head_tilt_motor
transmission: head_tilt_trans
velocity: -1.0
pid:
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bla...@us...> - 2009-08-07 03:29:13
|
Revision: 21003
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21003&view=rev
Author: blaisegassend
Date: 2009-08-07 03:29:05 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
Moved drivers out of pr2_drivers into pr2_power_drivers and
pr2_ethercat_drivers.
Added Paths:
-----------
pkg/trunk/stacks/ethercat_drivers/eml/
pkg/trunk/stacks/ethercat_drivers/ethercat_hardware/
pkg/trunk/stacks/pr2_ethercat_drivers/
pkg/trunk/stacks/pr2_power_drivers/ocean_battery_driver/
Removed Paths:
-------------
pkg/trunk/stacks/pr2_drivers/eml/
pkg/trunk/stacks/pr2_drivers/ethercat_hardware/
pkg/trunk/stacks/pr2_drivers/ocean_battery_driver/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bla...@us...> - 2009-08-07 03:32:14
|
Revision: 21004
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21004&view=rev
Author: blaisegassend
Date: 2009-08-07 03:32:05 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
Moved point_cloud_assembler to laser_drivers.
Added Paths:
-----------
pkg/trunk/stacks/laser_drivers/point_cloud_assembler/
Removed Paths:
-------------
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bla...@us...> - 2009-08-07 08:54:31
|
Revision: 21019
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21019&view=rev
Author: blaisegassend
Date: 2009-08-07 08:54:22 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
Moved contents of ethercat_drivers to pr2_ethercat_drivers
Modified Paths:
--------------
pkg/trunk/stacks/imu_drivers/stack.xml
pkg/trunk/stacks/joystick_drivers/stack.xml
pkg/trunk/stacks/laser_drivers/stack.xml
Added Paths:
-----------
pkg/trunk/stacks/pr2_ethercat_drivers/CMakeLists.txt
pkg/trunk/stacks/pr2_ethercat_drivers/Makefile
pkg/trunk/stacks/pr2_ethercat_drivers/eml/
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/
pkg/trunk/stacks/pr2_ethercat_drivers/fingertip_pressure/
pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml
Removed Paths:
-------------
pkg/trunk/stacks/ethercat_drivers/CMakeLists.txt
pkg/trunk/stacks/ethercat_drivers/Makefile
pkg/trunk/stacks/ethercat_drivers/eml/
pkg/trunk/stacks/ethercat_drivers/ethercat_hardware/
pkg/trunk/stacks/ethercat_drivers/fingertip_pressure/
pkg/trunk/stacks/ethercat_drivers/stack.xml
Deleted: pkg/trunk/stacks/ethercat_drivers/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/ethercat_drivers/CMakeLists.txt 2009-08-07 08:03:45 UTC (rev 21018)
+++ pkg/trunk/stacks/ethercat_drivers/CMakeLists.txt 2009-08-07 08:54:22 UTC (rev 21019)
@@ -1,21 +0,0 @@
-cmake_minimum_required(VERSION 2.4.6)
-include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
-
-set(ROSPACK_MAKEDIST true)
-
-# Append to CPACK_SOURCE_IGNORE_FILES a semicolon-separated list of
-# directories (or patterns, but directories should suffice) that should
-# be excluded from the distro. This is not the place to put things that
-# should be ignored everywhere, like "build" directories; that happens in
-# rosbuild/rosbuild.cmake. Here should be listed packages that aren't
-# ready for inclusion in a distro.
-#
-# This list is combined with the list in rosbuild/rosbuild.cmake. Note
-# that CMake 2.6 may be required to ensure that the two lists are combined
-# properly. CMake 2.4 seems to have unpredictable scoping rules for such
-# variables.
-#list(APPEND CPACK_SOURCE_IGNORE_FILES /core/experimental)
-
-rosbuild(ethercat_drivers 0.1.0)
-# After next ROS release, change to new macro
-#rosbuild_make_distribution(0.1.0)
Deleted: pkg/trunk/stacks/ethercat_drivers/Makefile
===================================================================
--- pkg/trunk/stacks/ethercat_drivers/Makefile 2009-08-07 08:03:45 UTC (rev 21018)
+++ pkg/trunk/stacks/ethercat_drivers/Makefile 2009-08-07 08:54:22 UTC (rev 21019)
@@ -1 +0,0 @@
-include $(shell rospack find mk)/cmake_stack.mk
Deleted: pkg/trunk/stacks/ethercat_drivers/stack.xml
===================================================================
--- pkg/trunk/stacks/ethercat_drivers/stack.xml 2009-08-07 08:03:45 UTC (rev 21018)
+++ pkg/trunk/stacks/ethercat_drivers/stack.xml 2009-08-07 08:54:22 UTC (rev 21019)
@@ -1,14 +0,0 @@
-<stack name="camera_drivers" version="0.1">
- <description brief="drivers related to ethercat">
- This stack contains drivers for the ethercat system and the peripherals
- that connect to it: motor control boards, fingertip sensors, texture
- projector, hand accelerometer.
- </description>
- <author>Maintained by Blaise Gassend</author>
- <review status="unreviewed" notes=""/>
- <url>http://pr.willowgarage.com/wiki/ethercat_drivers</url>
- <depend stack="ros"/> <!-- rospy, rostest, wxswig, roslaunch, pycrypto -->
- <depend stack="visualization_core"/> <!-- visualization_msgs -->
- <depend stack="common_msgs"/> <!-- robot_msgs, geometry_msgs -->
-
-</stack>
Modified: pkg/trunk/stacks/imu_drivers/stack.xml
===================================================================
--- pkg/trunk/stacks/imu_drivers/stack.xml 2009-08-07 08:03:45 UTC (rev 21018)
+++ pkg/trunk/stacks/imu_drivers/stack.xml 2009-08-07 08:54:22 UTC (rev 21019)
@@ -1,8 +1,6 @@
<stack name="imu_drivers" version="0.1.0">
- <description brief="imu_drivers">
-
- imu_drivers
-
+ <description brief="Drivers for IMUs">
+ This stack contains drivers for IMUs.
</description>
<author>Blaise Gassend</author>
<license>BSD,LGPL</license>
Modified: pkg/trunk/stacks/joystick_drivers/stack.xml
===================================================================
--- pkg/trunk/stacks/joystick_drivers/stack.xml 2009-08-07 08:03:45 UTC (rev 21018)
+++ pkg/trunk/stacks/joystick_drivers/stack.xml 2009-08-07 08:54:22 UTC (rev 21019)
@@ -1,8 +1,7 @@
<stack name="joystick_drivers" version="0.1.0">
- <description brief="joystick_drivers">
-
- joystick_drivers
-
+ <description brief="Drivers related to joysticks.">
+This stack contains a ROS node to interface with joysticks, and drivers
+for joysticks that are not well supported by a common linux distribution.
</description>
<author>Blaise Gassend</author>
<license>BSD</license>
Modified: pkg/trunk/stacks/laser_drivers/stack.xml
===================================================================
--- pkg/trunk/stacks/laser_drivers/stack.xml 2009-08-07 08:03:45 UTC (rev 21018)
+++ pkg/trunk/stacks/laser_drivers/stack.xml 2009-08-07 08:54:22 UTC (rev 21019)
@@ -1,8 +1,6 @@
<stack name="laser_drivers" version="0.1.0">
- <description brief="laser_drivers">
-
- laser_drivers
-
+ <description brief="Drivers for Laser Scanners">
+ This stack contains drivers for laser scanners.
</description>
<author>Blaise Gassend</author>
<license>BSD,LGPL</license>
Copied: pkg/trunk/stacks/pr2_ethercat_drivers/CMakeLists.txt (from rev 21018, pkg/trunk/stacks/ethercat_drivers/CMakeLists.txt)
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/CMakeLists.txt (rev 0)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/CMakeLists.txt 2009-08-07 08:54:22 UTC (rev 21019)
@@ -0,0 +1,21 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+set(ROSPACK_MAKEDIST true)
+
+# Append to CPACK_SOURCE_IGNORE_FILES a semicolon-separated list of
+# directories (or patterns, but directories should suffice) that should
+# be excluded from the distro. This is not the place to put things that
+# should be ignored everywhere, like "build" directories; that happens in
+# rosbuild/rosbuild.cmake. Here should be listed packages that aren't
+# ready for inclusion in a distro.
+#
+# This list is combined with the list in rosbuild/rosbuild.cmake. Note
+# that CMake 2.6 may be required to ensure that the two lists are combined
+# properly. CMake 2.4 seems to have unpredictable scoping rules for such
+# variables.
+#list(APPEND CPACK_SOURCE_IGNORE_FILES /core/experimental)
+
+rosbuild(ethercat_drivers 0.1.0)
+# After next ROS release, change to new macro
+#rosbuild_make_distribution(0.1.0)
Property changes on: pkg/trunk/stacks/pr2_ethercat_drivers/CMakeLists.txt
___________________________________________________________________
Added: svn:mergeinfo
+
Copied: pkg/trunk/stacks/pr2_ethercat_drivers/Makefile (from rev 21018, pkg/trunk/stacks/ethercat_drivers/Makefile)
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/Makefile (rev 0)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/Makefile 2009-08-07 08:54:22 UTC (rev 21019)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake_stack.mk
Property changes on: pkg/trunk/stacks/pr2_ethercat_drivers/Makefile
___________________________________________________________________
Added: svn:mergeinfo
+
Copied: pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml (from rev 21018, pkg/trunk/stacks/ethercat_drivers/stack.xml)
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml (rev 0)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml 2009-08-07 08:54:22 UTC (rev 21019)
@@ -0,0 +1,13 @@
+<stack name="pr2_ethercat_drivers" version="0.1">
+ <description brief="drivers related to ethercat">
+ This stack contains drivers for the ethercat system and the peripherals
+ that connect to it: motor control boards, fingertip sensors, texture
+ projector, hand accelerometer.
+ </description>
+ <author>Maintained by Rob Wheeler</author>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/ethercat_drivers</url>
+ <depend stack="ros"/> <!-- rospy, rostest, wxswig, roslaunch, pycrypto -->
+ <depend stack="visualization_core"/> <!-- visualization_msgs -->
+ <depend stack="common_msgs"/> <!-- robot_msgs, geometry_msgs -->
+</stack>
Property changes on: pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml
___________________________________________________________________
Added: svn:mergeinfo
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bla...@us...> - 2009-08-07 09:10:35
|
Revision: 21020
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21020&view=rev
Author: blaisegassend
Date: 2009-08-07 09:10:29 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
Got rid of ethercat_drivers. Tweaked pr2_ethercat_drivers stack.xml. Fixed a missing dependency in dynamic_reconfigure's cmake script.
Modified Paths:
--------------
pkg/trunk/stacks/driver_common/dynamic_reconfigure/cmake/cfgbuild.cmake
pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml
Removed Paths:
-------------
pkg/trunk/stacks/ethercat_drivers/
Modified: pkg/trunk/stacks/driver_common/dynamic_reconfigure/cmake/cfgbuild.cmake
===================================================================
--- pkg/trunk/stacks/driver_common/dynamic_reconfigure/cmake/cfgbuild.cmake 2009-08-07 08:54:22 UTC (rev 21019)
+++ pkg/trunk/stacks/driver_common/dynamic_reconfigure/cmake/cfgbuild.cmake 2009-08-07 09:10:29 UTC (rev 21020)
@@ -172,6 +172,7 @@
set(_output_getsrv ${PROJECT_SOURCE_DIR}/srv/Get${_cfg_bare}Config.srv)
set(_output_setsrv ${PROJECT_SOURCE_DIR}/srv/Set${_cfg_bare}Config.srv)
set(_output_dox ${PROJECT_SOURCE_DIR}/dox/${_cfg_bare}Config.dox)
+ set(_output_usage ${PROJECT_SOURCE_DIR}/dox/${_cfg_bare}Config-Usage.dox)
# Indicate the msg and srv files that will get generated.
string(REPLACE ${PROJECT_SOURCE_DIR}/msg/ "" _output_msg_name ${_output_msg})
@@ -183,10 +184,10 @@
# Add the rule to build the .h the .cfg and the .msg
# FIXME Horrible hack. Can't get CMAKE to add dependencies for anything
# but the first output in add_custom_command.
- add_custom_command(OUTPUT ${_output_msg} ${_output_cpp} ${_output_getsrv} ${_output_setsrv} ${_output_dox}
+ add_custom_command(OUTPUT ${_output_msg} ${_output_cpp} ${_output_getsrv} ${_output_setsrv} ${_output_dox} ${_output_usage}
COMMAND ${gencfg_cpp_exe} ${_input}
DEPENDS ${_input} ${gencfg_cpp_exe} ${ROS_MANIFEST_LIST} ${gencfg_build_files})
- list(APPEND _autogen ${_output_cpp} ${_output_msg} ${_output_getsrv} ${_output_setsrv} ${_output_dox})
+ list(APPEND _autogen ${_output_cpp} ${_output_msg} ${_output_getsrv} ${_output_setsrv} ${_output_dox} ${_output_usage})
endforeach(_cfg)
# Create a target that depends on the union of all the autogenerated
# files
Modified: pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml 2009-08-07 08:54:22 UTC (rev 21019)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml 2009-08-07 09:10:29 UTC (rev 21020)
@@ -1,5 +1,5 @@
<stack name="pr2_ethercat_drivers" version="0.1">
- <description brief="drivers related to ethercat">
+ <description brief="Drivers related to PR2 ethercat hardware">
This stack contains drivers for the ethercat system and the peripherals
that connect to it: motor control boards, fingertip sensors, texture
projector, hand accelerometer.
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-08-07 20:42:09
|
Revision: 21043
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21043&view=rev
Author: tfoote
Date: 2009-08-07 20:41:56 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
moving PoseArray into geometry_msgs #1907
Modified Paths:
--------------
pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp
pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
pkg/trunk/stacks/navigation/fake_localization/manifest.xml
pkg/trunk/stacks/navigation/nav_view/manifest.xml
pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h
pkg/trunk/stacks/visualization/rviz/manifest.xml
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseArray.msg
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg
Copied: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseArray.msg (from rev 20633, pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseArray.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/PoseArray.msg 2009-08-07 20:41:56 UTC (rev 21043)
@@ -0,0 +1,3 @@
+Header header
+
+geometry_msgs/Pose[] poses
Deleted: pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/msg/PoseArray.msg 2009-08-07 20:41:56 UTC (rev 21043)
@@ -1,3 +0,0 @@
-Header header
-
-geometry_msgs/Pose[] poses
Modified: pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/amcl/src/amcl_node.cpp 2009-08-07 20:41:56 UTC (rev 21043)
@@ -38,7 +38,7 @@
// Messages that I need
#include "sensor_msgs/LaserScan.h"
#include "geometry_msgs/PoseWithCovariance.h"
-#include "nav_msgs/PoseArray.h"
+#include "geometry_msgs/PoseArray.h"
#include "geometry_msgs/Pose.h"
#include "nav_msgs/GetMap.h"
#include "std_srvs/Empty.h"
@@ -320,7 +320,7 @@
laser_likelihood_max_dist);
ros::Node::instance()->advertise<geometry_msgs::PoseWithCovariance>("amcl_pose",2);
- ros::Node::instance()->advertise<nav_msgs::PoseArray>("particlecloud",2);
+ ros::Node::instance()->advertise<geometry_msgs::PoseArray>("particlecloud",2);
ros::Node::instance()->advertise<visualization_msgs::Polyline>("gui_laser",2);
ros::Node::instance()->advertiseService("global_localization",
&AmclNode::globalLocalizationCallback,
@@ -606,7 +606,7 @@
// Publish the resulting cloud
// TODO: set maximum rate for publishing
- nav_msgs::PoseArray cloud_msg;
+ geometry_msgs::PoseArray cloud_msg;
cloud_msg.header.stamp = ros::Time::now();
cloud_msg.header.frame_id = "map";
cloud_msg.set_poses_size(set->sample_count);
Modified: pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp
===================================================================
--- pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/fake_localization/fake_localization.cpp 2009-08-07 20:41:56 UTC (rev 21043)
@@ -60,7 +60,7 @@
Publishes to (name / type):
- @b "amcl_pose" geometry_msgs/PoseWithCovariance : robot's estimated pose in the map, with covariance
-- @b "particlecloud" nav_msgs/PoseArray : fake set of poses being maintained by the filter (one paricle only).
+- @b "particlecloud" geometry_msgs/PoseArray : fake set of poses being maintained by the filter (one paricle only).
<hr>
@@ -74,7 +74,7 @@
#include <ros/time.h>
#include <geometry_msgs/PoseWithRatesStamped.h>
-#include <nav_msgs/PoseArray.h>
+#include <geometry_msgs/PoseArray.h>
#include <geometry_msgs/PoseWithCovariance.h>
#include <angles/angles.h>
@@ -92,7 +92,7 @@
FakeOdomNode(void) : ros::Node("fake_localization")
{
advertise<geometry_msgs::PoseWithCovariance>("amcl_pose",1);
- advertise<nav_msgs::PoseArray>("particlecloud",1);
+ advertise<geometry_msgs::PoseArray>("particlecloud",1);
m_tfServer = new tf::TransformBroadcaster();
m_tfListener = new tf::TransformListener(*this);
m_lastUpdate = ros::Time::now();
@@ -140,7 +140,7 @@
bool m_base_pos_received;
geometry_msgs::PoseWithRatesStamped m_basePosMsg;
- nav_msgs::PoseArray m_particleCloud;
+ geometry_msgs::PoseArray m_particleCloud;
geometry_msgs::PoseWithCovariance m_currentPos;
//parameter for what odom to use
Modified: pkg/trunk/stacks/navigation/fake_localization/manifest.xml
===================================================================
--- pkg/trunk/stacks/navigation/fake_localization/manifest.xml 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/fake_localization/manifest.xml 2009-08-07 20:41:56 UTC (rev 21043)
@@ -7,6 +7,7 @@
<depend package="roscpp" />
<depend package="rosconsole" />
<depend package="nav_msgs" />
+ <depend package="geometry_msgs" />
<depend package="robot_msgs" />
<depend package="tf" />
<depend package="angles" />
Modified: pkg/trunk/stacks/navigation/nav_view/manifest.xml
===================================================================
--- pkg/trunk/stacks/navigation/nav_view/manifest.xml 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/nav_view/manifest.xml 2009-08-07 20:41:56 UTC (rev 21043)
@@ -7,6 +7,7 @@
<depend package="roscpp"/>
<depend package="robot_srvs"/>
<depend package="nav_msgs"/>
+ <depend package="geometry_msgs"/>
<depend package="tf"/>
<depend package="ogre"/>
<depend package="ogre_tools"/>
Modified: pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.cpp
===================================================================
--- pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.cpp 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.cpp 2009-08-07 20:41:56 UTC (rev 21043)
@@ -32,7 +32,7 @@
#include "ogre_tools/wx_ogre_render_window.h"
#include "nav_msgs/GetMap.h"
-#include "nav_msgs/PoseArray.h"
+#include "geometry_msgs/PoseArray.h"
#include <tf/transform_listener.h>
@@ -474,7 +474,7 @@
queueRender();
}
-void NavViewPanel::incomingPoseArray(const nav_msgs::PoseArray::ConstPtr& msg)
+void NavViewPanel::incomingPoseArray(const geometry_msgs::PoseArray::ConstPtr& msg)
{
if ( !cloud_object_ )
{
Modified: pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h
===================================================================
--- pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/navigation/nav_view/src/nav_view/nav_view_panel.h 2009-08-07 20:41:56 UTC (rev 21043)
@@ -32,7 +32,7 @@
#include "nav_view_panel_generated.h"
-#include "nav_msgs/PoseArray.h"
+#include "geometry_msgs/PoseArray.h"
#include "geometry_msgs/PoseStamped.h"
#include "visualization_msgs/Polyline.h"
#include "geometry_msgs/PoseWithCovariance.h"
@@ -89,7 +89,7 @@
@section topic ROS topics
Subscribes to (name/type):
-- @b "particlecloud"nav_msgs/PoseArray : a set particles from a probabilistic localization system. Rendered is a set of small arrows.
+- @b "particlecloud"geometry_msgs/PoseArray : a set particles from a probabilistic localization system. Rendered is a set of small arrows.
- @b "gui_path"/Polyline : a path from a planner. Rendered as a dashed line.
- @b "gui_laser"/Polyline : re-projected laser scan from a planner. Rendered as a set of points.
- @b "local_path"/Polyline : local path from a planner. Rendered as a dashed line.
@@ -164,7 +164,7 @@
void loadMap();
void clearMap();
- void incomingPoseArray(const nav_msgs::PoseArray::ConstPtr& msg);
+ void incomingPoseArray(const geometry_msgs::PoseArray::ConstPtr& msg);
void incomingGuiPath(const visualization_msgs::Polyline::ConstPtr& msg);
void incomingLocalPath(const visualization_msgs::Polyline::ConstPtr& msg);
void incomingRobotFootprint(const visualization_msgs::Polyline::ConstPtr& msg);
Modified: pkg/trunk/stacks/visualization/rviz/manifest.xml
===================================================================
--- pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-08-07 20:41:56 UTC (rev 21043)
@@ -16,6 +16,7 @@
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="sensor_msgs"/>
+ <depend package="geometry_msgs"/>
<depend package="nav_msgs"/>
<depend package="mechanism_msgs" />
<depend package="deprecated_msgs"/>
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp 2009-08-07 20:41:56 UTC (rev 21043)
@@ -168,7 +168,7 @@
topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &ParticleCloud2DDisplay::getTopic, this ),
boost::bind( &ParticleCloud2DDisplay::setTopic, this, _1 ), category_, this );
ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
- topic_prop->setMessageType(nav_msgs::PoseArray::__s_getDataType());
+ topic_prop->setMessageType(geometry_msgs::PoseArray::__s_getDataType());
}
void ParticleCloud2DDisplay::fixedFrameChanged()
@@ -180,7 +180,7 @@
{
}
-void ParticleCloud2DDisplay::processMessage(const nav_msgs::PoseArray::ConstPtr& msg)
+void ParticleCloud2DDisplay::processMessage(const geometry_msgs::PoseArray::ConstPtr& msg)
{
clear();
@@ -275,7 +275,7 @@
causeRender();
}
-void ParticleCloud2DDisplay::incomingMessage(const nav_msgs::PoseArray::ConstPtr& msg)
+void ParticleCloud2DDisplay::incomingMessage(const geometry_msgs::PoseArray::ConstPtr& msg)
{
processMessage(msg);
}
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h 2009-08-07 20:38:02 UTC (rev 21042)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h 2009-08-07 20:41:56 UTC (rev 21043)
@@ -35,7 +35,7 @@
#include "helpers/color.h"
#include "properties/forwards.h"
-#include <nav_msgs/PoseArray.h>
+#include <geometry_msgs/PoseArray.h>
#include <ros/ros.h>
@@ -84,8 +84,8 @@
void subscribe();
void unsubscribe();
void clear();
- void incomingMessage(const nav_msgs::PoseArray::ConstPtr& msg);
- void processMessage(const nav_msgs::PoseArray::ConstPtr& msg);
+ void incomingMessage(const geometry_msgs::PoseArray::ConstPtr& msg);
+ void processMessage(const geometry_msgs::PoseArray::ConstPtr& msg);
// overrides from Display
virtual void onEnable();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jam...@us...> - 2009-08-07 22:14:13
|
Revision: 21065
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21065&view=rev
Author: jamesbowman
Date: 2009-08-07 22:14:04 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
New sensor_msgs::Image message
Modified Paths:
--------------
pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
pkg/trunk/stacks/opencv/image_view/image_view.cpp
pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h
pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp
pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp
Added Paths:
-----------
pkg/trunk/stacks/opencv/opencv_tests/
pkg/trunk/stacks/opencv/opencv_tests/CMakeLists.txt
pkg/trunk/stacks/opencv/opencv_tests/Makefile
pkg/trunk/stacks/opencv/opencv_tests/mainpage.dox
pkg/trunk/stacks/opencv/opencv_tests/manifest.xml
pkg/trunk/stacks/opencv/opencv_tests/nodes/
pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py
pkg/trunk/stacks/opencv/opencv_tests/test/
pkg/trunk/stacks/opencv/opencv_tests/test/enumerants.py
Modified: pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-07 22:11:46 UTC (rev 21064)
+++ pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-07 22:14:04 UTC (rev 21065)
@@ -203,10 +203,9 @@
{
if (img_data->imRawType != COLOR_CODING_NONE)
{
- fillImage(img_, "image_raw",
- img_data->imHeight, img_data->imWidth, 1,
- "mono", "uint8",
- img_data->imRaw );
+ fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ img_data->imHeight, img_data->imWidth, img_data->imWidth,
+ img_data->imRaw);
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
timestamp_diag_.tick(img_.header.stamp);
@@ -215,10 +214,9 @@
if (img_data->imType != COLOR_CODING_NONE)
{
- fillImage(img_, "image",
- img_data->imHeight, img_data->imWidth, 1,
- "mono", "uint8",
- img_data->im );
+ fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ img_data->imHeight, img_data->imWidth, img_data->imWidth,
+ img_data->im);
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
timestamp_diag_.tick(img_.header.stamp);
publish(base_name + std::string("image"), img_);
@@ -226,9 +224,8 @@
if (img_data->imColorType != COLOR_CODING_NONE && img_data->imColorType == COLOR_CODING_RGB8)
{
- fillImage(img_, "image_color",
- img_data->imHeight, img_data->imWidth, 3,
- "rgb", "uint8",
+ fillImage(img_, sensor_msgs::Image::TYPE_8UC3,
+ img_data->imHeight, img_data->imWidth, 3 * img_data->imWidth,
img_data->imColor );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
@@ -238,9 +235,8 @@
if (img_data->imRectType != COLOR_CODING_NONE)
{
- fillImage(img_, "image_rect",
- img_data->imHeight, img_data->imWidth, 1,
- "mono", "uint8",
+ fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ img_data->imHeight, img_data->imWidth, img_data->imWidth,
img_data->imRect );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
timestamp_diag_.tick(img_.header.stamp);
@@ -249,9 +245,8 @@
if (img_data->imRectColorType != COLOR_CODING_NONE && img_data->imRectColorType == COLOR_CODING_RGB8)
{
- fillImage(img_, "image_rect_color",
- img_data->imHeight, img_data->imWidth, 3,
- "rgb", "uint8",
+ fillImage(img_, sensor_msgs::Image::TYPE_8UC3,
+ img_data->imHeight, img_data->imWidth, 3 * img_data->imWidth,
img_data->imRectColor );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
timestamp_diag_.tick(img_.header.stamp);
@@ -260,9 +255,8 @@
if (img_data->imRectColorType != COLOR_CODING_NONE && img_data->imRectColorType == COLOR_CODING_RGBA8)
{
- fillImage(img_, "image_rect_color",
- img_data->imHeight, img_data->imWidth, 4,
- "rgba", "uint8",
+ fillImage(img_,sensor_msgs::Image::TYPE_8UC4,
+ img_data->imHeight, img_data->imWidth, 4 * img_data->imWidth,
img_data->imRectColor );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
timestamp_diag_.tick(img_.header.stamp);
Modified: pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp 2009-08-07 22:11:46 UTC (rev 21064)
+++ pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp 2009-08-07 22:14:04 UTC (rev 21065)
@@ -954,7 +954,7 @@
int publishImage(size_t width, size_t height, uint8_t *frameData, ros::Time t)
{
- fillImage(image_, "image", height, width, 1, "bayer_bggr", "uint8", frameData);
+ fillImage(image_, sensor_msgs::Image::TYPE_8UC1, height, width, width, frameData);
image_.header.stamp = t;
cam_pub_.publish(image_);
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-08-07 22:11:46 UTC (rev 21064)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-08-07 22:14:04 UTC (rev 21065)
@@ -86,8 +86,9 @@
return false;
// Copy into result
- fillImage(res.image, "image", img.Height(), img.Width(), 3,
- "bgr", "uint8", img.ImageData(), 3, img.WidthStep());
+ fillImage(res.image, sensor_msgs::Image::TYPE_8UC3,
+ img.Height(), img.Width(), 3 * img.Width(),
+ img.ImageData());
// Copy cam info we care about
memcpy(&res.cam_info.D[0], D_->data.db, 5*sizeof(double));
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-07 22:11:46 UTC (rev 21064)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-07 22:14:04 UTC (rev 21065)
@@ -543,20 +543,11 @@
static void setBgrLayout(sensor_msgs::Image &image, int width, int height)
{
- image.label = "image";
- image.encoding = "bgr";
- image.depth = "uint8";
- image.uint8_data.layout.dim.resize(3);
- image.uint8_data.layout.dim[0].label = "height";
- image.uint8_data.layout.dim[0].size = height;
- image.uint8_data.layout.dim[0].stride = height * (width * 3);
- image.uint8_data.layout.dim[1].label = "width";
- image.uint8_data.layout.dim[1].size = width;
- image.uint8_data.layout.dim[1].stride = width * 3;
- image.uint8_data.layout.dim[2].label = "channel";
- image.uint8_data.layout.dim[2].size = 3;
- image.uint8_data.layout.dim[2].stride = 3;
- image.uint8_data.data.resize(height * (width * 3));
+ image.type = sensor_msgs::Image::TYPE_8UC3;
+ image.rows = height;
+ image.cols = width;
+ image.step = width * 3;
+ image.data.resize(height * (width * 3));
}
static bool frameToImage(tPvFrame* frame, sensor_msgs::Image &image)
@@ -564,41 +555,42 @@
// NOTE: 16-bit formats and Yuv444 not supported
switch (frame->Format)
{
+
case ePvFmtMono8:
- fillImage(image, "image", frame->Height, frame->Width, 1,
- "mono", "uint8", frame->ImageBuffer);
+ fillImage(image, sensor_msgs::Image::TYPE_8UC1, frame->Height, frame->Width, frame->Width, frame->ImageBuffer);
break;
+
case ePvFmtBayer8:
// Debayer to bgr format so CvBridge can handle it
setBgrLayout(image, frame->Width, frame->Height);
- PvUtilityColorInterpolate(frame, &image.uint8_data.data[2],
- &image.uint8_data.data[1], &image.uint8_data.data[0],
+ PvUtilityColorInterpolate(frame, &image.data[2],
+ &image.data[1], &image.data[0],
2, 0);
break;
- case ePvFmtRgb24:
- fillImage(image, "image", frame->Height, frame->Width, 3,
- "rgb", "uint8", frame->ImageBuffer);
- break;
- case ePvFmtYuv411:
- fillImage(image, "image", frame->Height, frame->Width, 6,
- "yuv411", "uint8", frame->ImageBuffer);
- break;
- case ePvFmtYuv422:
- fillImage(image, "image", frame->Height, frame->Width, 4,
- "yuv422", "uint8", frame->ImageBuffer);
- break;
+
case ePvFmtBgr24:
- fillImage(image, "image", frame->Height, frame->Width, 3,
- "bgr", "uint8", frame->ImageBuffer);
+ fillImage(image, sensor_msgs::Image::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
break;
+
case ePvFmtRgba32:
- fillImage(image, "image", frame->Height, frame->Width, 4,
- "rgba", "uint8", frame->ImageBuffer);
+ fillImage(image, sensor_msgs::Image::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
break;
+
case ePvFmtBgra32:
- fillImage(image, "image", frame->Height, frame->Width, 4,
- "bgra", "uint8", frame->ImageBuffer);
+ fillImage(image, sensor_msgs::Image::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
break;
+
+#if 0 // XXX JCB - these cannot be represented in a CvMat
+ case ePvFmtRgb24:
+ // fillImage(image, sensor_msgs::Image::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
+ break;
+ case ePvFmtYuv411:
+ // fillImage(image, "image", frame->Height, frame->Width, 6, "yuv411", "uint8", frame->ImageBuffer);
+ break;
+ case ePvFmtYuv422:
+ // fillImage(image, "image", frame->Height, frame->Width, 4, "yuv422", "uint8", frame->ImageBuffer);
+ break;
+#endif
default:
ROS_WARN("Received frame with unsupported pixel format %d", frame->Format);
return false;
@@ -611,8 +603,8 @@
sensor_msgs::CameraInfo &cam_info)
{
// Currently assume BGR format so bridge.toIpl() image points to msg data buffer
- if (img.encoding != "bgr") {
- ROS_WARN("Couldn't rectify frame, unsupported encoding %s", img.encoding.c_str());
+ if (img.type != sensor_msgs::Image::TYPE_8UC1) {
+ ROS_WARN("Couldn't rectify frame, unsupported encoding %d", img.type);
return false;
}
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h 2009-08-07 22:11:46 UTC (rev 21064)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h 2009-08-07 22:14:04 UTC (rev 21065)
@@ -40,105 +40,28 @@
namespace sensor_msgs
{
- template <class M>
- void fillImageHelper(M &m,
- uint32_t sz0, uint32_t st0,
- uint32_t sz1, uint32_t st1,
- uint32_t sz2, uint32_t st2,
- void *d)
- {
- m.layout.dim.resize(3);
- m.layout.dim[0].label = "height";
- m.layout.dim[0].size = sz0;
- m.layout.dim[0].stride = st0;
- m.layout.dim[1].label = "width";
- m.layout.dim[1].size = sz1;
- m.layout.dim[1].stride = st1;
- m.layout.dim[2].label = "channel";
- m.layout.dim[2].size = sz2;
- m.layout.dim[2].stride = st2;
- m.data.resize(st0);
- memcpy((char*)(&m.data[0]), (char*)(d), st0*sizeof(m.data[0]));
- }
-
- template <class M>
- void clearImageHelper(M &m)
- {
- m.layout.dim.resize(0);
- m.data.resize(0);
- }
-
bool fillImage(Image& image,
- std::string label_arg,
- uint32_t height_arg, uint32_t width_arg, uint32_t channel_arg,
- std::string encoding_arg, std::string depth_arg,
- void* data_arg,
- uint32_t channel_step = 0, uint32_t width_step = 0, uint32_t height_step = 0)
+ uint32_t type_arg,
+ uint32_t rows_arg,
+ uint32_t cols_arg,
+ uint32_t step_arg,
+ void* data_arg)
{
- image.label = label_arg;
- image.encoding = encoding_arg;
- image.depth = depth_arg;
-
- if (channel_step == 0)
- channel_step = channel_arg;
-
- if (width_step == 0)
- width_step = width_arg * channel_step;
-
- if (height_step == 0)
- height_step = height_arg * width_step;
-
- if (image.depth == "uint8")
- fillImageHelper(image.uint8_data,
- height_arg, height_step,
- width_arg, width_step,
- channel_arg, channel_step,
- data_arg);
-
- else if (image.depth == "uint16")
- fillImageHelper(image.uint16_data,
- height_arg, height_step,
- width_arg, width_step,
- channel_arg, channel_step,
- data_arg);
+ image.type = type_arg;
+ image.rows = rows_arg;
+ image.cols = cols_arg;
+ image.step = step_arg;
+ size_t st0 = (step_arg * rows_arg);
+ image.data.resize(st0);
+ memcpy((char*)(&image.data[0]), (char*)(data_arg), st0);
- else if (image.depth == "int16")
- fillImageHelper(image.int16_data,
- height_arg, height_step,
- width_arg, width_step,
- channel_arg, channel_step,
- data_arg);
- else
- {
- return false;
- }
-
+ image.is_bigendian = 0;
return true;
}
void clearImage(Image& image)
{
- image.label = "none";
- image.encoding = "other";
- if (image.depth == "uint8")
- clearImageHelper(image.uint8_data);
- else if (image.depth == "uint16")
- clearImageHelper(image.uint16_data);
- else if (image.depth == "int16")
- clearImageHelper(image.int16_data);
- else if (image.depth == "uint32")
- clearImageHelper(image.uint32_data);
- else if (image.depth == "int32")
- clearImageHelper(image.int32_data);
- else if (image.depth == "uint64")
- clearImageHelper(image.uint64_data);
- else if (image.depth == "int64")
- clearImageHelper(image.int64_data);
- else if (image.depth == "float32")
- clearImageHelper(image.float32_data);
- else if (image.depth == "float64")
- clearImageHelper(image.float64_data);
- image.depth = "none";
+ image.data.resize(0);
}
}
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-07 22:11:46 UTC (rev 21064)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-07 22:14:04 UTC (rev 21065)
@@ -1,38 +1,37 @@
Header header # Header
-string label # Label for the image
-string encoding # Specifies the color encoding of the data
- # Acceptable values are:
- # 1 channel types:
- # mono, bayer_rggb, bayer_gbrg, bayer_grbg, bayer_bggr
- # 3 channel types:
- # rgb, bgr
- # 4 channel types:
- # rgba, bgra, yuv422
- # 6 channel types:
- # yuv411
- # N channel types:
- # other
-string depth # Specifies the depth of the data:
- # Acceptable values:
- # uint8, int8, uint16, int16, uint32, int32, uint64, int64, float32, float64
-# Based on depth ONE of the following MultiArrays may contain data.
-# The multi-array MUST have 3 dimensions, labeled as "height",
-# "width", and "channel", though depending on usage the ordering of
-# the dimensions may very. Note that IPL Image convention will order
-# these as: height, width, channel, which is the preferred ordering
-# unless performance dictates otherwise.
-#
-# Height, width, and number of channels are specified in the dimension
-# sizes within the appropriate MultiArray
+int32 TYPE_8UC1=0
+int32 TYPE_8UC2=8
+int32 TYPE_8UC3=16
+int32 TYPE_8UC4=24
+int32 TYPE_8SC1=1
+int32 TYPE_8SC2=9
+int32 TYPE_8SC3=17
+int32 TYPE_8SC4=25
+int32 TYPE_16UC1=2
+int32 TYPE_16UC2=10
+int32 TYPE_16UC3=18
+int32 TYPE_16UC4=26
+int32 TYPE_16SC1=3
+int32 TYPE_16SC2=11
+int32 TYPE_16SC3=19
+int32 TYPE_16SC4=27
+int32 TYPE_32SC1=4
+int32 TYPE_32SC2=12
+int32 TYPE_32SC3=20
+int32 TYPE_32SC4=28
+int32 TYPE_32FC1=5
+int32 TYPE_32FC2=13
+int32 TYPE_32FC3=21
+int32 TYPE_32FC4=29
+int32 TYPE_64FC1=6
+int32 TYPE_64FC2=14
+int32 TYPE_64FC3=22
+int32 TYPE_64FC4=30
-std_msgs/UInt8MultiArray uint8_data
-std_msgs/Int8MultiArray int8_data
-std_msgs/UInt16MultiArray uint16_data
-std_msgs/Int16MultiArray int16_data
-std_msgs/UInt32MultiArray uint32_data
-std_msgs/Int32MultiArray int32_data
-std_msgs/UInt64MultiArray uint64_data
-std_msgs/Int64MultiArray int64_data
-std_msgs/Float32MultiArray float32_data
-std_msgs/Float64MultiArray float64_data
+int32 type # Type of elements, and channels. Encoded as in OpenCV's TYPE_8UC1 .. TYPE_64FC4.
+int32 step # Full row length in bytes
+uint8[] data # actual matrix data, size is (step * rows)
+int32 rows # Number of rows
+int32 cols # Number of columns
+uint8 is_bigendian # is this data bigendian
Modified: pkg/trunk/stacks/opencv/image_view/image_view.cpp
===================================================================
--- pkg/trunk/stacks/opencv/image_view/image_view.cpp 2009-08-07 22:11:46 UTC (rev 21064)
+++ pkg/trunk/stacks/opencv/image_view/image_view.cpp 2009-08-07 22:14:04 UTC (rev 21065)
@@ -98,7 +98,7 @@
if (img_bridge_.fromImage(*msg, "bgr"))
cvShowImage(window_name_.c_str(), img_bridge_.toIpl());
else
- ROS_ERROR("Unable to convert from %s to bgr", msg->encoding.c_str());
+ ROS_ERROR("Unable to convert from %d to bgr", msg->type);
}
static void mouse_cb(int event, int x, int y, int flags, void* param)
Modified: pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h
===================================================================
--- pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h 2009-08-07 22:11:46 UTC (rev 21064)
+++ pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h 2009-08-07 22:14:04 UTC (rev 21065)
@@ -44,6 +44,8 @@
class CvBridge
{
+ public:
+
IplImage* img_;
IplImage* rosimg_;
IplImage* cvtimg_;
@@ -68,8 +70,6 @@
return false;
}
- public:
-
CvBridge() : img_(0), rosimg_(0), cvtimg_(0)
{
rosimg_ = cvCreateImageHeader( cvSize(0,0), IPL_DEPTH_8U, 1 );
@@ -88,68 +88,41 @@
}
}
-
inline IplImage* toIpl()
{
return img_;
}
+ /**
+ * Converts a ROS Image into an OpenCV IPL Image.
+ * \param rosimg The ROS Image message
+ */
bool fromImage(const Image& rosimg, std::string encoding = "")
{
- unsigned int depth;
- if (rosimg.depth == "uint8")
- {
- depth = IPL_DEPTH_8U;
- cvInitImageHeader(rosimg_, cvSize(rosimg.uint8_data.layout.dim[1].size, rosimg.uint8_data.layout.dim[0].size),
- IPL_DEPTH_8U, rosimg.uint8_data.layout.dim[2].size);
- cvSetData(rosimg_, const_cast<uint8_t*>(&(rosimg.uint8_data.data[0])), rosimg.uint8_data.layout.dim[1].stride);
+ CvMat cvmHeader;
+
+ cvInitMatHeader(&cvmHeader, rosimg.rows, rosimg.cols, rosimg.type, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
+ cvGetImage(&cvmHeader, rosimg_);
+
+ // cvSetData(rosimg_, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
+
+ if (encoding == "") {
img_ = rosimg_;
- } else if (rosimg.depth == "uint16") {
- depth = IPL_DEPTH_16U;
- cvInitImageHeader(rosimg_, cvSize(rosimg.uint16_data.layout.dim[1].size, rosimg.uint16_data.layout.dim[0].size),
- IPL_DEPTH_16U, rosimg.uint16_data.layout.dim[2].size);
- cvSetData(rosimg_, const_cast<uint16_t*>(&(rosimg.uint16_data.data[0])), rosimg.uint16_data.layout.dim[1].stride*sizeof(uint16_t));
- img_ = rosimg_;
} else {
- return false;
- }
-
- if (encoding != "" && (encoding != rosimg.encoding))
- {
- if (encoding == "bgr" && rosimg.encoding == "rgb")
+ if ((encoding == "bgr" || encoding == "rgb") && rosimg.type == CV_8UC1)
{
- reallocIfNeeded(&cvtimg_, depth, 3);
- cvCvtColor(rosimg_, cvtimg_, CV_RGB2BGR);
- img_ = cvtimg_;
- }
- else if (encoding == "rgb" && rosimg.encoding == "bgr")
- {
- reallocIfNeeded(&cvtimg_, depth, 3);
- cvCvtColor(rosimg_, cvtimg_, CV_BGR2RGB);
- img_ = cvtimg_;
- }
- else if (encoding == "bgr" && rosimg.encoding == "mono" )
- {
- reallocIfNeeded(&cvtimg_, depth, 3);
+ reallocIfNeeded(&cvtimg_, IPL_DEPTH_8U, 3);
cvCvtColor(rosimg_, cvtimg_, CV_GRAY2BGR);
img_ = cvtimg_;
}
- else if (encoding == "mono" && rosimg.encoding == "rgb" )
+ else if (encoding == "mono" && rosimg.type == CV_8UC3)
{
- reallocIfNeeded(&cvtimg_, depth, 1);
+ reallocIfNeeded(&cvtimg_, IPL_DEPTH_8U, 1);
cvCvtColor(rosimg_, cvtimg_, CV_RGB2GRAY);
img_ = cvtimg_;
+ } else {
+ img_ = rosimg_;
}
- else if (encoding == "mono" && rosimg.encoding == "bgr" )
- {
- reallocIfNeeded(&cvtimg_, depth, 1);
- cvCvtColor(rosimg_, cvtimg_, CV_BGR2GRAY);
- img_ = cvtimg_;
- }
- else
- {
- return false;
- }
}
return true;
}
@@ -164,59 +137,23 @@
}
/**
- * Converts an openCV IPL Image into a ROS Image that can be sent 'over the wire'.
- * Note that this hasn't been rigorously tested
+ * Converts an OpenCV IPL Image into a ROS Image that can be sent 'over the wire'.
* \param source The original Ipl Image that we want to copy from
* \param dest The ROS Image message that we want to copy to
*/
static bool fromIpltoRosImage(const IplImage* source, sensor_msgs::Image& dest)
{
- switch(source->nChannels)
- {
- case 1: dest.encoding = "mono"; break;
- case 3: dest.encoding = "rgb"; break;
- case 4: dest.encoding = "rgba"; break;
- default:
- ROS_ERROR("unknown image format\n");
- return false;
- }
- switch(source->depth)
- {
- case IPL_DEPTH_8U : dest.depth = "uint8"; fillImageHelperCV(dest.uint8_data, source); break;
- case IPL_DEPTH_8S : dest.depth = "int8"; fillImageHelperCV(dest.int8_data, source); break;
- case IPL_DEPTH_16U: dest.depth = "uint16"; fillImageHelperCV(dest.uint16_data, source); break;
- case IPL_DEPTH_16S: dest.depth = "int16"; fillImageHelperCV(dest.int16_data, source); break;
- case IPL_DEPTH_32S: dest.depth = "int32"; fillImageHelperCV(dest.int32_data, source); break;
- case IPL_DEPTH_32F: dest.depth = "float32"; fillImageHelperCV(dest.float32_data, source); break;
- case IPL_DEPTH_64F: dest.depth = "float64"; fillImageHelperCV(dest.float64_data, source); break;
- default:
- ROS_ERROR("unsupported depth %d\n", source->depth);
- return false;
- }
+ CvMat header, *cvm;
+
+ cvm = cvGetMat(source, &header);
+ dest.type = cvm->type & (CV_MAT_TYPE_MASK | CV_MAT_DEPTH_MASK);
+ dest.cols = cvm->cols;
+ dest.rows = cvm->rows;
+ dest.step = cvm->step;
+ dest.data.resize(cvm->step * cvm->rows);
+ memcpy((char*)(&dest.data[0]), source->imageData, cvm->step * cvm->rows);
return true;
}
-
- private:
- /**
- * Helper method used by fromIplToRosImage in order to populate the images
- */
- template <typename T>
- static void fillImageHelperCV(T& m, const IplImage* frame)
- {
- m.layout.dim.resize(3);
- m.layout.dim.resize(3);
- m.layout.dim[0].label = "height";
- m.layout.dim[0].size = frame->height;
- m.layout.dim[0].stride = frame->widthStep*frame->height/sizeof(m.data[0]);
- m.layout.dim[1].label = "width";
- m.layout.dim[1].size = frame->width;
- m.layout.dim[1].stride = frame->widthStep/sizeof(m.data[0]);
- m.layout.dim[2].label = "channel";
- m.layout.dim[2].size = frame->nChannels;
- m.layout.dim[2].stride = frame->nChannels*sizeof(m.data[0]);
- m.data.resize(frame->widthStep*frame->height/sizeof(m.data[0]));
- memcpy((char*)(&m.data[0]), frame->imageData, m.data.size()*sizeof(m.data[0]));
- }
};
}
Added: pkg/trunk/stacks/opencv/opencv_tests/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/CMakeLists.txt (rev 0)
+++ pkg/trunk/stacks/opencv/opencv_tests/CMakeLists.txt 2009-08-07 22:14:04 UTC (rev 21065)
@@ -0,0 +1,34 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+# Set the build type. Options are:
+# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage
+# Debug : w/ debug symbols, w/o optimization
+# Release : w/o debug symbols, w/ optimization
+# RelWithDebInfo : w/ debug symbols, w/ optimization
+# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries
+#set(ROS_BUILD_TYPE RelWithDebInfo)
+
+rospack(opencv_tests)
+
+#set the default path for built executables to the "bin" directory
+#set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set the default path for built libraries to the "lib" directory
+set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+
+#uncomment if you have defined messages
+#genmsg()
+#uncomment if you have defined services
+#gensrv()
+
+#common commands for building c++ executables and libraries
+#rospack_add_library(${PROJECT_NAME} src/example.cpp)
+#target_link_libraries(${PROJECT_NAME} another_library)
+#rospack_add_boost_directories()
+#rospack_link_boost(${PROJECT_NAME} thread)
+#rospack_add_executable(example examples/example.cpp)
+#target_link_libraries(example ${PROJECT_NAME})
+
+rospack_add_gtest(test/utest test/utest.cpp)
+rospack_add_pyunit(test/enumerants.py)
+
Added: pkg/trunk/stacks/opencv/opencv_tests/Makefile
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/Makefile (rev 0)
+++ pkg/trunk/stacks/opencv/opencv_tests/Makefile 2009-08-07 22:14:04 UTC (rev 21065)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
Added: pkg/trunk/stacks/opencv/opencv_tests/mainpage.dox
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/mainpage.dox (rev 0)
+++ pkg/trunk/stacks/opencv/opencv_tests/mainpage.dox 2009-08-07 22:14:04 UTC (rev 21065)
@@ -0,0 +1,119 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b opencv_tests is ...
+
+<!--
+In addition to providing an overview of your package,
+this is the section where the specification and design/architecture
+should be detailed. While the original specification may be done on the
+wiki, it should be transferred here once your package starts to take shape.
+You can then link to this documentation page from the Wiki.
+-->
+
+
+\section codeapi Code API
+
+<!--
+Provide links to specific auto-generated API documentation within your
+package that is of particular interest to a reader. Doxygen will
+document pretty much every part of your code, so do your best here to
+point the reader to the actual API.
+
+If your codebase is fairly large or has different sets of APIs, you
+should use the doxygen 'group' tag to keep these APIs together. For
+example, the roscpp documentation has 'libros' group.
+-->
+
+\section rosapi ROS API
+
+<!--
+Names are very important in ROS because they can be remapped on the
+command-line, so it is VERY IMPORTANT THAT YOU LIST NAMES AS THEY
+APPEAR IN THE CODE. You should list names of every topic, service and
+parameter used in your code. There is a template below that you can
+use to document each node separately.
+
+List of nodes:
+- \b node_name1
+- \b node_name2
+-->
+
+<!-- START: copy from here to 'END' for each node
+
+<hr>
+
+\subsection node_name node_name
+
+node_name does (provide a basic description of your node)
+
+\subsubsection Usage
+\verbatim
+$ node_type1 [standard ROS args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ node_type1
+\endverbatim
+
+
+\subsubsection topics ROS topics
+
+Subscribes to:
+- \b "in": [std_msgs/FooType] description of in
+
+Publishes to:
+- \b "out": [std_msgs/FooType] description of out
+
+...
[truncated message content] |
|
From: <jfa...@us...> - 2009-08-08 03:14:02
|
Revision: 21120
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21120&view=rev
Author: jfaustwg
Date: 2009-08-08 03:13:52 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
QuaternionStamped::quaternion -> QuaternionStamped::data (#2278)
Modified Paths:
--------------
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg
pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
pkg/trunk/stacks/geometry/tf/src/tf/listener.py
pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
Modified: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg 2009-08-08 03:11:05 UTC (rev 21119)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg 2009-08-08 03:13:52 UTC (rev 21120)
@@ -1,2 +1,2 @@
Header header
-Quaternion quaternion
+Quaternion data
Modified: pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
===================================================================
--- pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-08 03:11:05 UTC (rev 21119)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-08 03:13:52 UTC (rev 21120)
@@ -135,10 +135,10 @@
/** \brief convert QuaternionStamped msg to Stamped<Quaternion> */
static inline void quaternionStampedMsgToTF(const geometry_msgs::QuaternionStamped & msg, Stamped<Quaternion>& bt)
-{quaternionMsgToTF(msg.quaternion, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
+{quaternionMsgToTF(msg.data, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Quaternion> to QuaternionStamped msg*/
static inline void quaternionStampedTFToMsg(const Stamped<Quaternion>& bt, geometry_msgs::QuaternionStamped & msg)
-{quaternionTFToMsg(bt, msg.quaternion); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+{quaternionTFToMsg(bt, msg.data); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Vector3 msg to Vector3 */
static inline void vector3MsgToTF(const geometry_msgs::Vector3& msg_v, Vector3& bt_v) {bt_v = Vector3(msg_v.x, msg_v.y, msg_v.z);};
Modified: pkg/trunk/stacks/geometry/tf/src/tf/listener.py
===================================================================
--- pkg/trunk/stacks/geometry/tf/src/tf/listener.py 2009-08-08 03:11:05 UTC (rev 21119)
+++ pkg/trunk/stacks/geometry/tf/src/tf/listener.py 2009-08-08 03:13:52 UTC (rev 21120)
@@ -104,7 +104,7 @@
r = geometry_msgs.msg.QuaternionStamped()
r.header.stamp = ps.header.stamp
r.header.frame_id = target_frame
- r.quaternion = geometry_msgs.msg.Quaternion(*quat)
+ r.data = geometry_msgs.msg.Quaternion(*quat)
return r
## Transforms a robot_msgs PoseStamped message to frame target_frame, returns the resulting PoseStamped.
Modified: pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
===================================================================
--- pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 03:11:05 UTC (rev 21119)
+++ pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 03:13:52 UTC (rev 21120)
@@ -59,18 +59,18 @@
## Setup the quaternion tests
self.tfquaternion_stamped = tf.QuaternionStamped()
- self.tfquaternion_stamped.quaternion.x = 0
- self.tfquaternion_stamped.quaternion.y = 0
- self.tfquaternion_stamped.quaternion.z = 0
- self.tfquaternion_stamped.quaternion.w = 1
+ self.tfquaternion_stamped.data.x = 0
+ self.tfquaternion_stamped.data.y = 0
+ self.tfquaternion_stamped.data.z = 0
+ self.tfquaternion_stamped.data.w = 1
self.tfquaternion_stamped.frame_id = "frame1"
self.tfquaternion_stamped.stamp = roslib.rostime.Time(10, 0)
self.msgquaternion_stamped = robot_msgs.msg.QuaternionStamped()
- self.msgquaternion_stamped.quaternion.x = 0
- self.msgquaternion_stamped.quaternion.y = 0
- self.msgquaternion_stamped.quaternion.z = 0
- self.msgquaternion_stamped.quaternion.w = 1
+ self.msgquaternion_stamped.data.x = 0
+ self.msgquaternion_stamped.data.y = 0
+ self.msgquaternion_stamped.data.z = 0
+ self.msgquaternion_stamped.data.w = 1
self.msgquaternion_stamped.header.frame_id = "frame1"
self.msgquaternion_stamped.header.stamp = roslib.rostime.Time(10,0)
@@ -159,9 +159,9 @@
self.assertEquals(tf.quaternion_stamped_msg_to_bt(self.msgquaternion_stamped), tf.quaternion_stamped_msg_to_bt(self.msgquaternion_stamped), "quaternion bt test correctness after conversion")
def test_to_msg_quaternion(self):
- self.assertEquals(tf.quaternion_bt_to_msg(self.tfquaternion_stamped.quaternion), self.msgquaternion_stamped.quaternion, "quaternion tf to msg incorrect")
+ self.assertEquals(tf.quaternion_bt_to_msg(self.tfquaternion_stamped.data), self.msgquaternion_stamped.data, "quaternion tf to msg incorrect")
def test_to_tf_quaternion(self):
- self.assertEquals(tf.quaternion_msg_to_bt(self.msgquaternion_stamped.quaternion), self.tfquaternion_stamped.quaternion, "quaternion stamped msg to tf incorrect")
+ self.assertEquals(tf.quaternion_msg_to_bt(self.msgquaternion_stamped.data), self.tfquaternion_stamped.data, "quaternion stamped msg to tf incorrect")
def test_stamped_to_msg_quaternion(self):
self.assertEquals(tf.quaternion_stamped_bt_to_msg(self.tfquaternion_stamped), self.msgquaternion_stamped, "quaternion stamped tf to msg incorrect")
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-08-08 04:39:30
|
Revision: 21132
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21132&view=rev
Author: tfoote
Date: 2009-08-08 04:39:22 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
fixing through diagnostic_updater
Modified Paths:
--------------
pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/KeyValue.msg
pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h
pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/update_functions.h
pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp
pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp
Modified: pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/KeyValue.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/KeyValue.msg 2009-08-08 04:19:29 UTC (rev 21131)
+++ pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/KeyValue.msg 2009-08-08 04:39:22 UTC (rev 21132)
@@ -1,2 +1,2 @@
-float32 value # a value to track over time
+string value # a value to track over time
string label # what to label this value when viewing
Modified: pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h 2009-08-08 04:19:29 UTC (rev 21131)
+++ pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h 2009-08-08 04:39:22 UTC (rev 21132)
@@ -114,22 +114,22 @@
void addsf(const std::string &key, const char *format, ...); // In practice format will always be a char *
- void addv(const std::string &key, double v)
+ /* void addv(const std::string &key, double v)
{
diagnostic_msgs::KeyValue dv;
dv.label = key;
dv.value = v;
values.push_back(dv);
- }
+ }*/
};
template<>
void DiagnosticStatusWrapper::adds<std::string>(const std::string &key, const std::string &s)
{
- diagnostic_msgs::DiagnosticString ds;
+ diagnostic_msgs::KeyValue ds;
ds.label = key;
ds.value = s;
- strings.push_back(ds);
+ values.push_back(ds);
}
// Need to place addsf after DiagnosticStatusWrapper::adds<std::string> or
Modified: pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/update_functions.h
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/update_functions.h 2009-08-08 04:19:29 UTC (rev 21131)
+++ pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/update_functions.h 2009-08-08 04:39:22 UTC (rev 21132)
@@ -126,17 +126,17 @@
summary.summary(0, "Desired frequency met");
}
- details.addv("Events in window", events);
- details.addv("Events since startup", count_);
- details.addv("Duration of window (s)", window);
- details.addv("Actual frequency (Hz)", freq);
+ details.addsf("Events in window", "%f", events);
+ details.addsf("Events since startup", "%f", count_);
+ details.addsf("Duration of window (s)", "%f", window);
+ details.addsf("Actual frequency (Hz)", "%f",freq);
if (*params_.min_freq_ == *params_.max_freq_)
- details.addv("Target frequency (Hz)", *params_.min_freq_);
+ details.addsf("Target frequency (Hz)", "%f",*params_.min_freq_);
if (*params_.min_freq_ > 0)
- details.addv("Minimum acceptable frequency (Hz)",
+ details.addsf("Minimum acceptable frequency (Hz)", "%f",
*params_.min_freq_ * (1 - params_.tolerance_));
if (finite(*params_.max_freq_))
- details.addv("Maximum acceptable frequency (Hz)",
+ details.addsf("Maximum acceptable frequency (Hz)", "%f",
*params_.max_freq_ * (1 + params_.tolerance_));
}
};
@@ -240,10 +240,10 @@
}
}
- details.addv("Earliest timestamp delay:", min_delta_);
- details.addv("Latest timestamp delay:", max_delta_);
- details.addv("Earliest acceptable timestamp delay:", params_.min_acceptable_);
- details.addv("Latest acceptable timestamp delay:", params_.max_acceptable_);
+ details.addsf("Earliest timestamp delay:", "%f", min_delta_);
+ details.addsf("Latest timestamp delay:", "%f", max_delta_);
+ details.addsf("Earliest acceptable timestamp delay:", "%f", params_.min_acceptable_);
+ details.addsf("Latest acceptable timestamp delay:", "%f", params_.max_acceptable_);
details.adds("Late diagnostic update count:", late_count_);
details.adds("Early diagnostic update count:", early_count_);
details.adds("Zero seen diagnostic update count:", zero_count_);
Modified: pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp 2009-08-08 04:19:29 UTC (rev 21131)
+++ pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp 2009-08-08 04:39:22 UTC (rev 21132)
@@ -62,7 +62,7 @@
void run(DiagnosticStatusWrapper &s)
{
s.summary(0, "Test is running");
- s.addv("Value", 5);
+ s.addsf("Value", "%f", 5);
s.adds("String", "Toto");
s.adds("Floating", 5.55);
s.adds("Integer", 5);
@@ -96,16 +96,16 @@
EXPECT_STREQ(message, stat.message.c_str()) << "DiagnosticStatusWrapper::summary failed to set message";
EXPECT_EQ(level, stat.level) << "DiagnosticStatusWrapper::summary failed to set level";
- stat.addv("toto", 5);
+ stat.addsf("toto", "%.1f", 5.0);
stat.adds("baba", 5);
stat.addsf("foo", "%05i", 27);
- EXPECT_EQ(5.0, stat.values[0].value) << "Bad value, adding a value with addv";
- EXPECT_STREQ("5", stat.strings[0].value.c_str()) << "Bad value, adding a string with adds";
- EXPECT_STREQ("00027", stat.strings[1].value.c_str()) << "Bad value, adding a string with addsf";
+ EXPECT_STREQ("5.0", stat.values[0].value.c_str()) << "Bad value, adding a value with addsf";
+ EXPECT_STREQ("5", stat.values[1].value.c_str()) << "Bad value, adding a string with adds";
+ EXPECT_STREQ("00027", stat.values[2].value.c_str()) << "Bad value, adding a string with addsf";
EXPECT_STREQ("toto", stat.values[0].label.c_str()) << "Bad label, adding a value with addv";
- EXPECT_STREQ("baba", stat.strings[0].label.c_str()) << "Bad label, adding a string with adds";
- EXPECT_STREQ("foo", stat.strings[1].label.c_str()) << "Bad label, adding a string with addsf";
+ EXPECT_STREQ("baba", stat.values[1].label.c_str()) << "Bad label, adding a string with adds";
+ EXPECT_STREQ("foo", stat.values[2].label.c_str()) << "Bad label, adding a string with addsf";
}
TEST(DiagnosticUpdater, testFrequencyStatus)
Modified: pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp 2009-08-08 04:19:29 UTC (rev 21131)
+++ pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp 2009-08-08 04:39:22 UTC (rev 21132)
@@ -110,12 +110,12 @@
#define ADD_STRING_FMT(lab, fmt, ...) \
- s.label = (lab); \
+ v.label = (lab); \
{ char buf[1024]; \
snprintf(buf, sizeof(buf), fmt, ##__VA_ARGS__); \
- s.value = buf; \
+ v.value = buf; \
} \
- strings.push_back(s)
+ values.push_back(v)
// Must be realtime safe.
@@ -452,10 +452,8 @@
std::vector<diagnostic_msgs::DiagnosticStatus> statuses;
std::vector<diagnostic_msgs::KeyValue> values;
- std::vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
diagnostic_msgs::KeyValue v;
- diagnostic_msgs::DiagnosticString s;
status.name = "Mechanism Control";
status.level = 0;
@@ -505,7 +503,6 @@
ADD_STRING_FMT("Active controllers", "%d", active);
status.set_values_vec(values);
- status.set_strings_vec(strings);
statuses.push_back(status);
pub_diagnostics_.msg_.set_status_vec(statuses);
pub_diagnostics_.unlockAndPublish();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jfa...@us...> - 2009-08-08 05:28:37
|
Revision: 21142
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21142&view=rev
Author: jfaustwg
Date: 2009-08-08 05:28:29 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
reverse QuaternionStamped::quaternion -> QuaternionStamped::data change
Modified Paths:
--------------
pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg
pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
pkg/trunk/stacks/geometry/tf/src/tf/listener.py
pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py
Modified: pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg 2009-08-08 05:22:40 UTC (rev 21141)
+++ pkg/trunk/stacks/common_msgs/geometry_msgs/msg/QuaternionStamped.msg 2009-08-08 05:28:29 UTC (rev 21142)
@@ -1,2 +1,2 @@
Header header
-Quaternion data
+Quaternion quaternion
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:22:40 UTC (rev 21141)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-08-08 05:28:29 UTC (rev 21142)
@@ -135,10 +135,10 @@
/** \brief convert QuaternionStamped msg to Stamped<Quaternion> */
static inline void quaternionStampedMsgToTF(const geometry_msgs::QuaternionStamped & msg, Stamped<Quaternion>& bt)
-{quaternionMsgToTF(msg.data, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
+{quaternionMsgToTF(msg.quaternion, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Quaternion> to QuaternionStamped msg*/
static inline void quaternionStampedTFToMsg(const Stamped<Quaternion>& bt, geometry_msgs::QuaternionStamped & msg)
-{quaternionTFToMsg(bt, msg.data); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+{quaternionTFToMsg(bt, msg.quaternion); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Vector3 msg to Vector3 */
static inline void vector3MsgToTF(const geometry_msgs::Vector3& msg_v, Vector3& bt_v) {bt_v = Vector3(msg_v.x, msg_v.y, msg_v.z);};
Modified: pkg/trunk/stacks/geometry/tf/src/tf/listener.py
===================================================================
--- pkg/trunk/stacks/geometry/tf/src/tf/listener.py 2009-08-08 05:22:40 UTC (rev 21141)
+++ pkg/trunk/stacks/geometry/tf/src/tf/listener.py 2009-08-08 05:28:29 UTC (rev 21142)
@@ -104,7 +104,7 @@
r = geometry_msgs.msg.QuaternionStamped()
r.header.stamp = ps.header.stamp
r.header.frame_id = target_frame
- r.data = geometry_msgs.msg.Quaternion(*quat)
+ r.quaternion = geometry_msgs.msg.Quaternion(*quat)
return r
## Transforms a robot_msgs PoseStamped message to frame target_frame, returns the resulting PoseStamped.
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:22:40 UTC (rev 21141)
+++ pkg/trunk/stacks/geometry/tf/test/test_datatype_conversion.py 2009-08-08 05:28:29 UTC (rev 21142)
@@ -59,18 +59,18 @@
## Setup the quaternion tests
self.tfquaternion_stamped = tf.QuaternionStamped()
- self.tfquaternion_stamped.data.x = 0
- self.tfquaternion_stamped.data.y = 0
- self.tfquaternion_stamped.data.z = 0
- self.tfquaternion_stamped.data.w = 1
+ self.tfquaternion_stamped.quaternion.x = 0
+ self.tfquaternion_stamped.quaternion.y = 0
+ self.tfquaternion_stamped.quaternion.z = 0
+ self.tfquaternion_stamped.quaternion.w = 1
self.tfquaternion_stamped.frame_id = "frame1"
self.tfquaternion_stamped.stamp = roslib.rostime.Time(10, 0)
self.msgquaternion_stamped = robot_msgs.msg.QuaternionStamped()
- self.msgquaternion_stamped.data.x = 0
- self.msgquaternion_stamped.data.y = 0
- self.msgquaternion_stamped.data.z = 0
- self.msgquaternion_stamped.data.w = 1
+ self.msgquaternion_stamped.quaternion.x = 0
+ self.msgquaternion_stamped.quaternion.y = 0
+ self.msgquaternion_stamped.quaternion.z = 0
+ self.msgquaternion_stamped.quaternion.w = 1
self.msgquaternion_stamped.header.frame_id = "frame1"
self.msgquaternion_stamped.header.stamp = roslib.rostime.Time(10,0)
@@ -159,9 +159,9 @@
self.assertEquals(tf.quaternion_stamped_msg_to_bt(self.msgquaternion_stamped), tf.quaternion_stamped_msg_to_bt(self.msgquaternion_stamped), "quaternion bt test correctness after conversion")
def test_to_msg_quaternion(self):
- self.assertEquals(tf.quaternion_bt_to_msg(self.tfquaternion_stamped.data), self.msgquaternion_stamped.data, "quaternion tf to msg incorrect")
+ self.assertEquals(tf.quaternion_bt_to_msg(self.tfquaternion_stamped.quaternion), self.msgquaternion_stamped.quaternion, "quaternion tf to msg incorrect")
def test_to_tf_quaternion(self):
- self.assertEquals(tf.quaternion_msg_to_bt(self.msgquaternion_stamped.data), self.tfquaternion_stamped.data, "quaternion stamped msg to tf incorrect")
+ self.assertEquals(tf.quaternion_msg_to_bt(self.msgquaternion_stamped.quaternion), self.tfquaternion_stamped.quaternion, "quaternion stamped msg to tf incorrect")
def test_stamped_to_msg_quaternion(self):
self.assertEquals(tf.quaternion_stamped_bt_to_msg(self.tfquaternion_stamped), self.msgquaternion_stamped, "quaternion stamped tf to msg incorrect")
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jam...@us...> - 2009-08-08 06:38:18
|
Revision: 21165
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21165&view=rev
Author: jamesbowman
Date: 2009-08-08 06:38:06 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
Rename rows,cols to height,width in Image message
Modified Paths:
--------------
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h
pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py
pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-08 06:38:06 UTC (rev 21165)
@@ -544,8 +544,8 @@
static void setBgrLayout(sensor_msgs::Image &image, int width, int height)
{
image.type = sensor_msgs::Image::TYPE_8UC3;
- image.rows = height;
- image.cols = width;
+ image.height = height;
+ image.width = width;
image.step = width * 3;
image.data.resize(height * (width * 3));
}
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/FillImage.h 2009-08-08 06:38:06 UTC (rev 21165)
@@ -48,8 +48,8 @@
void* data_arg)
{
image.type = type_arg;
- image.rows = rows_arg;
- image.cols = cols_arg;
+ image.height = rows_arg;
+ image.width = cols_arg;
image.step = step_arg;
size_t st0 = (step_arg * rows_arg);
image.data.resize(st0);
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-08 06:38:06 UTC (rev 21165)
@@ -1,37 +1,41 @@
Header header # Header
-int32 TYPE_8UC1=0
-int32 TYPE_8UC2=8
-int32 TYPE_8UC3=16
-int32 TYPE_8UC4=24
-int32 TYPE_8SC1=1
-int32 TYPE_8SC2=9
-int32 TYPE_8SC3=17
-int32 TYPE_8SC4=25
-int32 TYPE_16UC1=2
-int32 TYPE_16UC2=10
-int32 TYPE_16UC3=18
-int32 TYPE_16UC4=26
-int32 TYPE_16SC1=3
-int32 TYPE_16SC2=11
-int32 TYPE_16SC3=19
-int32 TYPE_16SC4=27
-int32 TYPE_32SC1=4
-int32 TYPE_32SC2=12
-int32 TYPE_32SC3=20
-int32 TYPE_32SC4=28
-int32 TYPE_32FC1=5
-int32 TYPE_32FC2=13
-int32 TYPE_32FC3=21
-int32 TYPE_32FC4=29
-int32 TYPE_64FC1=6
-int32 TYPE_64FC2=14
-int32 TYPE_64FC3=22
-int32 TYPE_64FC4=30
+# These are the two most popular image types, so make special synonyms for them
+uint32 TYPE_MONO8=0
+uint32 TYPE_BGR8=16
-int32 type # Type of elements, and channels. Encoded as in OpenCV's TYPE_8UC1 .. TYPE_64FC4.
-int32 step # Full row length in bytes
+uint32 TYPE_8UC1=0
+uint32 TYPE_8UC2=8
+uint32 TYPE_8UC3=16
+uint32 TYPE_8UC4=24
+uint32 TYPE_8SC1=1
+uint32 TYPE_8SC2=9
+uint32 TYPE_8SC3=17
+uint32 TYPE_8SC4=25
+uint32 TYPE_16UC1=2
+uint32 TYPE_16UC2=10
+uint32 TYPE_16UC3=18
+uint32 TYPE_16UC4=26
+uint32 TYPE_16SC1=3
+uint32 TYPE_16SC2=11
+uint32 TYPE_16SC3=19
+uint32 TYPE_16SC4=27
+uint32 TYPE_32SC1=4
+uint32 TYPE_32SC2=12
+uint32 TYPE_32SC3=20
+uint32 TYPE_32SC4=28
+uint32 TYPE_32FC1=5
+uint32 TYPE_32FC2=13
+uint32 TYPE_32FC3=21
+uint32 TYPE_32FC4=29
+uint32 TYPE_64FC1=6
+uint32 TYPE_64FC2=14
+uint32 TYPE_64FC3=22
+uint32 TYPE_64FC4=30
+
+uint32 type # Type of elements, and channels. Encoded as in OpenCV's TYPE_8UC1 .. TYPE_64FC4.
+uint32 step # Full row length in bytes
uint8[] data # actual matrix data, size is (step * rows)
-int32 rows # Number of rows
-int32 cols # Number of columns
+uint32 height # image height, that is, number of rows
+uint32 width # image width, that is, number of columns
uint8 is_bigendian # is this data bigendian
Modified: pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h
===================================================================
--- pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h 2009-08-08 06:38:06 UTC (rev 21165)
@@ -101,7 +101,7 @@
{
CvMat cvmHeader;
- cvInitMatHeader(&cvmHeader, rosimg.rows, rosimg.cols, rosimg.type, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
+ cvInitMatHeader(&cvmHeader, rosimg.height, rosimg.width, rosimg.type, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
cvGetImage(&cvmHeader, rosimg_);
// cvSetData(rosimg_, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
@@ -147,11 +147,11 @@
cvm = cvGetMat(source, &header);
dest.type = cvm->type & (CV_MAT_TYPE_MASK | CV_MAT_DEPTH_MASK);
- dest.cols = cvm->cols;
- dest.rows = cvm->rows;
+ dest.width = cvm->width;
+ dest.height = cvm->height;
dest.step = cvm->step;
- dest.data.resize(cvm->step * cvm->rows);
- memcpy((char*)(&dest.data[0]), source->imageData, cvm->step * cvm->rows);
+ dest.data.resize(cvm->step * cvm->height);
+ memcpy((char*)(&dest.data[0]), source->imageData, cvm->step * cvm->height);
return true;
}
};
Modified: pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py 2009-08-08 06:38:06 UTC (rev 21165)
@@ -69,8 +69,8 @@
ball_yv = -ball_yv
img_msg = sensor_msgs.msg.Image()
- img_msg.rows = 480
- img_msg.cols = 640
+ img_msg.width = 640
+ img_msg.height = 480
img_msg.type = cv.CV_8UC1
img_msg.step = 640
img_msg.data = cvim.tostring()
Modified: pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
===================================================================
--- pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h 2009-08-08 06:38:06 UTC (rev 21165)
@@ -211,8 +211,8 @@
// FIXME: this to avoid segfault when right image empty (disparity image requested instead).
// this all seems kind of hacky
if (im_msg.type == sensor_msgs::Image::TYPE_8UC1) {
- im->imHeight = im_msg.rows;
- im->imWidth = im_msg.cols;
+ im->imHeight = im_msg.height;
+ im->imWidth = im_msg.width;
} else {
im->imHeight = info_msg.height;
im->imWidth = info_msg.width;
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp 2009-08-08 06:34:59 UTC (rev 21164)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp 2009-08-08 06:38:06 UTC (rev 21165)
@@ -112,10 +112,10 @@
return false;
}
- width_ = image->cols;
- height_ = image->rows;
+ width_ = image->width;
+ height_ = image->height;
- uint32_t size = image->rows * image->step;
+ uint32_t size = image->height * image->step;
Ogre::DataStreamPtr pixel_stream;
pixel_stream.bind(new Ogre::MemoryDataStream((void*)(&image->data[0]), size));
texture_->unload();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jam...@us...> - 2009-08-09 19:14:21
|
Revision: 21244
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21244&view=rev
Author: jamesbowman
Date: 2009-08-09 19:14:00 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
Image message and CvBridge change
Modified Paths:
--------------
pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_grab.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h
pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/image_encodings.h
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
pkg/trunk/stacks/common_msgs/sensor_msgs/src/image_encodings.cpp
pkg/trunk/stacks/opencv/image_view/image_view.cpp
pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h
pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py
pkg/trunk/stacks/opencv/opencv_tests/test/enumerants.py
pkg/trunk/stacks/opencv/opencv_tests/test/utest.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp
pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp
pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_calibration.cpp
pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_detector.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/stacks/visual_feature_detectors/outlet_detection/src/outlet_tracker.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/plug_tracker.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/image/ros_image_texture.h
Modified: pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -203,7 +203,7 @@
{
if (img_data->imRawType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data->imHeight, img_data->imWidth, img_data->imWidth,
img_data->imRaw);
@@ -214,7 +214,7 @@
if (img_data->imType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data->imHeight, img_data->imWidth, img_data->imWidth,
img_data->im);
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
@@ -224,7 +224,7 @@
if (img_data->imColorType != COLOR_CODING_NONE && img_data->imColorType == COLOR_CODING_RGB8)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC3,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC3,
img_data->imHeight, img_data->imWidth, 3 * img_data->imWidth,
img_data->imColor );
@@ -235,7 +235,7 @@
if (img_data->imRectType != COLOR_CODING_NONE)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC1,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC1,
img_data->imHeight, img_data->imWidth, img_data->imWidth,
img_data->imRect );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
@@ -245,7 +245,7 @@
if (img_data->imRectColorType != COLOR_CODING_NONE && img_data->imRectColorType == COLOR_CODING_RGB8)
{
- fillImage(img_, sensor_msgs::Image::TYPE_8UC3,
+ fillImage(img_, sensor_msgs::image_encodings::TYPE_8UC3,
img_data->imHeight, img_data->imWidth, 3 * img_data->imWidth,
img_data->imRectColor );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
@@ -255,7 +255,7 @@
if (img_data->imRectColorType != COLOR_CODING_NONE && img_data->imRectColorType == COLOR_CODING_RGBA8)
{
- fillImage(img_,sensor_msgs::Image::TYPE_8UC4,
+ fillImage(img_,sensor_msgs::image_encodings::TYPE_8UC4,
img_data->imHeight, img_data->imWidth, 4 * img_data->imWidth,
img_data->imRectColor );
img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
Modified: pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/forearm_cam/src/nodes/forearm_node.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -954,7 +954,7 @@
int publishImage(size_t width, size_t height, uint8_t *frameData, ros::Time t)
{
- fillImage(image_, sensor_msgs::Image::TYPE_8UC1, height, width, width, frameData);
+ fillImage(image_, sensor_msgs::image_encodings::TYPE_8UC1, height, width, width, frameData);
image_.header.stamp = t;
cam_pub_.publish(image_);
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -86,7 +86,7 @@
return false;
// Copy into result
- fillImage(res.image, sensor_msgs::Image::TYPE_8UC3,
+ fillImage(res.image, sensor_msgs::image_encodings::TYPE_8UC3,
img.Height(), img.Width(), 3 * img.Width(),
img.ImageData());
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_grab.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_grab.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_grab.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -23,7 +23,7 @@
return NULL;
}
- if (!bridge.fromImage(res.image, "bgr")) {
+ if (!bridge.fromImage(res.image, "bgr8")) {
ROS_ERROR("CvBridge::fromImage failed");
return NULL;
}
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -543,7 +543,7 @@
static void setBgrLayout(sensor_msgs::Image &image, int width, int height)
{
- image.type = sensor_msgs::Image::TYPE_8UC3;
+ image.encoding = sensor_msgs::image_encodings::TYPE_8UC3;
image.height = height;
image.width = width;
image.step = width * 3;
@@ -557,7 +557,7 @@
{
case ePvFmtMono8:
- fillImage(image, sensor_msgs::Image::TYPE_8UC1, frame->Height, frame->Width, frame->Width, frame->ImageBuffer);
+ fillImage(image, sensor_msgs::image_encodings::TYPE_8UC1, frame->Height, frame->Width, frame->Width, frame->ImageBuffer);
break;
case ePvFmtBayer8:
@@ -569,20 +569,20 @@
break;
case ePvFmtBgr24:
- fillImage(image, sensor_msgs::Image::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
+ fillImage(image, sensor_msgs::image_encodings::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
break;
case ePvFmtRgba32:
- fillImage(image, sensor_msgs::Image::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
+ fillImage(image, sensor_msgs::image_encodings::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
break;
case ePvFmtBgra32:
- fillImage(image, sensor_msgs::Image::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
+ fillImage(image, sensor_msgs::image_encodings::TYPE_8UC4, frame->Height, frame->Width, 4 * frame->Width, frame->ImageBuffer);
break;
#if 0 // XXX JCB - these cannot be represented in a CvMat
case ePvFmtRgb24:
- // fillImage(image, sensor_msgs::Image::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
+ // fillImage(image, sensor_msgs::image_encodings::TYPE_8UC3, frame->Height, frame->Width, 3 * frame->Width, frame->ImageBuffer);
break;
case ePvFmtYuv411:
// fillImage(image, "image", frame->Height, frame->Width, 6, "yuv411", "uint8", frame->ImageBuffer);
@@ -603,15 +603,15 @@
sensor_msgs::CameraInfo &cam_info)
{
// Currently assume BGR format so bridge.toIpl() image points to msg data buffer
- if (img.type != sensor_msgs::Image::TYPE_8UC1) {
- ROS_WARN("Couldn't rectify frame, unsupported encoding %d", img.type);
+ if (img.encoding != sensor_msgs::image_encodings::TYPE_8UC1) {
+ ROS_WARN("Couldn't rectify frame, unsupported encoding %s", img.encoding.c_str());
return false;
}
// Prepare image buffer
setBgrLayout(rect_img, frame->Width, frame->Height);
- if (!img_bridge_.fromImage(img, "bgr") ||
- !rect_img_bridge_.fromImage(rect_img, "bgr")) {
+ if (!img_bridge_.fromImage(img, "bgr8") ||
+ !rect_img_bridge_.fromImage(rect_img, "bgr8")) {
ROS_WARN("Couldn't rectify frame, failed to convert");
return false;
}
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/fill_image.h 2009-08-09 19:14:00 UTC (rev 21244)
@@ -36,21 +36,22 @@
#define FILLIMAGE_HH
#include "sensor_msgs/Image.h"
+#include "sensor_msgs/image_encodings.h"
namespace sensor_msgs
{
bool fillImage(Image& image,
- uint32_t type_arg,
+ std::string encoding_arg,
uint32_t rows_arg,
uint32_t cols_arg,
uint32_t step_arg,
void* data_arg)
{
- image.type = type_arg;
- image.height = rows_arg;
- image.width = cols_arg;
- image.step = step_arg;
+ image.encoding = encoding_arg;
+ image.height = rows_arg;
+ image.width = cols_arg;
+ image.step = step_arg;
size_t st0 = (step_arg * rows_arg);
image.data.resize(st0);
memcpy((char*)(&image.data[0]), (char*)(data_arg), st0);
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/image_encodings.h
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/image_encodings.h 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/include/sensor_msgs/image_encodings.h 2009-08-09 19:14:00 UTC (rev 21244)
@@ -43,6 +43,35 @@
extern const std::string RGBA8;
extern const std::string BGR8;
extern const std::string BGRA8;
- // etc.
+ extern const std::string MONO8;
+ extern const std::string MONO16;
+ extern const std::string TYPE_8UC1;
+ extern const std::string TYPE_8UC2;
+ extern const std::string TYPE_8UC3;
+ extern const std::string TYPE_8UC4;
+ extern const std::string TYPE_8SC1;
+ extern const std::string TYPE_8SC2;
+ extern const std::string TYPE_8SC3;
+ extern const std::string TYPE_8SC4;
+ extern const std::string TYPE_16UC1;
+ extern const std::string TYPE_16UC2;
+ extern const std::string TYPE_16UC3;
+ extern const std::string TYPE_16UC4;
+ extern const std::string TYPE_16SC1;
+ extern const std::string TYPE_16SC2;
+ extern const std::string TYPE_16SC3;
+ extern const std::string TYPE_16SC4;
+ extern const std::string TYPE_32SC1;
+ extern const std::string TYPE_32SC2;
+ extern const std::string TYPE_32SC3;
+ extern const std::string TYPE_32SC4;
+ extern const std::string TYPE_32FC1;
+ extern const std::string TYPE_32FC2;
+ extern const std::string TYPE_32FC3;
+ extern const std::string TYPE_32FC4;
+ extern const std::string TYPE_64FC1;
+ extern const std::string TYPE_64FC2;
+ extern const std::string TYPE_64FC3;
+ extern const std::string TYPE_64FC4;
}
}
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/msg/Image.msg 2009-08-09 19:14:00 UTC (rev 21244)
@@ -1,44 +1,9 @@
Header header # Header
-# These are the two most popular image types, so make special synonyms for them
-uint32 TYPE_MONO8=0
-uint32 TYPE_BGR8=16
+# The legal values for encoding are in file src/image_encodings.cpp
+# If you want to standardize a new string format, join ros...@li... and send an email proposing a new encoding.
-# Encoded as OpenCV's CvMat type.
-# S=signed, U=unsigned, F=float.
-# For example, TYPE_8UC1 means the elements are 8-bit unsigned and the
-# there is 1 channel, and TYPE_32SC2 means the elements are 32-bit
-# signed and there are 2 channels.
-uint32 TYPE_8UC1=0
-uint32 TYPE_8UC2=8
-uint32 TYPE_8UC3=16
-uint32 TYPE_8UC4=24
-uint32 TYPE_8SC1=1
-uint32 TYPE_8SC2=9
-uint32 TYPE_8SC3=17
-uint32 TYPE_8SC4=25
-uint32 TYPE_16UC1=2
-uint32 TYPE_16UC2=10
-uint32 TYPE_16UC3=18
-uint32 TYPE_16UC4=26
-uint32 TYPE_16SC1=3
-uint32 TYPE_16SC2=11
-uint32 TYPE_16SC3=19
-uint32 TYPE_16SC4=27
-uint32 TYPE_32SC1=4
-uint32 TYPE_32SC2=12
-uint32 TYPE_32SC3=20
-uint32 TYPE_32SC4=28
-uint32 TYPE_32FC1=5
-uint32 TYPE_32FC2=13
-uint32 TYPE_32FC3=21
-uint32 TYPE_32FC4=29
-uint32 TYPE_64FC1=6
-uint32 TYPE_64FC2=14
-uint32 TYPE_64FC3=22
-uint32 TYPE_64FC4=30
-
-uint32 type # Type of elements, and channels. Encoded as in OpenCV's TYPE_8UC1 .. TYPE_64FC4.
+string encoding # Encoding of pixels -- channel meaning, ordering, size -- taken from the list of strings in src/image_encodings.cpp
uint32 step # Full row length in bytes
uint8[] data # actual matrix data, size is (step * rows)
uint32 height # image height, that is, number of rows
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/src/image_encodings.cpp
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/src/image_encodings.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/src/image_encodings.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -42,6 +42,36 @@
const std::string RGBA8 = "rgba8";
const std::string BGR8 = "bgr8";
const std::string BGRA8 = "bgra8";
- // etc.
+ const std::string MONO8="mono8";
+ const std::string MONO16="mono16";
+
+ const std::string TYPE_8UC1="8UC1";
+ const std::string TYPE_8UC2="8UC2";
+ const std::string TYPE_8UC3="8UC3";
+ const std::string TYPE_8UC4="8UC4";
+ const std::string TYPE_8SC1="8SC1";
+ const std::string TYPE_8SC2="8SC2";
+ const std::string TYPE_8SC3="8SC3";
+ const std::string TYPE_8SC4="8SC4";
+ const std::string TYPE_16UC1="16UC1";
+ const std::string TYPE_16UC2="16UC2";
+ const std::string TYPE_16UC3="16UC3";
+ const std::string TYPE_16UC4="16UC4";
+ const std::string TYPE_16SC1="16SC1";
+ const std::string TYPE_16SC2="16SC2";
+ const std::string TYPE_16SC3="16SC3";
+ const std::string TYPE_16SC4="16SC4";
+ const std::string TYPE_32SC1="32SC1";
+ const std::string TYPE_32SC2="32SC2";
+ const std::string TYPE_32SC3="32SC3";
+ const std::string TYPE_32SC4="32SC4";
+ const std::string TYPE_32FC1="32FC1";
+ const std::string TYPE_32FC2="32FC2";
+ const std::string TYPE_32FC3="32FC3";
+ const std::string TYPE_32FC4="32FC4";
+ const std::string TYPE_64FC1="64FC1";
+ const std::string TYPE_64FC2="64FC2";
+ const std::string TYPE_64FC3="64FC3";
+ const std::string TYPE_64FC4="64FC4";
}
}
Modified: pkg/trunk/stacks/opencv/image_view/image_view.cpp
===================================================================
--- pkg/trunk/stacks/opencv/image_view/image_view.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/image_view/image_view.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -95,10 +95,10 @@
msg->encoding = "mono";
#endif
- if (img_bridge_.fromImage(*msg))
+ if (img_bridge_.fromImage(*msg, "bgr8"))
cvShowImage(window_name_.c_str(), img_bridge_.toIpl());
else
- ROS_ERROR("Unable to convert from %d to bgr", msg->type);
+ ROS_ERROR("Unable to convert image to bgr");
}
static void mouse_cb(int event, int x, int y, int flags, void* param)
Modified: pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h
===================================================================
--- pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/opencv_latest/include/opencv_latest/CvBridge.h 2009-08-09 19:14:00 UTC (rev 21244)
@@ -97,32 +97,121 @@
* Converts a ROS Image into an OpenCV IPL Image.
* \param rosimg The ROS Image message
*/
- bool fromImage(const Image& rosimg, std::string encoding = "")
+ bool fromImage(const Image& rosimg, std::string encoding = "passthrough")
{
CvMat cvmHeader;
- cvInitMatHeader(&cvmHeader, rosimg.height, rosimg.width, rosimg.type, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
+ int type;
+ if (rosimg.encoding == "_8UC1") type = CV_8UC1;
+ else if (rosimg.encoding == "_8UC2") type = CV_8UC2;
+ else if (rosimg.encoding == "_8UC3") type = CV_8UC3;
+ else if (rosimg.encoding == "_8UC4") type = CV_8UC4;
+ else if (rosimg.encoding == "_8SC1") type = CV_8SC1;
+ else if (rosimg.encoding == "_8SC2") type = CV_8SC2;
+ else if (rosimg.encoding == "_8SC3") type = CV_8SC3;
+ else if (rosimg.encoding == "_8SC4") type = CV_8SC4;
+ else if (rosimg.encoding == "_16UC1") type = CV_16UC1;
+ else if (rosimg.encoding == "_16UC2") type = CV_16UC2;
+ else if (rosimg.encoding == "_16UC3") type = CV_16UC3;
+ else if (rosimg.encoding == "_16UC4") type = CV_16UC4;
+ else if (rosimg.encoding == "_16SC1") type = CV_16SC1;
+ else if (rosimg.encoding == "_16SC2") type = CV_16SC2;
+ else if (rosimg.encoding == "_16SC3") type = CV_16SC3;
+ else if (rosimg.encoding == "_16SC4") type = CV_16SC4;
+ else if (rosimg.encoding == "_32SC1") type = CV_32SC1;
+ else if (rosimg.encoding == "_32SC2") type = CV_32SC2;
+ else if (rosimg.encoding == "_32SC3") type = CV_32SC3;
+ else if (rosimg.encoding == "_32SC4") type = CV_32SC4;
+ else if (rosimg.encoding == "_32FC1") type = CV_32FC1;
+ else if (rosimg.encoding == "_32FC2") type = CV_32FC2;
+ else if (rosimg.encoding == "_32FC3") type = CV_32FC3;
+ else if (rosimg.encoding == "_32FC4") type = CV_32FC4;
+ else if (rosimg.encoding == "_64FC1") type = CV_64FC1;
+ else if (rosimg.encoding == "_64FC2") type = CV_64FC2;
+ else if (rosimg.encoding == "_64FC3") type = CV_64FC3;
+ else if (rosimg.encoding == "_64FC4") type = CV_64FC4;
+ else if (rosimg.encoding == "rgb8") type = CV_8UC3;
+ else if (rosimg.encoding == "bgr8") type = CV_8UC3;
+ else if (rosimg.encoding == "rgba8") type = CV_8UC4;
+ else if (rosimg.encoding == "bgra8") type = CV_8UC4;
+ else if (rosimg.encoding == "mono8") type = CV_8UC1;
+ else if (rosimg.encoding == "mono16") type = CV_16UC1;
+ else return false;
+ cvInitMatHeader(&cvmHeader, rosimg.height, rosimg.width, type, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
cvGetImage(&cvmHeader, rosimg_);
// cvSetData(rosimg_, const_cast<uint8_t*>(&(rosimg.data[0])), rosimg.step);
- if (encoding == "") {
+ if ((encoding == "passthrough") || (rosimg.encoding == encoding)) {
img_ = rosimg_;
} else {
- if ((encoding == "bgr" || encoding == "rgb") && rosimg.type == CV_8UC1)
- {
- reallocIfNeeded(&cvtimg_, IPL_DEPTH_8U, 3);
- cvCvtColor(rosimg_, cvtimg_, CV_GRAY2BGR);
- img_ = cvtimg_;
+ int change = -1;
+ int newtype = -1;
+
+ if (rosimg.encoding == "rgb8") {
+ if (encoding == "bgr8")
+ change = CV_RGB2BGR;
+ if (encoding == "bgra8")
+ change = CV_RGB2BGRA;
+ if (encoding == "rgba8")
+ change = CV_RGB2RGBA;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_RGB2GRAY;
+ } else if ((rosimg.encoding == "bgr8") || (rosimg.encoding == "_8UC3")) {
+ if (encoding == "rgb8")
+ change = CV_BGR2RGB;
+ if (encoding == "bgra8")
+ change = CV_BGR2BGRA;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_BGR2GRAY;
+ } else if (rosimg.encoding == "rgba8") {
+ if (encoding == "rgb8")
+ change = CV_RGBA2RGB;
+ if (encoding == "bgr8")
+ change = CV_RGBA2BGR;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_RGBA2GRAY;
+ } else if ((rosimg.encoding == "bgra8") || (rosimg.encoding == "_8UC4")) {
+ if (encoding == "rgb8")
+ change = CV_BGRA2RGB;
+ if (encoding == "bgr8")
+ change = CV_BGRA2BGR;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_BGRA2GRAY;
+ } else if (rosimg.encoding == "mono8" || rosimg.encoding == "mono16" || rosimg.encoding == "_8UC1") {
+ if (encoding == "rgb8")
+ change = CV_GRAY2RGB;
+ if (encoding == "bgr8")
+ change = CV_GRAY2BGR;
+ if (encoding == "bgra8")
+ change = CV_GRAY2BGRA;
+ if (encoding == "rgba8")
+ change = CV_GRAY2RGBA;
+ if (encoding == "mono8" || encoding == "mono16")
+ change = CV_COLORCVT_MAX; // means do no conversion
}
- else if (encoding == "mono" && rosimg.type == CV_8UC3)
- {
- reallocIfNeeded(&cvtimg_, IPL_DEPTH_8U, 1);
- cvCvtColor(rosimg_, cvtimg_, CV_RGB2GRAY);
- img_ = cvtimg_;
- } else {
- img_ = rosimg_;
- }
+
+ if (encoding == "bgr8")
+ newtype = CV_8UC3;
+ if (encoding == "rgb8")
+ newtype = CV_8UC3;
+ if (encoding == "bgra8")
+ newtype = CV_8UC4;
+ if (encoding == "rgba")
+ newtype = CV_8UC4;
+ if (encoding == "mono8")
+ newtype = CV_8UC1;
+ if (encoding == "mono16")
+ newtype = CV_16UC1;
+
+ if (change == -1 || newtype == -1)
+ return false;
+ reallocIfNeeded(&cvtimg_, IPL_DEPTH_8U, CV_MAT_CN(newtype));
+ if (change == CV_COLORCVT_MAX)
+ cvConvertScale(rosimg_, cvtimg_);
+ else
+ cvCvtColor(rosimg_, cvtimg_, change);
+ img_ = cvtimg_;
}
return true;
}
@@ -141,12 +230,52 @@
* \param source The original Ipl Image that we want to copy from
* \param dest The ROS Image message that we want to copy to
*/
- static bool fromIpltoRosImage(const IplImage* source, sensor_msgs::Image& dest)
+ static bool fromIpltoRosImage(const IplImage* source, sensor_msgs::Image& dest, std::string encoding = "passthrough")
{
CvMat header, *cvm;
cvm = cvGetMat(source, &header);
- dest.type = cvm->type & (CV_MAT_TYPE_MASK | CV_MAT_DEPTH_MASK);
+ // dest.type = cvm->type & (CV_MAT_TYPE_MASK | CV_MAT_DEPTH_MASK);
+ dest.encoding = encoding;
+
+ if (encoding == "passthrough") {
+ switch (cvm->type & (CV_MAT_TYPE_MASK | CV_MAT_DEPTH_MASK)) {
+ case CV_8UC1: dest.encoding = "_8UC1"; break;
+ case CV_8UC2: dest.encoding = "_8UC2"; break;
+ case CV_8UC3: dest.encoding = "_8UC3"; break;
+ case CV_8UC4: dest.encoding = "_8UC4"; break;
+ case CV_8SC1: dest.encoding = "_8SC1"; break;
+ case CV_8SC2: dest.encoding = "_8SC2"; break;
+ case CV_8SC3: dest.encoding = "_8SC3"; break;
+ case CV_8SC4: dest.encoding = "_8SC4"; break;
+ case CV_16UC1: dest.encoding = "_16UC1"; break;
+ case CV_16UC2: dest.encoding = "_16UC2"; break;
+ case CV_16UC3: dest.encoding = "_16UC3"; break;
+ case CV_16UC4: dest.encoding = "_16UC4"; break;
+ case CV_16SC1: dest.encoding = "_16SC1"; break;
+ case CV_16SC2: dest.encoding = "_16SC2"; break;
+ case CV_16SC3: dest.encoding = "_16SC3"; break;
+ case CV_16SC4: dest.encoding = "_16SC4"; break;
+ case CV_32SC1: dest.encoding = "_32SC1"; break;
+ case CV_32SC2: dest.encoding = "_32SC2"; break;
+ case CV_32SC3: dest.encoding = "_32SC3"; break;
+ case CV_32SC4: dest.encoding = "_32SC4"; break;
+ case CV_32FC1: dest.encoding = "_32FC1"; break;
+ case CV_32FC2: dest.encoding = "_32FC2"; break;
+ case CV_32FC3: dest.encoding = "_32FC3"; break;
+ case CV_32FC4: dest.encoding = "_32FC4"; break;
+ case CV_64FC1: dest.encoding = "_64FC1"; break;
+ case CV_64FC2: dest.encoding = "_64FC2"; break;
+ case CV_64FC3: dest.encoding = "_64FC3"; break;
+ case CV_64FC4: dest.encoding = "_64FC4"; break;
+ default: assert(0);
+ }
+ } else {
+ // XXX JCB - should verify encoding
+ // XXX JCB - should verify that channels match the channels in original image
+ dest.encoding = encoding;
+ }
+
dest.width = cvm->width;
dest.height = cvm->height;
dest.step = cvm->step;
Modified: pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/opencv_tests/nodes/source.py 2009-08-09 19:14:00 UTC (rev 21244)
@@ -71,7 +71,7 @@
img_msg = sensor_msgs.msg.Image()
img_msg.width = 640
img_msg.height = 480
- img_msg.type = cv.CV_8UC1
+ img_msg.type = "8UC1"
img_msg.step = 640
img_msg.data = cvim.tostring()
self.pub.publish(img_msg)
@@ -92,4 +92,3 @@
if __name__ == '__main__':
main(sys.argv)
-
Modified: pkg/trunk/stacks/opencv/opencv_tests/test/enumerants.py
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/test/enumerants.py 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/opencv_tests/test/enumerants.py 2009-08-09 19:14:00 UTC (rev 21244)
@@ -10,12 +10,7 @@
class TestEnumerants(unittest.TestCase):
def test_enumerants(self):
- for t in ["8U", "8S", "16U", "16S", "32S", "32F", "64F" ]:
- for c in [1,2,3,4]:
- nm = "%sC%d" % (t, c)
- cv_num = eval("cv.CV_%s" % nm)
- msg_num = eval("sensor_msgs.msg.Image.TYPE_%s" % nm)
- self.assertEqual(cv_num, msg_num)
+ pass
if __name__ == '__main__':
if 1:
Modified: pkg/trunk/stacks/opencv/opencv_tests/test/utest.cpp
===================================================================
--- pkg/trunk/stacks/opencv/opencv_tests/test/utest.cpp 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/opencv/opencv_tests/test/utest.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -97,15 +97,15 @@
success = img_bridge_.fromIpltoRosImage(original, image_message);
ASSERT_TRUE(success);
- success = img_bridge_.fromImage(image_message, "");
+ success = img_bridge_.fromImage(image_message, "passthrough");
ASSERT_TRUE(success);
EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 1);
- success = img_bridge_.fromImage(image_message, "mono");
+ success = img_bridge_.fromImage(image_message, "mono8");
ASSERT_TRUE(success);
EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 1);
- success = img_bridge_.fromImage(image_message, "rgb");
+ success = img_bridge_.fromImage(image_message, "rgb8");
ASSERT_TRUE(success);
EXPECT_TRUE(CV_MAT_CN(cvGetElemType(img_bridge_.toIpl())) == 3);
}
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-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp 2009-08-09 19:14:00 UTC (rev 21244)
@@ -282,7 +282,7 @@
boost::unique_lock<boost::mutex> lock(data_lock_);
limage_ = image;
- if(lbridge_.fromImage(*limage_, "bgr")) {
+ if(lbridge_.fromImage(*limage_, "bgr8")) {
left_ = lbridge_.toIpl();
}
}
Modified: pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
===================================================================
--- pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h 2009-08-09 19:13:03 UTC (rev 21243)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h 2009-08-09 19:14:00 UTC (rev 21244)
@@ -45,37 +45,37 @@
{
if (im->imRawType != COLOR_CODING_NONE)
...
[truncated message content] |
|
From: <sf...@us...> - 2009-08-10 03:39:02
|
Revision: 21297
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21297&view=rev
Author: sfkwc
Date: 2009-08-10 03:38:56 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
visualization_core is being renamed to visualization_common for release
Added Paths:
-----------
pkg/trunk/stacks/visualization_common/
Removed Paths:
-------------
pkg/trunk/stacks/visualization_core/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <sf...@us...> - 2009-08-10 07:56:29
|
Revision: 21340
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21340&view=rev
Author: sfkwc
Date: 2009-08-10 07:56:21 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
updated stack.xmls
Modified Paths:
--------------
pkg/trunk/stacks/common/stack.xml
pkg/trunk/stacks/estimation/stack.xml
pkg/trunk/stacks/geometry/stack.xml
pkg/trunk/stacks/mechanism/stack.xml
pkg/trunk/stacks/navigation/stack.xml
pkg/trunk/stacks/pr2/stack.xml
pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml
pkg/trunk/stacks/semantic_mapping/stack.xml
pkg/trunk/stacks/stereo/stack.xml
pkg/trunk/stacks/visualization/stack.xml
pkg/trunk/stacks/visualization_common/stack.xml
Modified: pkg/trunk/stacks/common/stack.xml
===================================================================
--- pkg/trunk/stacks/common/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/common/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -10,7 +10,7 @@
<url>http://pr.willowgarage.com/wiki/ROS</url>
<depend stack="geometry"/> <!-- tf, angles -->
- <depend stack="ros"/> <!-- rosconsole, rospy, std_msgs, roslaunch, rostest, roscpp, std_msgs, rospy, rostopic, roscpp -->
- <depend stack="common_msgs"/> <!-- robot_msgs, geometry_msgs, robot_msgs, robot_msgs, geometry_msgs, robot_msgs, diagnostic_msgs, sensor_msgs -->
+ <depend stack="ros"/> <!-- rosconsole, rospy, roslaunch, rostest, roscpp, std_msgs, rostopic-->
+ <depend stack="common_msgs"/> <!-- geometry_msgs, diagnostic_msgs, sensor_msgs -->
</stack>
Modified: pkg/trunk/stacks/estimation/stack.xml
===================================================================
--- pkg/trunk/stacks/estimation/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/estimation/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -9,8 +9,8 @@
<depend stack="geometry"/> <!-- tf -->
- <depend stack="ros"/> <!-- roscpp, std_msgs, gtest -->
+ <depend stack="ros"/>
<depend stack="common"/> <!-- bfl -->
- <depend stack="common_msgs"/> <!-- robot_msgs, geometry_msgs -->
+ <depend stack="common_msgs"/> <!-- geometry_msgs -->
</stack>
Modified: pkg/trunk/stacks/geometry/stack.xml
===================================================================
--- pkg/trunk/stacks/geometry/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/geometry/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -8,6 +8,6 @@
<url>http://pr.willowgarage.com/wiki/ROS</url>
<depend stack="ros"/> <!-- rostest, roscpp, rosconsole, rospy, rostest, roswtf, message_filters -->
- <depend stack="common_msgs"/> <!-- geometry_msgs, robot_msgs, sensor_msgs -->
+ <depend stack="common_msgs"/> <!-- geometry_msgs, sensor_msgs -->
</stack>
Modified: pkg/trunk/stacks/mechanism/stack.xml
===================================================================
--- pkg/trunk/stacks/mechanism/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/mechanism/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -9,10 +9,10 @@
<depend stack="util"/> <!-- realtime_tools -->
- <depend stack="geometry"/> <!-- kdl, tf, bullet, angles, kdl, tf, tf -->
+ <depend stack="geometry"/> <!-- kdl, tf, bullet, angles -->
<depend stack="controllers"/> <!-- control_toolbox, robot_mechanism_controllers, pr2_mechanism_controllers -->
- <depend stack="common"/> <!-- tinyxml, tinyxml, loki, tinyxml, robot_actions -->
- <depend stack="ros"/> <!-- gtest, roscpp, roscpp, std_srvs, roscpp, roscpp, rospy, std_srvs, rosconsole, std_msgs -->
- <depend stack="common_msgs"/> <!-- robot_msgs, robot_msgs, robot_srvs, diagnostic_msgs, robot_msgs, robot_srvs -->
+ <depend stack="common"/> <!-- tinyxml, loki, robot_actions -->
+ <depend stack="ros"/> <!-- gtest, roscpp, rospy, std_srvs, rosconsole, std_msgs -->
+ <depend stack="common_msgs"/> <!-- diagnostic_msgs, robot_srvs -->
</stack>
Modified: pkg/trunk/stacks/navigation/stack.xml
===================================================================
--- pkg/trunk/stacks/navigation/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/navigation/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -8,10 +8,10 @@
<url>http://pr.willowgarage.com/wiki/navigation</url>
- <depend stack="geometry"/> <!-- tf, angles, tf, bullet, tf, tf, tf, angles, tf, tf, angles, tf -->
- <depend stack="ros"/> <!-- roscpp, rosconsole, roscpp, rosconsole, rosconsole, roscpp, rospy, roscpp, message_filters, roscpp, rosconsole, std_msgs, roslib, roscpp, roscpp, rosconsole, roscpp, std_srvs, rostest, std_msgs, rosconsole, roscpp, roslib, rospy, rosconsole, roscpp, std_msgs, std_msgs -->
- <depend stack="visualization_core"/> <!-- visualization_msgs, ogre, ogre_tools, visualization_msgs, visualization_msgs, visualization_msgs, visualization_msgs, visualization_msgs -->
- <depend stack="common"/> <!-- robot_actions, laser_scan, laser_scan, robot_actions, loki -->
- <depend stack="common_msgs"/> <!-- robot_msgs, geometry_msgs, nav_msgs, nav_msgs, robot_srvs, nav_msgs, robot_msgs, geometry_msgs, nav_msgs, nav_msgs, robot_msgs, robot_srvs, robot_msgs, nav_msgs, robot_msgs, geometry_msgs, sensor_msgs, nav_msgs, robot_msgs, geometry_msgs -->
+ <depend stack="geometry"/>
+ <depend stack="ros"/>
+ <depend stack="visualization_core"/>
+ <depend stack="common"/>
+ <depend stack="common_msgs"/>
</stack>
Modified: pkg/trunk/stacks/pr2/stack.xml
===================================================================
--- pkg/trunk/stacks/pr2/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/pr2/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -14,12 +14,12 @@
<depend stack="visualization_core"/> <!-- ogre_tools -->
<depend stack="drivers"/> <!-- forearm_cam -->
<depend stack="mechanism"/> <!-- mechanism_control, hardware_interface, mechanism_control, mechanism_model, convex_decomposition, ivcon, robot_state_publisher, mechanism_bringup, convex_decomposition, ivcon -->
- <depend stack="controllers"/> <!-- robot_mechanism_controllers, pr2_mechanism_controllers, joint_qualification_controllers, dynamic_verification_controllers, pr2_mechanism_controllers, robot_mechanism_controllers -->
+ <depend stack="controllers"/> <!-- robot_mechanism_controllers, pr2_mechanism_controllers, joint_qualification_controllers, dynamic_verification_controllers, pr2_mechanism_controllers -->
<depend stack="common"/> <!-- robot_actions, xacro -->
<depend stack="sound_drivers"/> <!-- sound_play -->
<depend stack="estimation"/> <!-- robot_pose_ekf -->
- <depend stack="ros"/> <!-- std_msgs, roscpp, std_srvs, std_msgs, rxtools, rospy, roslib, std_srvs -->
- <depend stack="common_msgs"/> <!-- robot_msgs, geometry_msgs, diagnostic_msgs -->
+ <depend stack="ros"/> <!-- std_msgs, roscpp, std_msgs, rxtools, rospy, roslib, std_srvs -->
+ <depend stack="common_msgs"/> <!-- geometry_msgs, diagnostic_msgs -->
<depend stack="hardware_test"/> <!-- runtime_monitor -->
<depend stack="highlevel"/> <!-- door_msgs, plugs_msgs -->
Modified: pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -9,5 +9,5 @@
<url>http://pr.willowgarage.com/wiki/ethercat_drivers</url>
<depend stack="ros"/> <!-- rospy, rostest, wxswig, roslaunch, pycrypto -->
<depend stack="visualization_core"/> <!-- visualization_msgs -->
- <depend stack="common_msgs"/> <!-- robot_msgs, geometry_msgs -->
+ <depend stack="common_msgs"/> <!-- geometry_msgs -->
</stack>
Modified: pkg/trunk/stacks/semantic_mapping/stack.xml
===================================================================
--- pkg/trunk/stacks/semantic_mapping/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/semantic_mapping/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -10,12 +10,12 @@
<url>http://pr.willowgarage.com/wiki/mapping</url>
- <depend stack="geometry"/> <!-- angles, eigen, tf, tf, kdl, angles, angles, tf -->
- <depend stack="common_msgs"/> <!-- robot_msgs, sensor_msgs, sensor_msgs, geometry_msgs, mapping_msgs, robot_msgs, geometry_msgs, mapping_msgs, sensor_msgs, robot_srvs, robot_msgs, mapping_msgs -->
+ <depend stack="geometry"/> <!-- angles, eigen, kdl -->
+ <depend stack="common_msgs"/> <!-- sensor_msgs, geometry_msgs, mapping_msgs -->
<depend stack="opencv"/> <!-- opencv_latest -->
<depend stack="common"/> <!-- robot_actions -->
- <depend stack="ros"/> <!-- roscpp, roscpp, std_msgs, roscpp, std_msgs, std_srvs, roscpp -->
- <depend stack="visualization_core"/> <!-- visualization_msgs, visualization_msgs -->
+ <depend stack="ros"/> <!-- std_msgs, std_srvs, roscpp -->
+ <depend stack="visualization_core"/> <!-- visualization_msgs -->
<depend stack="highlevel"/> <!-- plugs_msgs, door_msgs, door_functions -->
</stack>
Modified: pkg/trunk/stacks/stereo/stack.xml
===================================================================
--- pkg/trunk/stacks/stereo/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/stereo/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -11,7 +11,7 @@
<depend stack="opencv"/> <!-- opencvpython, opencv_latest, opencv_latest -->
<depend stack="hardware_test"/> <!-- diagnostic_updater -->
<depend stack="ros"/> <!-- roscpp, rostest, rosrecord, roscpp -->
- <depend stack="common_msgs"/> <!-- sensor_msgs, robot_msgs -->
+ <depend stack="common_msgs"/> <!-- sensor_msgs -->
<depend stack="camera_drivers"/> <!-- libdc1394v2 -->
</stack>
Modified: pkg/trunk/stacks/visualization/stack.xml
===================================================================
--- pkg/trunk/stacks/visualization/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/visualization/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -14,6 +14,6 @@
<depend stack="common"/> <!-- laser_scan -->
<depend stack="ros"/> <!-- roscpp, rosconsole, message_filters, std_msgs, rxtools, wxswig, wxPython_swig_interface -->
<depend stack="visualization_core"/> <!-- ogre, ogre_tools, visualization_msgs -->
- <depend stack="common_msgs"/> <!-- robot_msgs, sensor_msgs, nav_msgs, robot_srvs, mapping_msgs -->
+ <depend stack="common_msgs"/> <!-- sensor_msgs, nav_msgs, mapping_msgs -->
</stack>
Modified: pkg/trunk/stacks/visualization_common/stack.xml
===================================================================
--- pkg/trunk/stacks/visualization_common/stack.xml 2009-08-10 07:55:36 UTC (rev 21339)
+++ pkg/trunk/stacks/visualization_common/stack.xml 2009-08-10 07:56:21 UTC (rev 21340)
@@ -9,6 +9,6 @@
<depend stack="ros"/> <!-- wxswig, rosconsole, roslib, std_msgs -->
- <depend stack="common_msgs"/> <!-- robot_msgs, geometry_msgs -->
+ <depend stack="common_msgs"/> <!-- geometry_msgs -->
</stack>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2009-08-10 08:32:14
|
Revision: 21358
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21358&view=rev
Author: jleibs
Date: 2009-08-10 08:32:06 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
Elaborating on test_stereo_msgs to more fully test RawStereo.
Modified Paths:
--------------
pkg/trunk/stacks/stereo/test_stereo_msgs/manifest.xml
pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py
Added Paths:
-----------
pkg/trunk/stacks/stereo/test_stereo_msgs/test/StereoInfo.saved
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/test_common_msgs/test/StereoInfo.saved
Deleted: pkg/trunk/stacks/common_msgs/test_common_msgs/test/StereoInfo.saved
===================================================================
--- pkg/trunk/stacks/common_msgs/test_common_msgs/test/StereoInfo.saved 2009-08-10 08:31:38 UTC (rev 21357)
+++ pkg/trunk/stacks/common_msgs/test_common_msgs/test/StereoInfo.saved 2009-08-10 08:32:06 UTC (rev 21358)
@@ -1,30 +0,0 @@
-[image_msgs/StereoInfo]:
-# This message defines meta information for a stereo pair. It should
-# be in a stereo namespace and accompanied by 2 camera namespaces, and
-# a disparity image, named:
-#
-# left, right, and disparity, respectively
-
-Header header
-
-uint32 height
-uint32 width
-
-float64[3] T # Pose of right camera in left camera coords
-float64[3] Om # rotation vector
-float64[16] RP # Reprojection Matrix
-
-================================================================================
-MSG: roslib/Header
-#Standard metadata for higher-level flow data types
-#sequence ID: consecutively increasing ID
-uint32 seq
-#Two-integer timestamp that is expressed as:
-# * stamp.secs: seconds (stamp_secs) since epoch
-# * stamp.nsecs: nanoseconds since stamp_secs
-# time-handling sugar is provided by the client library
-time stamp
-#Frame this data is associated with
-# 0: no frame
-# 1: global frame
-string frame_id
\ No newline at end of file
Modified: pkg/trunk/stacks/stereo/test_stereo_msgs/manifest.xml
===================================================================
--- pkg/trunk/stacks/stereo/test_stereo_msgs/manifest.xml 2009-08-10 08:31:38 UTC (rev 21357)
+++ pkg/trunk/stacks/stereo/test_stereo_msgs/manifest.xml 2009-08-10 08:32:06 UTC (rev 21358)
@@ -13,6 +13,7 @@
<depend package="rosbagmigration"/>
<depend package="sensor_msgs"/>
+ <depend package="stereo_msgs"/>
<url>http://pr.willowgarage.com/wiki/test_stereo_msgs</url>
Copied: pkg/trunk/stacks/stereo/test_stereo_msgs/test/StereoInfo.saved (from rev 21347, pkg/trunk/stacks/common_msgs/test_common_msgs/test/StereoInfo.saved)
===================================================================
--- pkg/trunk/stacks/stereo/test_stereo_msgs/test/StereoInfo.saved (rev 0)
+++ pkg/trunk/stacks/stereo/test_stereo_msgs/test/StereoInfo.saved 2009-08-10 08:32:06 UTC (rev 21358)
@@ -0,0 +1,30 @@
+[image_msgs/StereoInfo]:
+# This message defines meta information for a stereo pair. It should
+# be in a stereo namespace and accompanied by 2 camera namespaces, and
+# a disparity image, named:
+#
+# left, right, and disparity, respectively
+
+Header header
+
+uint32 height
+uint32 width
+
+float64[3] T # Pose of right camera in left camera coords
+float64[3] Om # rotation vector
+float64[16] RP # Reprojection Matrix
+
+================================================================================
+MSG: roslib/Header
+#Standard metadata for higher-level flow data types
+#sequence ID: consecutively increasing ID
+uint32 seq
+#Two-integer timestamp that is expressed as:
+# * stamp.secs: seconds (stamp_secs) since epoch
+# * stamp.nsecs: nanoseconds since stamp_secs
+# time-handling sugar is provided by the client library
+time stamp
+#Frame this data is associated with
+# 0: no frame
+# 1: global frame
+string frame_id
\ No newline at end of file
Property changes on: pkg/trunk/stacks/stereo/test_stereo_msgs/test/StereoInfo.saved
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/stacks/common_msgs/test_common_msgs/test/StereoInfo.saved:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Modified: pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py
===================================================================
--- pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py 2009-08-10 08:31:38 UTC (rev 21357)
+++ pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py 2009-08-10 08:32:06 UTC (rev 21358)
@@ -162,18 +162,84 @@
(722.28197999999998, 0.0, 309.70123000000001, -64.130840000000006,
0.0, 722.28197999999998, 240.53899000000001, 0.0,
0.0, 0.0, 1.0, 0.0)),
- 2,
+ raw_stereo.IMAGE,
right_img,
- raw_stereo.IMAGE,
+ 0,
disparity_info(),
image())
def get_new_raw_stereo(self):
from stereo_msgs.msg import RawStereo
+ from stereo_msgs.msg import StereoInfo
+ from stereo_msgs.msg import CamInfo
+ from sensor_msgs.msg import RegionOfInterest
+ from sensor_msgs.msg import Image
+
+ from sensor_msgs.msg import DisparityInfo
+
+ import random
+ r = random.Random(5678)
- return RawStereo()
+ left_img = Image(None,
+ 'mono8',
+ 640,
+ [r.randint(0,255) for x in xrange(0,307200)],
+ 480,
+ 640,
+ 0)
+ right_img = Image(None,
+ 'mono8',
+ 640,
+ [r.randint(0,255) for x in xrange(0,307200)],
+ 480,
+ 640,
+ 0)
+
+ return RawStereo(None,
+ StereoInfo(None,
+ 480, 640,
+ (-0.088779999999999998, -0.00017000000000000001, 0.0015399999999999999),
+ (-0.00296, 0.01155, 0.00064999999999999997),
+ (1.0, 0.0, 0.0, -309.70123000000001,
+ 0.0, 1.0, 0.0, -240.53899000000001,
+ 0.0, 0.0, 0.0, 722.28197999999998,
+ 0.0, 0.0, 11.262630896461046, -0.0)),
+ CamInfo(None,
+ 480, 640,
+ RegionOfInterest(0,0,480,640),
+ (-0.45795000000000002, 0.29532999999999998, 0.0, 0.0, 0.0),
+ (734.37707999999998, 0.0, 343.25992000000002,
+ 0.0, 734.37707999999998, 229.65119999999999,
+ 0.0, 0.0, 1.0),
+ (0.99997999999999998, 0.0012800000000000001, -0.0057400000000000003,
+ -0.0012700000000000001, 1.0, 0.00148,
+ 0.0057400000000000003, -0.00147, 0.99997999999999998),
+ (722.28197999999998, 0.0, 309.70123000000001, 0.0,
+ 0.0, 722.28197999999998, 240.53899000000001, 0.0,
+ 0.0, 0.0, 1.0, 0.0)),
+ RawStereo.IMAGE,
+ left_img,
+ CamInfo(None,
+ 480, 640,
+ RegionOfInterest(0,0,480,640),
+ (-0.46471000000000001, 0.28405999999999998, 0.0, 0.0, 0.0),
+ (732.43358999999998, 0.0, 330.20074,
+ 0.0, 732.43358999999998, 234.71764999999999,
+ 0.0, 0.0, 1.0),
+ (0.99985000000000002, 0.0019, -0.017299999999999999,
+ -0.0019300000000000001, 1.0, -0.0014599999999999999,
+ 0.017299999999999999, 0.00149, 0.99985000000000002),
+ (722.28197999999998, 0.0, 309.70123000000001, -64.130840000000006,
+ 0.0, 722.28197999999998, 240.53899000000001, 0.0,
+ 0.0, 0.0, 1.0, 0.0)),
+ RawStereo.IMAGE,
+ right_img,
+ 0,
+ DisparityInfo(),
+ Image())
+
def test_raw_stereo(self):
self.do_test('raw_stereo', self.get_old_raw_stereo, self.get_new_raw_stereo)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2009-08-10 08:53:23
|
Revision: 21364
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21364&view=rev
Author: jleibs
Date: 2009-08-10 08:53:09 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
Migration of RawStereo message.
Modified Paths:
--------------
pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr
pkg/trunk/stacks/stereo/stereo_msgs/manifest.xml
pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr 2009-08-10 08:46:24 UTC (rev 21363)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr 2009-08-10 08:53:09 UTC (rev 21364)
@@ -315,6 +315,9 @@
valid = True
+ def update_empty(self, old_msg, new_msg):
+ pass
+
def update_mono_uint8(self, old_msg, new_msg):
assert (len(old_msg.uint8_data.layout.dim) == 3 and
old_msg.uint8_data.layout.dim[0].label == 'height' and
@@ -361,7 +364,8 @@
new_msg.is_bigendian = 0
def update(self, old_msg, new_msg):
- encoding_map = {('mono', 'uint8'): self.update_mono_uint8,
+ encoding_map = {('',''): self.update_empty,
+ ('mono', 'uint8'): self.update_mono_uint8,
('rgb', 'uint8'): self.update_rgb_uint8,
('bgr', 'uint8'): self.update_bgr_uint8}
key = (old_msg.encoding, old_msg.depth)
Modified: pkg/trunk/stacks/stereo/stereo_msgs/manifest.xml
===================================================================
--- pkg/trunk/stacks/stereo/stereo_msgs/manifest.xml 2009-08-10 08:46:24 UTC (rev 21363)
+++ pkg/trunk/stacks/stereo/stereo_msgs/manifest.xml 2009-08-10 08:53:09 UTC (rev 21364)
@@ -9,9 +9,12 @@
<review status="unreviewed" notes=""/>
<url>http://pr.willowgarage.com/wiki/stereo_msgs</url>
<depend package="sensor_msgs"/>
+ <depend package="rosbagmigration"/>
<export>
<cpp cflags="-I${prefix}/msg/cpp"/>
+ <rosbagmigration rule_file="migration_rules/stereo_msgs.bmr"/>
</export>
+
</package>
Modified: pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py
===================================================================
--- pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py 2009-08-10 08:46:24 UTC (rev 21363)
+++ pkg/trunk/stacks/stereo/test_stereo_msgs/test/test_stereo_msgs_migration.py 2009-08-10 08:53:09 UTC (rev 21364)
@@ -172,12 +172,11 @@
def get_new_raw_stereo(self):
from stereo_msgs.msg import RawStereo
from stereo_msgs.msg import StereoInfo
- from stereo_msgs.msg import CamInfo
+ from stereo_msgs.msg import DisparityInfo
+ from sensor_msgs.msg import CameraInfo
from sensor_msgs.msg import RegionOfInterest
from sensor_msgs.msg import Image
- from sensor_msgs.msg import DisparityInfo
-
import random
r = random.Random(5678)
@@ -206,7 +205,7 @@
0.0, 1.0, 0.0, -240.53899000000001,
0.0, 0.0, 0.0, 722.28197999999998,
0.0, 0.0, 11.262630896461046, -0.0)),
- CamInfo(None,
+ CameraInfo(None,
480, 640,
RegionOfInterest(0,0,480,640),
(-0.45795000000000002, 0.29532999999999998, 0.0, 0.0, 0.0),
@@ -221,7 +220,7 @@
0.0, 0.0, 1.0, 0.0)),
RawStereo.IMAGE,
left_img,
- CamInfo(None,
+ CameraInfo(None,
480, 640,
RegionOfInterest(0,0,480,640),
(-0.46471000000000001, 0.28405999999999998, 0.0, 0.0, 0.0),
@@ -297,10 +296,10 @@
m.deserialize(buff.getvalue())
#Compare
- print "old"
- print roslib.message.strify_message(msgs[0][1])
- print "new"
- print roslib.message.strify_message(m)
+# print "old"
+# print roslib.message.strify_message(msgs[0][1])
+# print "new"
+# print roslib.message.strify_message(m)
# Strifying them helps make the comparison easier until I figure out why the equality operator is failing
self.assertTrue(roslib.message.strify_message(msgs[0][1]) == roslib.message.strify_message(m))
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2009-08-10 19:32:47
|
Revision: 21448
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21448&view=rev
Author: jleibs
Date: 2009-08-10 19:32:33 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
Updating migration rules to better support the intermediate Image message that existed.
Modified Paths:
--------------
pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr
pkg/trunk/stacks/stereo/stereo_msgs/migration_rules/stereo_msgs.bmr
Modified: pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr
===================================================================
--- pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr 2009-08-10 19:11:57 UTC (rev 21447)
+++ pkg/trunk/stacks/common_msgs/sensor_msgs/migration_rules/sensor_msgs.bmr 2009-08-10 19:32:33 UTC (rev 21448)
@@ -99,9 +99,285 @@
new_msg.name = old_msg.name
new_msg.values = old_msg.vals
-class update_image_msgs_Image_97d4ca3868dc81af4a2403bcb6558cb0(MessageUpdateRule):
- old_type = "image_msgs/Image"
+
+
+
+
+class update_image_msgs_CamInfo_a48ffa77e74ab6901331e50745dff353(MessageUpdateRule):
+ old_type = "image_msgs/CamInfo"
old_full_text = """
+# This message defines meta information for a camera. It should be in a
+# camera namespace and accompanied by up to 5 image topics named:
+#
+# image_raw, image, image_color, image_rect, and image_rect_color
+
+Header header
+
+uint32 height
+uint32 width
+
+float64[5] D # Distortion: k1, k2, t1, t2, k3
+float64[9] K # original camera matrix
+float64[9] R # rectification matrix
+float64[12] P # projection/camera matrix
+
+# Should put exposure, gain, etc. information here as well
+
+================================================================================
+MSG: roslib/Header
+#Standard metadata for higher-level flow data types
+#sequence ID: consecutively increasing ID
+uint32 seq
+#Two-integer timestamp that is expressed as:
+# * stamp.secs: seconds (stamp_secs) since epoch
+# * stamp.nsecs: nanoseconds since stamp_secs
+# time-handling sugar is provided by the client library
+time stamp
+#Frame this data is associated with
+# 0: no frame
+# 1: global frame
+string frame_id
+"""
+
+ new_type = "sensor_msgs/CameraInfo"
+ new_full_text = """
+# This message defines meta information for a camera. It should be in a
+# camera namespace and accompanied by up to 5 image topics named:
+#
+# image_raw, image, image_color, image_rect, and image_rect_color
+#
+# The meaning of the camera parameters are described in detail at
+# http://pr.willowgarage.com/wiki/Camera_Calibration.
+
+Header header
+
+# Resolution in pixels
+uint32 height
+uint32 width
+
+########################
+# Intrinsic parameters #
+########################
+
+# Distortion parameters: k1, k2, t1, t2, k3
+# These model radial and tangential distortion of the camera.
+float64[5] D # 5x1 vector
+
+# Original camera matrix
+# Projects 3D points in the camera coordinate frame to 2D pixel
+# coordinates using the focal lengths (fx, fy) and principal point
+# (cx, cy):
+# [fx 0 cx]
+# K = [ 0 fy cy]
+# [ 0 0 1]
+float64[9] K # 3x3 row-major matrix
+
+########################
+# Extrinsic parameters #
+########################
+
+# Rectification matrix (stereo cameras only)
+# A homography which takes an image to the ideal stereo image plane
+# so that epipolar lines in both stereo images are parallel.
+float64[9] R # 3x3 row-major matrix
+
+# Projection/camera matrix
+# Projects 3D points in a world coordinate frame to 2D pixel coordinates.
+float64[12] P # 3x4 row-major matrix
+
+================================================================================
+MSG: roslib/Header
+#Standard metadata for higher-level flow data types
+#sequence ID: consecutively increasing ID
+uint32 seq
+#Two-integer timestamp that is expressed as:
+# * stamp.secs: seconds (stamp_secs) since epoch
+# * stamp.nsecs: nanoseconds since stamp_secs
+# time-handling sugar is provided by the client library
+time stamp
+#Frame this data is associated with
+# 0: no frame
+# 1: global frame
+string frame_id
+"""
+
+ order = 0
+ migrated_types = [
+ ("Header","Header"),]
+
+ valid = True
+
+ def update(self, old_msg, new_msg):
+ self.migrate(old_msg.header, new_msg.header)
+ new_msg.height = old_msg.height
+ new_msg.width = old_msg.width
+ new_msg.D = old_msg.D
+ new_msg.K = old_msg.K
+ new_msg.R = old_msg.R
+ new_msg.P = old_msg.P
+
+
+class update_sensor_msgs_CameraInfo_a48ffa77e74ab6901331e50745dff353(MessageUpdateRule):
+
+ old_type = "sensor_msgs/CameraInfo"
+ old_full_text = """
+# This message defines meta information for a camera. It should be in a
+# camera namespace and accompanied by up to 5 image topics named:
+#
+# image_raw, image, image_color, image_rect, and image_rect_color
+#
+# The meaning of the camera parameters are described in detail at
+# http://pr.willowgarage.com/wiki/Camera_Calibration.
+
+Header header
+
+# Resolution in pixels
+uint32 height
+uint32 width
+
+########################
+# Intrinsic parameters #
+########################
+
+# Distortion parameters: k1, k2, t1, t2, k3
+# These model radial and tangential distortion of the camera.
+float64[5] D # 5x1 vector
+
+# Original camera matrix
+# Projects 3D points in the camera coordinate frame to 2D pixel
+# coordinates using the focal lengths (fx, fy) and principal point
+# (cx, cy):
+# [fx 0 cx]
+# K = [ 0 fy cy]
+# [ 0 0 1]
+float64[9] K # 3x3 row-major matrix
+
+########################
+# Extrinsic parameters #
+########################
+
+# Rectification matrix (stereo cameras only)
+# A homography which takes an image to the ideal stereo image plane
+# so that epipolar lines in both stereo images are parallel.
+float64[9] R # 3x3 row-major matrix
+
+# Projection/camera matrix
+# Projects 3D points in a world coordinate frame to 2D pixel coordinates.
+float64[12] P # 3x4 row-major matrix
+
+================================================================================
+MSG: roslib/Header
+#Standard metadata for higher-level flow data types
+#sequence ID: consecutively increasing ID
+uint32 seq
+#Two-integer timestamp that is expressed as:
+# * stamp.secs: seconds (stamp_secs) since epoch
+# * stamp.nsecs: nanoseconds since stamp_secs
+# time-handling sugar is provided by the client library
+time stamp
+#Frame this data is associated with
+# 0: no frame
+# 1: global frame
+string frame_id
+"""
+
+ new_type = "sensor_msgs/CameraInfo"
+ new_full_text = """
+# This message defines meta information for a camera. It should be in a
+# camera namespace and accompanied by up to 5 image topics named:
+#
+# image_raw, image, image_color, image_rect, and image_rect_color
+#
+# The meaning of the camera parameters are described in detail at
+# http://pr.willowgarage.com/wiki/Camera_Calibration.
+
+##########################
+# Image acquisition info #
+##########################
+
+# Time of image acquisition, camera coordinate frame ID
+Header header
+
+# Camera resolution in pixels
+uint32 height
+uint32 width
+
+# Region of interest (subwindow of full camera resolution), if applicable
+RegionOfInterest roi
+
+########################
+# Intrinsic parameters #
+########################
+
+# Distortion parameters: k1, k2, t1, t2, k3
+# These model radial and tangential distortion of the camera.
+float64[5] D # 5x1 vector
+
+# Original camera matrix
+# Projects 3D points in the camera coordinate frame to 2D pixel
+# coordinates using the focal lengths (fx, fy) and principal point
+# (cx, cy):
+# [fx 0 cx]
+# K = [ 0 fy cy]
+# [ 0 0 1]
+float64[9] K # 3x3 row-major matrix
+
+########################
+# Extrinsic parameters #
+########################
+
+# Rectification matrix (stereo cameras only)
+# A homography which takes an image to the ideal stereo image plane
+# so that epipolar lines in both stereo images are parallel.
+float64[9] R # 3x3 row-major matrix
+
+# Projection/camera matrix
+# Projects 3D points in a world coordinate frame to 2D pixel coordinates.
+float64[12] P # 3x4 row-major matrix
+
+================================================================================
+MSG: roslib/Header
+#Standard metadata for higher-level flow data types
+#sequence ID: consecutively increasing ID
+uint32 seq
+#Two-integer timestamp that is expressed as:
+# * stamp.secs: seconds (stamp_secs) since epoch
+# * stamp.nsecs: nanoseconds since stamp_secs
+# time-handling sugar is provided by the client library
+time stamp
+#Frame this data is associated with
+# 0: no frame
+# 1: global frame
+string frame_id
+
+================================================================================
+MSG: sensor_msgs/RegionOfInterest
+uint32 x_offset
+uint32 y_offset
+uint32 height
+uint32 width
+"""
+
+ order = 0
+ migrated_types = [
+ ("Header","Header"),]
+
+ valid = True
+
+ def update(self, old_msg, new_msg):
+ self.migrate(old_msg.header, new_msg.header)
+ new_msg.height = old_msg.height
+ new_msg.width = old_msg.width
+ new_msg.roi = self.get_new_class('sensor_msgs/RegionOfInterest')(0,0,old_msg.height,old_msg.width)
+ new_msg.D = old_msg.D
+ new_msg.K = old_msg.K
+ new_msg.R = old_msg.R
+ new_msg.P = old_msg.P
+
+
+class update_sensor_msgs_Image_97d4ca3868dc81af4a2403bcb6558cb0(MessageUpdateRule):
+ old_type = "sensor_msgs/Image"
+ old_full_text = """
Header header # Header
string label # Label for the image
string encoding # Specifies the color encoding of the data
@@ -316,6 +592,7 @@
valid = True
+
def update_empty(self, old_msg, new_msg):
pass
@@ -376,26 +653,52 @@
encoding_map[key](old_msg, new_msg)
-class update_image_msgs_CamInfo_a48ffa77e74ab6901331e50745dff353(MessageUpdateRule):
- old_type = "image_msgs/CamInfo"
- old_full_text = """
-# This message defines meta information for a camera. It should be in a
-# camera namespace and accompanied by up to 5 image topics named:
-#
-# image_raw, image, image_color, image_rect, and image_rect_color
-Header header
-uint32 height
-uint32 width
-float64[5] D # Distortion: k1, k2, t1, t2, k3
-float64[9] K # original camera matrix
-float64[9] R # rectification matrix
-float64[12] P # projection/camera matrix
-# Should put exposure, gain, etc. information here as well
+class update_image_msgs_Image_97d4ca3868dc81af4a2403bcb6558cb0(MessageUpdateRule):
+ old_type = "image_msgs/Image"
+ old_full_text = """
+Header header # Header
+string label # Label for the image
+string encoding # Specifies the color encoding of the data
+ # Acceptable values are:
+ # 1 channel types:
+ # mono, bayer_rggb, bayer_gbrg, bayer_grbg, bayer_bggr
+ # 3 channel types:
+ # rgb, bgr
+ # 4 channel types:
+ # rgba, bgra, yuv422
+ # 6 channel types:
+ # yuv411
+ # N channel types:
+ # other
+string depth # Specifies the depth of the data:
+ # Acceptable values:
+ # uint8, int8, uint16, int16, uint32, int32, uint64, int64, float32, float64
+# Based on depth ONE of the following MultiArrays may contain data.
+# The multi-array MUST have 3 dimensions, labeled as "height",
+# "width", and "channel", though depending on usage the ordering of
+# the dimensions may very. Note that IPL Image convention will order
+# these as: height, width, channel, which is the preferred ordering
+# unless performance dictates otherwise.
+#
+# Height, width, and number of channels are specified in the dimension
+# sizes within the appropriate MultiArray
+
+std_msgs/UInt8MultiArray uint8_data
+std_msgs/Int8MultiArray int8_data
+std_msgs/UInt16MultiArray uint16_data
+std_msgs/Int16MultiArray int16_data
+std_msgs/UInt32MultiArray uint32_data
+std_msgs/Int32MultiArray int32_data
+std_msgs/UInt64MultiArray uint64_data
+std_msgs/Int64MultiArray int64_data
+std_msgs/Float32MultiArray float32_data
+std_msgs/Float64MultiArray float64_data
+
================================================================================
MSG: roslib/Header
#Standard metadata for higher-level flow data types
@@ -410,63 +713,173 @@
# 0: no frame
# 1: global frame
string frame_id
-"""
- new_type = "sensor_msgs/CameraInfo"
- new_full_text = """
-# This message defines meta information for a camera. It should be in a
-# camera namespace and accompanied by up to 5 image topics named:
+================================================================================
+MSG: std_msgs/UInt8MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint8[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/MultiArrayLayout
+# The multiarray declares a generic multi-dimensional array of a
+# particular data type. Dimensions are ordered from outer most
+# to inner most.
+
+MultiArrayDimension[] dim # Array of dimension properties
+uint32 data_offset # padding bytes at front of data
+
+# Accessors should ALWAYS be written in terms of dimension stride
+# and specified outer-most dimension first.
#
-# image_raw, image, image_color, image_rect, and image_rect_color
+# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]
#
-# The meaning of the camera parameters are described in detail at
-# http://pr.willowgarage.com/wiki/Camera_Calibration.
+# A standard, 3-channel 640x480 image with interleaved color channels
+# would be specified as:
+#
+# dim[0].label = "height"
+# dim[0].size = 480
+# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)
+# dim[1].label = "width"
+# dim[1].size = 640
+# dim[1].stride = 3*640 = 1920
+# dim[2].label = "channel"
+# dim[2].size = 3
+# dim[2].stride = 3
+#
+# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.
+================================================================================
+MSG: std_msgs/MultiArrayDimension
+string label # label of given dimension
+uint32 size # size of given dimension (in type units)
+uint32 stride # stride of given dimension
+================================================================================
+MSG: std_msgs/Int8MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
-##########################
-# Image acquisition info #
-##########################
+MultiArrayLayout layout # specification of data layout
+int8[] data # array of data
-# Time of image acquisition, camera coordinate frame ID
-Header header
-# Camera resolution in pixels
-uint32 height
-uint32 width
+================================================================================
+MSG: std_msgs/UInt16MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
-# Region of interest (subwindow of full camera resolution), if applicable
-RegionOfInterest roi
+MultiArrayLayout layout # specification of data layout
+uint16[] data # array of data
-########################
-# Intrinsic parameters #
-########################
-# Distortion parameters: k1, k2, t1, t2, k3
-# These model radial and tangential distortion of the camera.
-float64[5] D # 5x1 vector
+================================================================================
+MSG: std_msgs/Int16MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
-# Original camera matrix
-# Projects 3D points in the camera coordinate frame to 2D pixel
-# coordinates using the focal lengths (fx, fy) and principal point
-# (cx, cy):
-# [fx 0 cx]
-# K = [ 0 fy cy]
-# [ 0 0 1]
-float64[9] K # 3x3 row-major matrix
+MultiArrayLayout layout # specification of data layout
+int16[] data # array of data
-########################
-# Extrinsic parameters #
-########################
-# Rectification matrix (stereo cameras only)
-# A homography which takes an image to the ideal stereo image plane
-# so that epipolar lines in both stereo images are parallel.
-float64[9] R # 3x3 row-major matrix
+================================================================================
+MSG: std_msgs/UInt32MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
-# Projection/camera matrix
-# Projects 3D points in a world coordinate frame to 2D pixel coordinates.
-float64[12] P # 3x4 row-major matrix
+MultiArrayLayout layout # specification of data layout
+uint32[] data # array of data
+
================================================================================
+MSG: std_msgs/Int32MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int32[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/UInt64MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint64[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/Int64MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int64[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/Float32MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+float32[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/Float64MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+float64[] data # array of data
+"""
+
+
+ new_type = "sensor_msgs/Image"
+ new_full_text = """
+Header header # Header
+string label # Label for the image
+string encoding # Specifies the color encoding of the data
+ # Acceptable values are:
+ # 1 channel types:
+ # mono, bayer_rggb, bayer_gbrg, bayer_grbg, bayer_bggr
+ # 3 channel types:
+ # rgb, bgr
+ # 4 channel types:
+ # rgba, bgra, yuv422
+ # 6 channel types:
+ # yuv411
+ # N channel types:
+ # other
+string depth # Specifies the depth of the data:
+ # Acceptable values:
+ # uint8, int8, uint16, int16, uint32, int32, uint64, int64, float32, float64
+
+# Based on depth ONE of the following MultiArrays may contain data.
+# The multi-array MUST have 3 dimensions, labeled as "height",
+# "width", and "channel", though depending on usage the ordering of
+# the dimensions may very. Note that IPL Image convention will order
+# these as: height, width, channel, which is the preferred ordering
+# unless performance dictates otherwise.
+#
+# Height, width, and number of channels are specified in the dimension
+# sizes within the appropriate MultiArray
+
+std_msgs/UInt8MultiArray uint8_data
+std_msgs/Int8MultiArray int8_data
+std_msgs/UInt16MultiArray uint16_data
+std_msgs/Int16MultiArray int16_data
+std_msgs/UInt32MultiArray uint32_data
+std_msgs/Int32MultiArray int32_data
+std_msgs/UInt64MultiArray uint64_data
+std_msgs/Int64MultiArray int64_data
+std_msgs/Float32MultiArray float32_data
+std_msgs/Float64MultiArray float64_data
+
+================================================================================
MSG: roslib/Header
#Standard metadata for higher-level flow data types
#sequence ID: consecutively increasing ID
@@ -482,29 +895,141 @@
string frame_id
================================================================================
-MSG: sensor_msgs/RegionOfInterest
-uint32 x_offset
-uint32 y_offset
-uint32 height
-uint32 width
+MSG: std_msgs/UInt8MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint8[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/MultiArrayLayout
+# The multiarray declares a generic multi-dimensional array of a
+# particular data type. Dimensions are ordered from outer most
+# to inner most.
+
+MultiArrayDimension[] dim # Array of dimension properties
+uint32 data_offset # padding bytes at front of data
+
+# Accessors should ALWAYS be written in terms of dimension stride
+# and specified outer-most dimension first.
+#
+# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]
+#
+# A standard, 3-channel 640x480 image with interleaved color channels
+# would be specified as:
+#
+# dim[0].label = "height"
+# dim[0].size = 480
+# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)
+# dim[1].label = "width"
+# dim[1].size = 640
+# dim[1].stride = 3*640 = 1920
+# dim[2].label = "channel"
+# dim[2].size = 3
+# dim[2].stride = 3
+#
+# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.
+================================================================================
+MSG: std_msgs/MultiArrayDimension
+string label # label of given dimension
+uint32 size # size of given dimension (in type units)
+uint32 stride # stride of given dimension
+================================================================================
+MSG: std_msgs/Int8MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int8[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/UInt16MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint16[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/Int16MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int16[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/UInt32MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint32[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/Int32MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int32[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/UInt64MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint64[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/Int64MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int64[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/Float32MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+float32[] data # array of data
+
+
+================================================================================
+MSG: std_msgs/Float64MultiArray
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+float64[] data # array of data
"""
order = 0
migrated_types = [
- ("Header","Header"),]
+ ("Header","Header"),
+ ("Image","Image")]
valid = True
def update(self, old_msg, new_msg):
- self.migrate(old_msg.header, new_msg.header)
- new_msg.height = old_msg.height
- new_msg.width = old_msg.width
- new_msg.roi = self.get_new_class('RegionOfInterest')(0,0,old_msg.height,old_msg.width)
- new_msg.D = old_msg.D
- new_msg.K = old_msg.K
- new_msg.R = old_msg.R
- new_msg.P = old_msg.P
+ self.migrate(old_msg, new_msg)
+
+
+
class update_sensor_msgs_CompressedImage_9f25a34569b1b807704b985d4396ad35(MessageUpdateRule):
old_type = "sensor_msgs/CompressedImage"
old_full_text = """
Modified: pkg/trunk/stacks/stereo/stereo_msgs/migration_rules/stereo_msgs.bmr
===================================================================
--- pkg/trunk/stacks/stereo/stereo_msgs/migration_rules/stereo_msgs.bmr 2009-08-10 19:11:57 UTC (rev 21447)
+++ pkg/trunk/stacks/stereo/stereo_msgs/migration_rules/stereo_msgs.bmr 2009-08-10 19:32:33 UTC (rev 21448)
@@ -1,4 +1,4 @@
-class update_image_msgs_DisparityInfo_ee4a618c85ea54c8fc3afc56f741d65f(MessageUpdateRule):
+class update_image_msgs_DisparityInfo(MessageUpdateRule):
old_type = "image_msgs/DisparityInfo"
old_full_text = """
# This message defines meta information for a computed disparity image
@@ -40,6 +40,117 @@
string frame_id
"""
+ new_type = "sensor_msgs/DisparityInfo"
+ new_full_text = """
+# This message defines meta information for a computed disparity image
+
+Header header
+
+uint32 height
+uint32 width
+
+int32 dpp
+int32 num_disp
+int32 im_Dtop
+int32 im_Dleft
+int32 im_Dwidth
+int32 im_Dheight
+int32 corr_size
+int32 filter_size
+int32 hor_offset
+int32 texture_thresh
+int32 unique_thresh
+int32 smooth_thresh
+int32 speckle_diff
+int32 speckle_region_size
+byte unique_check
+
+================================================================================
+MSG: roslib/Header
+#Standard metadata for higher-level flow data types
+#sequence ID: consecutively increasing ID
+uint32 seq
+#Two-integer timestamp that is expressed as:
+# * stamp.secs: seconds (stamp_secs) since epoch
+# * stamp.nsecs: nanoseconds since stamp_secs
+# time-handling sugar is provided by the client library
+time stamp
+#Frame this data is associated with
+# 0: no frame
+# 1: global frame
+string frame_id
+"""
+
+ order = 0
+ migrated_types = [
+ ("Header","Header"),]
+
+ valid = True
+
+ def update(self, old_msg, new_msg):
+ self.migrate(old_msg.header, new_msg.header)
+ new_msg.height = old_msg.height
+ new_msg.width = old_msg.width
+ new_msg.dpp = old_msg.dpp
+ new_msg.num_disp = old_msg.num_disp
+ new_msg.im_Dtop = old_msg.im_Dtop
+ new_msg.im_Dleft = old_msg.im_Dleft
+ new_msg.im_Dwidth = old_msg.im_Dwidth
+ new_msg.im_Dheight = old_msg.im_Dheight
+ new_msg.corr_size = old_msg.corr_size
+ new_msg.filter_size = old_msg.filter_size
+ new_msg.hor_offset = old_msg.hor_offset
+ new_msg.texture_thresh = old_msg.texture_thresh
+ new_msg.unique_thresh = old_msg.unique_thresh
+ new_msg.smooth_thresh = old_msg.smooth_thresh
+ new_msg.speckle_diff = old_msg.speckle_diff
+ new_msg.speckle_region_size = old_msg.speckle_region_size
+ new_msg.unique_check = old_msg.unique_check
+
+
+
+class update_sensor_msgs_DisparityInfo(MessageUpdateRule):
+ old_type = "sensor_msgs/DisparityInfo"
+ old_full_text = """
+# This message defines meta information for a computed disparity image
+
+Header header
+
+uint32 height
+uint32 width
+
+int32 dpp
+int32 num_disp
+int32 im_Dtop
+int32 im_Dleft
+int32 im_Dwidth
+int32 im_Dheight
+int32 corr_size
+int32 filter_size
+int32 hor_offset
+int32 texture_thresh
+int32 unique_thresh
+int32 smooth_thresh
+int32 speckle_diff
+int32 speckle_region_size
+byte unique_check
+
+================================================================================
+MSG: roslib/Header
+#Standard metadata for higher-level flow data types
+#sequence ID: consecutively increasing ID
+uint32 seq
+#Two-integer timestamp that is expressed as:
+# * stamp.secs: seconds (stamp_secs) since epoch
+# * stamp.nsecs: nanoseconds since stamp_secs
+# time-handling sugar is provided by the client library
+time stamp
+#Frame this data is associated with
+# 0: no frame
+# 1: global frame
+string frame_id
+"""
+
new_type = "stereo_msgs/DisparityInfo"
new_full_text = """
# This message defines meta information for a computed disparity image
@@ -107,7 +218,9 @@
new_msg.speckle_region_size = old_msg.speckle_region_size
new_msg.unique_check = old_msg.unique_check
-class update_image_msgs_StereoInfo_8d1d3cc504dbf752747c4405c7f7f0c1(MessageUpdateRule):
+
+
+class update_image_msgs_StereoInfo(MessageUpdateRule):
old_type = "image_msgs/StereoInfo"
old_full_text = """
# This message defines meta information for a stereo pair. It should
@@...
[truncated message content] |
|
From: <ei...@us...> - 2009-08-10 21:16:03
|
Revision: 21462
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21462&view=rev
Author: eitanme
Date: 2009-08-10 21:15:51 +0000 (Mon, 10 Aug 2009)
Log Message:
-----------
Separating class implementation from definition for the action server... also moving into a server sub-dir
Modified Paths:
--------------
pkg/trunk/stacks/common/actionlib/src/move_base_server.cpp
pkg/trunk/stacks/navigation/move_base/include/move_base/move_base.h
Added Paths:
-----------
pkg/trunk/stacks/common/actionlib/include/actionlib/server/
pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/goal_handle_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/handle_tracker_deleter_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/single_goal_action_server.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/single_goal_action_server_imp.h
pkg/trunk/stacks/common/actionlib/include/actionlib/server/status_tracker_imp.h
Removed Paths:
-------------
pkg/trunk/stacks/common/actionlib/include/actionlib/action_server.h
pkg/trunk/stacks/common/actionlib/include/actionlib/single_goal_action_server.h
Deleted: pkg/trunk/stacks/common/actionlib/include/actionlib/action_server.h
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/action_server.h 2009-08-10 21:03:21 UTC (rev 21461)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/action_server.h 2009-08-10 21:15:51 UTC (rev 21462)
@@ -1,614 +0,0 @@
-/*********************************************************************
-*
-* Software License Agreement (BSD License)
-*
-* Copyright (c) 2008, Willow Garage, Inc.
-* All rights reserved.
-*
-* Redistribution and use in source and binary forms, with or without
-* modification, are permitted provided that the following conditions
-* are met:
-*
-* * Redistributions of source code must retain the above copyright
-* notice, this list of conditions and the following disclaimer.
-* * Redistributions in binary form must reproduce the above
-* copyright notice, this list of conditions and the following
-* disclaimer in the documentation and/or other materials provided
-* with the distribution.
-* * Neither the name of Willow Garage, Inc. nor the names of its
-* contributors may be used to endorse or promote products derived
-* from this software without specific prior written permission.
-*
-* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-* POSSIBILITY OF SUCH DAMAGE.
-*
-* Author: Eitan Marder-Eppstein
-*********************************************************************/
-#ifndef ACTION_LIB_ACTION_SERVER
-#define ACTION_LIB_ACTION_SERVER
-
-#include <ros/ros.h>
-#include <boost/thread.hpp>
-#include <boost/shared_ptr.hpp>
-#include <actionlib/GoalID.h>
-#include <actionlib/GoalStatusArray.h>
-#include <actionlib/GoalStatus.h>
-#include <actionlib/RequestType.h>
-#include <actionlib/enclosure_deleter.h>
-#include <actionlib/action_definition.h>
-
-#include <list>
-
-namespace actionlib {
- /**
- * @class ActionServer
- * @brief The ActionServer is a helpful tool for managing goal requests to a
- * node. It allows the user to specify callbacks that are invoked when goal
- * or cancel requests come over the wire, and passes back GoalHandles that
- * can be used to track the state of a given goal request. The ActionServer
- * makes no assumptions about the policy used to service these goals, and
- * sends status for each goal over the wire until the last GoalHandle
- * associated with a goal request is destroyed.
- */
- template <class ActionSpec>
- class ActionServer {
- private:
- //generates typedefs that we'll use to make our lives easier
- ACTION_DEFINITION(ActionSpec);
-
- /**
- * @class StatusTracker
- * @brief A class for storing the status of each goal the action server
- * is currently working on
- */
- class StatusTracker {
- public:
- StatusTracker(const GoalID& goal_id, unsigned int status){
- //set the goal id and status appropriately
- status_.goal_id = goal_id;
- status_.status = status;
- }
-
- StatusTracker(const boost::shared_ptr<const ActionGoal>& goal)
- : goal_(goal) {
- //set the goal_id from the message
- status_.goal_id = goal_->goal_id;
-
- //initialize the status of the goal to pending
- status_.status = GoalStatus::PENDING;
-
- //if the goal id is zero, then we need to make up an id for the goal
- if(status_.goal_id.id == ros::Time()){
- status_.goal_id.id = ros::Time::now();
- }
-
- //if the timestamp of the goal is zero, then we'll set it to now()
- if(status_.goal_id.stamp == ros::Time()){
- status_.goal_id.stamp = ros::Time::now();
- }
- }
-
- boost::shared_ptr<const ActionGoal> goal_;
- boost::weak_ptr<void> handle_tracker_;
- GoalStatus status_;
- ros::Time handle_destruction_time_;
- };
-
- /**
- * @class HandleTrackerDeleter
- * @brief A class to help with tracking GoalHandles and removing goals
- * from the status list when the last GoalHandle associated with a given
- * goal is deleted.
- */
- //class to help with tracking status objects
- class HandleTrackerDeleter {
- public:
- HandleTrackerDeleter(ActionServer<ActionSpec>* as,
- typename std::list<StatusTracker>::iterator status_it)
- : as_(as), status_it_(status_it) {}
-
- void operator()(void* ptr){
- if(as_){
- //make sure to lock while we erase status for this goal from the list
- as_->lock_.lock();
- (*status_it_).handle_destruction_time_ = ros::Time::now();
- //as_->status_list_.erase(status_it_);
- as_->lock_.unlock();
- }
- }
-
- private:
- ActionServer<ActionSpec>* as_;
- typename std::list<StatusTracker>::iterator status_it_;
- };
-
- public:
- /**
- * @class GoalHandle
- * @brief Encapsulates a state machine for a given goal that the user can
- * trigger transisions on. All ROS interfaces for the goal are managed by
- * the ActionServer to lessen the burden on the user.
- */
- class GoalHandle {
- public:
- /**
- * @brief Default constructor for a GoalHandle
- */
- GoalHandle(){}
-
- /** @brief Accept the goal referenced by the goal handle. This will
- * transition to the ACTIVE state or the PREEMPTING state depending
- * on whether a cancel request has been received for the goal
- */
- void setAccepted(){
- ROS_DEBUG("Accepting goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
- if(goal_){
- unsigned int status = (*status_it_).status_.status;
-
- //if we were pending before, then we'll go active
- if(status == GoalStatus::PENDING){
- (*status_it_).status_.status = GoalStatus::ACTIVE;
- as_->publishStatus();
- }
- //if we were recalling before, now we'll go to preempting
- else if(status == GoalStatus::RECALLING){
- (*status_it_).status_.status = GoalStatus::PREEMPTING;
- as_->publishStatus();
- }
- else
- ROS_ERROR("To transition to an active state, the goal must be in a pending or recalling state, it is currently in state: %d",
- (*status_it_).status_.status);
- }
- else
- ROS_ERROR("Attempt to set status on an uninitialized GoalHandle");
- }
-
- /**
- * @brief Set the status of the goal associated with the GoalHandle to RECALLED or PREEMPTED
- * depending on what the current status of the goal is
- * @param result Optionally, the user can pass in a result to be sent to any clients of the goal
- */
- void setCanceled(const Result& result = Result()){
- ROS_DEBUG("Setting status to canceled on goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
- if(goal_){
- unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PENDING || status == GoalStatus::RECALLING){
- (*status_it_).status_.status = GoalStatus::RECALLED;
- as_->publishResult((*status_it_).status_, result);
- }
- else if(status == GoalStatus::ACTIVE || status == GoalStatus::PREEMPTING){
- (*status_it_).status_.status = GoalStatus::PREEMPTED;
- as_->publishResult((*status_it_).status_, result);
- }
- else
- ROS_ERROR("To transition to a cancelled state, the goal must be in a pending, recalling, active, or preempting state, it is currently in state: %d",
- (*status_it_).status_.status);
- }
- else
- ROS_ERROR("Attempt to set status on an uninitialized GoalHandle");
- }
-
- /**
- * @brief Set the status of the goal associated with the GoalHandle to rejected
- * @param result Optionally, the user can pass in a result to be sent to any clients of the goal
- */
- void setRejected(const Result& result = Result()){
- ROS_DEBUG("Setting status to rejected on goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
- if(goal_){
- unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PENDING || status == GoalStatus::RECALLING){
- (*status_it_).status_.status = GoalStatus::REJECTED;
- as_->publishResult((*status_it_).status_, result);
- }
- else
- ROS_ERROR("To transition to a rejected state, the goal must be in a pending or recalling state, it is currently in state: %d",
- (*status_it_).status_.status);
- }
- else
- ROS_ERROR("Attempt to set status on an uninitialized GoalHandle");
- }
-
- /**
- * @brief Set the status of the goal associated with the GoalHandle to aborted
- * @param result Optionally, the user can pass in a result to be sent to any clients of the goal
- */
- void setAborted(const Result& result = Result()){
- ROS_DEBUG("Setting status to aborted on goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
- if(goal_){
- unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PREEMPTING || status == GoalStatus::ACTIVE){
- (*status_it_).status_.status = GoalStatus::ABORTED;
- as_->publishResult((*status_it_).status_, result);
- }
- else
- ROS_ERROR("To transition to an aborted state, the goal must be in a preempting or active state, it is currently in state: %d",
- status);
- }
- else
- ROS_ERROR("Attempt to set status on an uninitialized GoalHandle");
- }
-
- /**
- * @brief Set the status of the goal associated with the GoalHandle to succeeded
- * @param result Optionally, the user can pass in a result to be sent to any clients of the goal
- */
- void setSucceeded(const Result& result = Result()){
- ROS_DEBUG("Setting status to succeeded on goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
- if(goal_){
- unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PREEMPTING || status == GoalStatus::ACTIVE){
- (*status_it_).status_.status = GoalStatus::SUCCEEDED;
- as_->publishResult((*status_it_).status_, result);
- }
- else
- ROS_ERROR("To transition to a succeeded state, the goal must be in a preempting or active state, it is currently in state: %d",
- status);
- }
- else
- ROS_ERROR("Attempt to set status on an uninitialized GoalHandle");
- }
-
- /**
- * @brief Send feedback to any clients of the goal associated with this GoalHandle
- * @param feedback The feedback to send to the client
- */
- void publishFeedback(const Feedback& feedback){
- ROS_DEBUG("Publishing feedback for goal, id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
- if(goal_) {
- as_->publishFeedback((*status_it_).status_, feedback);
- }
- else
- ROS_ERROR("Attempt to publish feedback on an uninitialized GoalHandle");
- }
-
- /**
- * @brief Accessor for the goal associated with the GoalHandle
- * @return A shared_ptr to the goal object
- */
- boost::shared_ptr<const Goal> getGoal() const{
- //if we have a goal that is non-null
- if(goal_){
- //create the deleter for our goal subtype
- EnclosureDeleter<const ActionGoal> d(goal_);
- return boost::shared_ptr<const Goal>(&(goal_->goal), d);
- }
- return boost::shared_ptr<const Goal>();
- }
-
- /**
- * @brief Accessor for the goal id associated with the GoalHandle
- * @return The goal id
- */
- GoalID getGoalID() const{
- if(goal_)
- return (*status_it_).status_.goal_id;
- else{
- ROS_ERROR("Attempt to get a goal id on an uninitialized GoalHandle");
- return GoalID();
- }
- }
-
- /**
- * @brief Accessor for the status associated with the GoalHandle
- * @return The goal status
- */
- GoalStatus getGoalStatus() const{
- if(goal_)
- return (*status_it_).status_;
- else{
- ROS_ERROR("Attempt to get goal status on an uninitialized GoalHandle");
- return GoalStatus();
- }
- }
-
- /**
- * @brief Equals operator for GoalHandles
- * @param other The GoalHandle to compare to
- * @return True if the GoalHandles refer to the same goal, false otherwise
- */
- bool operator==(const GoalHandle& other){
- if(!goal_ || !other.goal_)
- return false;
- GoalID my_id = getGoalID();
- GoalID their_id = other.getGoalID();
- return my_id.id == their_id.id;
- }
-
- /**
- * @brief != operator for GoalHandles
- * @param other The GoalHandle to compare to
- * @return True if the GoalHandles refer to different goals, false otherwise
- */
- bool operator!=(const GoalHandle& other){
- if(!goal_ || !other.goal_)
- return true;
- GoalID my_id = getGoalID();
- GoalID their_id = other.getGoalID();
- return my_id.id != their_id.id;
- }
-
- private:
- /**
- * @brief A private constructor used by the ActionServer to initialize a GoalHandle
- */
- GoalHandle(typename std::list<StatusTracker>::iterator status_it,
- ActionServer<ActionSpec>* as, boost::shared_ptr<void> handle_tracker)
- : status_it_(status_it), goal_((*status_it).goal_),
- as_(as), handle_tracker_(handle_tracker){}
-
- /**
- * @brief A private method to set status to PENDING or RECALLING
- * @return True if the cancel request should be passed on to the user, false otherwise
- */
- bool setCancelRequested(){
- ROS_DEBUG("Transisitoning to a cancel requested state on goal id: %.2f, stamp: %.2f", getGoalID().id.toSec(), getGoalID().stamp.toSec());
- if(goal_){
- unsigned int status = (*status_it_).status_.status;
- if(status == GoalStatus::PENDING){
- (*status_it_).status_.status = GoalStatus::RECALLING;
- as_->publishStatus();
- return true;
- }
-
- if(status == GoalStatus::ACTIVE){
- (*status_it_).status_.status = GoalStatus::PREEMPTING;
- as_->publishStatus();
- return true;
- }
-
- }
- return false;
- }
-
- typename std::list<StatusTracker>::iterator status_it_;
- boost::shared_ptr<const ActionGoal> goal_;
- ActionServer<ActionSpec>* as_;
- boost::shared_ptr<void> handle_tracker_;
- friend class ActionServer<ActionSpec>;
- };
-
- /**
- * @brief Constructor for an ActionServer
- * @param n A NodeHandle to create a namespace under
- * @param name The name of the action
- * @param goal_cb A goal callback to be called when the ActionServer receives a new goal over the wire
- * @param cancel_cb A cancel callback to be called when the ActionServer receives a new cancel request over the wire
- */
- ActionServer(ros::NodeHandle n, std::string name,
- boost::function<void (GoalHandle)> goal_cb = boost::function<void (GoalHandle)>(),
- boost::function<void (GoalHandle)> cancel_cb = boost::function<void (GoalHandle)>())
- : node_(n, name), goal_callback_(goal_cb), cancel_callback_(cancel_cb) {
- status_pub_ = node_.advertise<actionlib::GoalStatusArray>("status", 1);
- result_pub_ = node_.advertise<ActionResult>("result", 1);
- feedback_pub_ = node_.advertise<ActionFeedback>("feedback", 1);
-
- goal_sub_ = node_.subscribe<ActionGoal>("goal", 1,
- boost::bind(&ActionServer::goalCallback, this, _1));
-
- cancel_sub_ = node_.subscribe<GoalID>("cancel", 1,
- boost::bind(&ActionServer::cancelCallback, this, _1));
-
- //read the frequency with which to publish status from the parameter server
- double status_frequency, status_list_timeout;
- node_.param("status_frequency", status_frequency, 5.0);
- node_.param("status_list_timeout", status_list_timeout, 5.0);
-
- status_list_timeout_ = ros::Duration(status_list_timeout);
-
- status_timer_ = node_.createTimer(ros::Duration(1.0 / status_frequency),
- boost::bind(&ActionServer::publishStatus, this, _1));
-
- }
-
- /**
- * @brief Register a callback to be invoked when a new goal is received, this will replace any previously registered callback
- * @param cb The callback to invoke
- */
- void registerGoalCallback(boost::function<void (GoalHandle)> cb){
- goal_callback_ = cb;
- }
-
- /**
- * @brief Register a callback to be invoked when a new cancel is received, this will replace any previously registered callback
- * @param cb The callback to invoke
- */
- void registerCancelCallback(boost::function<void (GoalHandle)> cb){
- cancel_callback_ = cb;
- }
-
- private:
- /**
- * @brief Publishes a result for a given goal
- * @param status The status of the goal with which the result is associated
- * @param result The result to publish
- */
- void publishResult(const GoalStatus& status, const Result& result){
- boost::recursive_mutex::scoped_lock lock(lock_);
- //we'll create a shared_ptr to pass to ROS to limit copying
- boost::shared_ptr<ActionResult> ar(new ActionResult);
- ar->status = status;
- ar->result = result;
- result_pub_.publish(ar);
- }
-
- /**
- * @brief Publishes feedback for a given goal
- * @param status The status of the goal with which the feedback is associated
- * @param feedback The feedback to publish
- */
- void publishFeedback(const GoalStatus& status, const Feedback& feedback){
- boost::recursive_mutex::scoped_lock lock(lock_);
- //we'll create a shared_ptr to pass to ROS to limit copying
- boost::shared_ptr<ActionFeedback> af(new ActionFeedback);
- af->status = status;
- af->feedback = feedback;
- feedback_pub_.publish(af);
- }
-
- /**
- * @brief The ROS callback for cancel requests coming into the ActionServer
- */
- void cancelCallback(const boost::shared_ptr<const GoalID>& goal_id){
- boost::recursive_mutex::scoped_lock lock(lock_);
- //we need to handle a cancel for the user
- ROS_DEBUG("The action server has received a new cancel request");
- bool goal_id_found = false;
- for(typename std::list<StatusTracker>::iterator it = status_list_.begin(); it != status_list_.end(); ++it){
- //check if the goal id is zero or if it is equal to the goal id of
- //the iterator or if the time of the iterator warrants a cancel
- if(
- (goal_id->id == ros::Time() && goal_id->stamp == ros::Time()) //id and stamp 0 --> cancel everything
- || goal_id->id == (*it).status_.goal_id.id //ids match... cancel that goal
- || (goal_id->stamp != ros::Time() && (*it).status_.goal_id.stamp <= goal_id->stamp) //stamp != 0 --> cancel everything before stamp
- ){
- //we need to check if we need to store this cancel request for later
- if(goal_id->id == (*it).status_.goal_id.id)
- goal_id_found = true;
-
- //attempt to get the handle_tracker for the list item if it exists
- boost::shared_ptr<void> handle_tracker = (*it).handle_tracker_.lock();
-
- if((*it).handle_tracker_.expired()){
- //if the handle tracker is expired, then we need to create a new one
- HandleTrackerDeleter d(this, it);
- handle_tracker = boost::shared_ptr<void>((void *)NULL, d);
- (*it).handle_tracker_ = handle_tracker;
-
- //we also need to reset the time that the status is supposed to be removed from the list
- (*it).handle_destruction_time_ = ros::Time();
- }
-
- //set the status of the goal to PREEMPTING or RECALLING as approriate
- //and check if the request should be passed on to the user
- GoalHandle gh(it, this, handle_tracker);
- if(gh.setCancelRequested()){
- //call the user's cancel callback on the relevant goal
- cancel_callback_(gh);
- }
- }
-
- }
-
- //if the requested goal_id was not found, and it is non-zero, then we need to store the cancel request
- if(goal_id->id != ros::Time() && !goal_id_found){
- typename std::list<StatusTracker>::iterator it = status_list_.insert(status_list_.end(),
- StatusTracker(*goal_id, GoalStatus::RECALLING));
- //start the timer for how long the status will live in the list without a goal handle to it
- (*it).handle_destruction_time_ = ros::Time::now();
- }
-
- //make sure to set last_cancel_ based on the stamp associated with this cancel request
- if(goal_id->stamp > last_cancel_)
- last_cancel_ = goal_id->stamp;
- }
-
- /**
- * @brief The ROS callback for goals coming into the ActionServer
- */
- void goalCallback(const boost::shared_ptr<const ActionGoal>& goal){
- boost::recursive_mutex::scoped_lock lock(lock_);
-
- ROS_DEBUG("The action server has received a new goal request");
-
- //we need to check if this goal already lives in the status list
- for(typename std::list<StatusTracker>::iterator it = status_list_.begin(); it != status_list_.end(); ++it){
- if(goal->goal_id.id == (*it).status_.goal_id.id){
-
- //if this is a request for a goal that has no active handles left,
- //we'll bump how long it stays in the list
- if((*it).handle_tracker_.expired()){
- (*it).handle_destruction_time_ = ros::Time::now();
- }
-
- //make sure not to call any user callbacks or add duplicate status onto the list
- return;
- }
- }
-
- //if the goal is not in our list, we need to create a StatusTracker associated with this goal and push it on
- typename std::list<StatusTracker>::iterator it = status_list_.insert(status_list_.end(), StatusTracker(goal));
-
- //we need to create a handle tracker for the incoming goal and update the StatusTracker
- HandleTrackerDeleter d(this, it);
- boost::shared_ptr<void> handle_tracker((void *)NULL, d);
- (*it).handle_tracker_ = handle_tracker;
-
- //check if this goal has already been canceled based on its timestamp
- if(goal->goal_id.stamp != ros::Time() && goal->goal_id.stamp <= last_cancel_){
- //if it has... just create a GoalHandle for it and setCanceled
- GoalHandle gh(it, this, handle_tracker);
- gh.setCanceled();
- }
- else{
- //now, we need to create a goal handle and call the user's callback
- goal_callback_(GoalHandle(it, this, handle_tracker));
- }
- }
-
- /**
- * @brief Publish status for all goals on a timer event
- */
- void publishStatus(const ros::TimerEvent& e){
- boost::recursive_mutex::scoped_lock lock(lock_);
- publishStatus();
- }
-
- /**
- * @brief Explicitly publish status
- */
- void publishStatus(){
- boost::recursive_mutex::scoped_lock lock(lock_);
- //build a status array
- GoalStatusArray status_array;
-
- status_array.set_status_list_size(status_list_.size());
-
- unsigned int i = 0;
- for(typename std::list<StatusTracker>::iterator it = status_list_.begin(); it != status_list_.end();){
- status_array.status_list[i] = (*it).status_;
-
- //check if the item is due for deletion from the status list
- if((*it).handle_destruction_time_ != ros::Time()
- && (*it).handle_destruction_time_ + status_list_timeout_ < ros::Time::now()){
- it = status_list_.erase(it);
- }
- else
- ++it;
-
- ++i;
- }
-
- status_pub_.publish(status_array);
- }
-
- ros::NodeHandle node_;
-
- ros::Subscriber goal_sub_, cancel_sub_;
- ros::Publisher status_pub_, result_pub_, feedback_pub_;
-
- boost::recursive_mutex lock_;
-
- ros::Timer status_timer_;
-
- std::list<StatusTracker> status_list_;
-
- boost::function<void (GoalHandle)> goal_callback_;
- boost::function<void (GoalHandle)> cancel_callback_;
-
- ros::Time last_cancel_;
- ros::Duration status_list_timeout_;
-
-
- };
-};
-#endif
Copied: pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server.h (from rev 21306, pkg/trunk/stacks/common/actionlib/include/actionlib/action_server.h)
===================================================================
--- pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server.h (rev 0)
+++ pkg/trunk/stacks/common/actionlib/include/actionlib/server/action_server.h 2009-08-10 21:15:51 UTC (rev 21462)
@@ -0,0 +1,293 @@
+/*********************************************************************
+*
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of Willow Garage, Inc. nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTI...
[truncated message content] |
|
From: <sf...@us...> - 2009-08-11 18:59:21
|
Revision: 21553
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21553&view=rev
Author: sfkwc
Date: 2009-08-11 18:59:08 +0000 (Tue, 11 Aug 2009)
Log Message:
-----------
svn ignores
Property Changed:
----------------
pkg/trunk/stacks/pr2/pr2_ogre/Media/models/
pkg/trunk/stacks/visualization_common/visualization_msgs/
Property changes on: pkg/trunk/stacks/pr2/pr2_ogre/Media/models
___________________________________________________________________
Added: svn:ignore
+ *.mesh
Property changes on: pkg/trunk/stacks/visualization_common/visualization_msgs
___________________________________________________________________
Added: svn:ignore
+ .build_version
.rosgcov_files
bin
src
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <sf...@us...> - 2009-08-11 19:13:06
|
Revision: 21555
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21555&view=rev
Author: sfkwc
Date: 2009-08-11 19:01:45 +0000 (Tue, 11 Aug 2009)
Log Message:
-----------
Moving stage to simulator_stage stack
Added Paths:
-----------
pkg/trunk/stacks/simulator_stage/stage/
Removed Paths:
-------------
pkg/trunk/stacks/simulators/stage/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-08-11 20:58:10
|
Revision: 21568
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21568&view=rev
Author: tfoote
Date: 2009-08-11 20:57:59 +0000 (Tue, 11 Aug 2009)
Log Message:
-----------
fixing visualization_common name and adding files for simulator_stage
Modified Paths:
--------------
pkg/trunk/stacks/visualization_common/CMakeLists.txt
pkg/trunk/stacks/visualization_common/stack.xml
Added Paths:
-----------
pkg/trunk/stacks/simulator_stage/CMakeLists.txt
pkg/trunk/stacks/simulator_stage/Makefile
Copied: pkg/trunk/stacks/simulator_stage/CMakeLists.txt (from rev 21562, pkg/trunk/stacks/common_msgs/CMakeLists.txt)
===================================================================
--- pkg/trunk/stacks/simulator_stage/CMakeLists.txt (rev 0)
+++ pkg/trunk/stacks/simulator_stage/CMakeLists.txt 2009-08-11 20:57:59 UTC (rev 21568)
@@ -0,0 +1,21 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+set(ROSPACK_MAKEDIST true)
+
+# Append to CPACK_SOURCE_IGNORE_FILES a semicolon-separated list of
+# directories (or patterns, but directories should suffice) that should
+# be excluded from the distro. This is not the place to put things that
+# should be ignored everywhere, like "build" directories; that happens in
+# rosbuild/rosbuild.cmake. Here should be listed packages that aren't
+# ready for inclusion in a distro.
+#
+# This list is combined with the list in rosbuild/rosbuild.cmake. Note
+# that CMake 2.6 may be required to ensure that the two lists are combined
+# properly. CMake 2.4 seems to have unpredictable scoping rules for such
+# variables.
+#list(APPEND CPACK_SOURCE_IGNORE_FILES /core/experimental)
+
+rosbuild(simulator_stage 0.1.0)
+# After next ROS release, change to new macro
+#rosbuild_make_distribution(0.1.0)
Property changes on: pkg/trunk/stacks/simulator_stage/CMakeLists.txt
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/stacks/common_msgs/CMakeLists.txt:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Copied: pkg/trunk/stacks/simulator_stage/Makefile (from rev 21562, pkg/trunk/stacks/common_msgs/Makefile)
===================================================================
--- pkg/trunk/stacks/simulator_stage/Makefile (rev 0)
+++ pkg/trunk/stacks/simulator_stage/Makefile 2009-08-11 20:57:59 UTC (rev 21568)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake_stack.mk
Property changes on: pkg/trunk/stacks/simulator_stage/Makefile
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/stacks/common_msgs/Makefile:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Modified: pkg/trunk/stacks/visualization_common/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/visualization_common/CMakeLists.txt 2009-08-11 20:48:23 UTC (rev 21567)
+++ pkg/trunk/stacks/visualization_common/CMakeLists.txt 2009-08-11 20:57:59 UTC (rev 21568)
@@ -16,6 +16,6 @@
# variables.
#list(APPEND CPACK_SOURCE_IGNORE_FILES /core/experimental)
-rosbuild(visualization_core 0.1.0)
+rosbuild(visualization_common 0.1.0)
# After next ROS release, change to new macro
#rosbuild_make_distribution(0.1.0)
Modified: pkg/trunk/stacks/visualization_common/stack.xml
===================================================================
--- pkg/trunk/stacks/visualization_common/stack.xml 2009-08-11 20:48:23 UTC (rev 21567)
+++ pkg/trunk/stacks/visualization_common/stack.xml 2009-08-11 20:57:59 UTC (rev 21568)
@@ -1,5 +1,5 @@
-<stack name="visualization_core" version="0.1">
- <description brief="Visualization Core">
+<stack name="visualization_common" version="0.1">
+ <description brief="Visualization Common">
Tools used for visualization
</description>
<author>Josh Faust jf...@wi...</author>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|