|
From: <tf...@us...> - 2008-12-04 02:50:28
|
Revision: 7556
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7556&view=rev
Author: tfoote
Date: 2008-12-04 02:50:26 +0000 (Thu, 04 Dec 2008)
Log Message:
-----------
moving laser_scan_utils to laser_scan as per API review
Modified Paths:
--------------
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/manifest.xml
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
pkg/trunk/highlevel/highlevel_controllers/manifest.xml
pkg/trunk/nav/wavefront_player/manifest.xml
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/util/laser_scan/CMakeLists.txt
pkg/trunk/util/laser_scan/manifest.xml
pkg/trunk/util/laser_scan/src/laser_scan.cc
pkg/trunk/util/rosTF/include/rosTF/rosTF.h
pkg/trunk/util/rosTF/manifest.xml
pkg/trunk/util/tf/include/tf/transform_listener.h
pkg/trunk/util/tf/manifest.xml
pkg/trunk/world_models/world_3d_map/manifest.xml
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Added Paths:
-----------
pkg/trunk/util/laser_scan/
pkg/trunk/util/laser_scan/include/laser_scan/
pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h
Removed Paths:
-------------
pkg/trunk/util/laser_scan_utils/
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -8,7 +8,7 @@
<url>http://pr.willowgarage.com/wiki/Point_clouds_from_scanning_URG</url>
<depend package="roscpp"/>
<depend package="std_msgs"/>
- <depend package="laser_scan_utils"/>
+ <depend package="laser_scan"/>
<depend package="tf"/>
<depend package="pr2_mechanism_controllers"/>
</package>
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-04 02:50:26 UTC (rev 7556)
@@ -75,7 +75,7 @@
#include "point_cloud_assembler/BuildCloud.h"
// Laser projection
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
#include "math.h"
Modified: pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2008-12-04 02:50:26 UTC (rev 7556)
@@ -57,7 +57,7 @@
#include <tf/transform_broadcaster.h>
// Laser projection
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
// Thread suppport
#include <rosthread/member_thread.h>
Modified: pkg/trunk/highlevel/highlevel_controllers/manifest.xml
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/highlevel/highlevel_controllers/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -18,7 +18,7 @@
<depend package="pr2_msgs"/>
<depend package="kinematic_planning"/>
<depend package="trajectory_rollout"/>
- <depend package="laser_scan_utils" />
+ <depend package="laser_scan" />
<depend package="costmap_2d"/>
<depend package="tf"/>
<depend package="ompl"/>
Modified: pkg/trunk/nav/wavefront_player/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront_player/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/nav/wavefront_player/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -5,7 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp" />
<depend package="player" />
- <depend package="laser_scan_utils" />
+ <depend package="laser_scan" />
<depend package="std_srvs" />
<depend package="tf"/>
<export>
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-04 02:50:26 UTC (rev 7556)
@@ -128,7 +128,7 @@
#include <tf/message_notifier.h>
//Laser projection
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
// For time support
#include <ros/time.h>
Modified: pkg/trunk/util/laser_scan/CMakeLists.txt
===================================================================
--- pkg/trunk/util/laser_scan_utils/CMakeLists.txt 2008-11-13 06:16:44 UTC (rev 6666)
+++ pkg/trunk/util/laser_scan/CMakeLists.txt 2008-12-04 02:50:26 UTC (rev 7556)
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.6)
include(rosbuild)
-rospack(laser_scan_utils)
+rospack(laser_scan)
rospack_add_library(laser_scan src/laser_scan.cc )
\ No newline at end of file
Added: pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h
===================================================================
--- pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h (rev 0)
+++ pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h 2008-12-04 02:50:26 UTC (rev 7556)
@@ -0,0 +1,119 @@
+/*
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ * * Neither the name of the Willow Garage, 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.
+ */
+
+#ifndef LASER_SCAN_UTILS_LASERSCAN_H
+#define LASER_SCAN_UTILS_LASERSCAN_H
+
+#include <map>
+#include <iostream>
+#include <sstream>
+
+#include <newmat10/newmat.h>
+#include <newmat10/newmatio.h>
+#include <newmat10/newmatap.h>
+
+#include "std_msgs/LaserScan.h"
+#include "std_msgs/PointCloud.h"
+#include "std_msgs/PointCloud.h"
+
+/* \mainpage
+ * This is a class for laser scan utilities.
+ * \todo The first goal will be to project laser scans into point clouds efficiently.
+ * The second goal is to provide median filtering.
+ * \todo Other potential additions are upsampling and downsampling algorithms for the scans.
+ */
+
+namespace laser_scan{
+ /** \brief A Class to Project Laser Scan
+ * This class will project laser scans into point clouds, and caches unit vectors
+ * between runs so as not to need to recalculate.
+ */
+ class LaserProjection
+ {
+ public:
+ /** \brief Destructor to deallocate stored unit vectors */
+ ~LaserProjection();
+
+ /** \brief Project Laser Scan
+ * This will project a laser scan from a linear array into a 3D point cloud
+ * \param scan_in The input laser scan
+ * \param cloudOut The output point cloud
+ * \param range_cutoff An additional range cutoff which can be applied which is more limiting than max_range in the scan.
+ * \param preservative Default: false If true all points in scan will be projected, including out of range values. Otherwise they will not be added to the cloud.
+ */
+ void projectLaser(const std_msgs::LaserScan& scan_in, std_msgs::PointCloud & cloud_out, double range_cutoff=-1.0, bool preservative = false);
+
+
+ /** \brief Return the unit vectors for this configuration
+ * Return the unit vectors for this configuration.
+ * if they have not been calculated yet, calculate them and store them
+ * Otherwise it will return them from memory. */
+ NEWMAT::Matrix& getUnitVectors(float angle_max, float angle_min, float angle_increment);
+ private:
+ ///The map of pointers to stored values
+ std::map<std::string,NEWMAT::Matrix*> unit_vector_map_;
+
+ };
+
+ /** \brief A class to provide median filtering of laser scans */
+ class LaserMedianFilter
+ {
+ public:
+ enum MedianMode_t { MEDIAN_TRAILING, MEDIAN_DOWNSAMPLE};
+
+ /** \brief Constructor
+ * \param averaging_length How many scans to average over.
+ * \param num_ranges Whether to downsample and return or compute a rolling median over the last n scans
+ * \param mode What mode to operate in Trailing or Downsampling (Effectively changes returning true every time or every 3)
+ */
+ LaserMedianFilter(unsigned int averaging_length, unsigned int num_ranges, MedianMode_t mode = MEDIAN_DOWNSAMPLE);
+ /** \brief Add a scan to the filter
+ * \param scan_in The new scan to filter
+ * return whether there is a new output to get */
+ bool addScan(const std_msgs::LaserScan& scan_in);
+ /** \brief get the Filtered results
+ * \param scan_result The scan to fill with the median results */
+ void getMedian(std_msgs::LaserScan& scan_result);
+
+
+ private:
+ unsigned int current_packet_num_; ///The number of scans recieved
+ NEWMAT::Matrix range_data_; ///Storage for range_data
+ NEWMAT::Matrix intensity_data_; ///Storage for intensity data
+ unsigned int filter_length_; ///How many scans to average over
+ unsigned int num_ranges_; /// How many data point are in each row
+ MedianMode_t mode_; ///Whether to return true every time or once every 3
+
+ std_msgs::LaserScan temp_scan_; /** \todo cache only shallow info not full scan */
+
+ };
+
+
+}
+#endif //LASER_SCAN_UTILS_LASERSCAN_H
Modified: pkg/trunk/util/laser_scan/manifest.xml
===================================================================
--- pkg/trunk/util/laser_scan_utils/manifest.xml 2008-11-13 06:16:44 UTC (rev 6666)
+++ pkg/trunk/util/laser_scan/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -6,7 +6,7 @@
</description>
<author>Tully Foote</author>
<license>BSD</license>
-<review status="unreviewed" notes="API review in progress (Tully)"/>
+<review status="API conditionally cleared" notes="API followup in progress (Tully)"/>
<url>http://pr.willowgarage.com</url>
<depend package="newmat10"/>
<depend package="std_msgs"/>
Modified: pkg/trunk/util/laser_scan/src/laser_scan.cc
===================================================================
--- pkg/trunk/util/laser_scan_utils/src/laser_scan.cc 2008-11-13 06:16:44 UTC (rev 6666)
+++ pkg/trunk/util/laser_scan/src/laser_scan.cc 2008-12-04 02:50:26 UTC (rev 7556)
@@ -27,7 +27,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*/
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
#include <algorithm>
namespace laser_scan{
Modified: pkg/trunk/util/rosTF/include/rosTF/rosTF.h
===================================================================
--- pkg/trunk/util/rosTF/include/rosTF/rosTF.h 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/util/rosTF/include/rosTF/rosTF.h 2008-12-04 02:50:26 UTC (rev 7556)
@@ -45,7 +45,7 @@
#include "rosTF/TransformArray.h"
#include "libTF/libTF.h"
#include "std_msgs/PointCloud.h"
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
/** \brief A basic ROS client library for libTF
Modified: pkg/trunk/util/rosTF/manifest.xml
===================================================================
--- pkg/trunk/util/rosTF/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/util/rosTF/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -13,7 +13,7 @@
</export>
<depend package="libTF"/>
<depend package="roscpp"/>
-<depend package="laser_scan_utils"/>
+<depend package="laser_scan"/>
<depend package="std_msgs"/>
<depend package="newmat10"/>
</package>
Modified: pkg/trunk/util/tf/include/tf/transform_listener.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-04 02:50:26 UTC (rev 7556)
@@ -33,7 +33,7 @@
#define TF_TRANSFORMLISTENER_H
#include "std_msgs/PointCloud.h"
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
#include "tf/tfMessage.h"
#include "tf/tf.h"
#include "ros/node.h"
Modified: pkg/trunk/util/tf/manifest.xml
===================================================================
--- pkg/trunk/util/tf/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/util/tf/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -15,7 +15,7 @@
<depend package="std_msgs"/>
<depend package="roscpp"/>
<depend package="bullet"/>
-<depend package="laser_scan_utils"/>
+<depend package="laser_scan"/>
<depend package="rosTF"/> <!-- For backwards compatibility only Fixme remove /-->
<depend package="boost"/>
<export>
Modified: pkg/trunk/world_models/world_3d_map/manifest.xml
===================================================================
--- pkg/trunk/world_models/world_3d_map/manifest.xml 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/world_models/world_3d_map/manifest.xml 2008-12-04 02:50:26 UTC (rev 7556)
@@ -6,6 +6,7 @@
<depend package="roscpp" />
<depend package="std_msgs" />
<depend package="rosTF" />
+<depend package="laser_scan" />
<depend package="random_utils" />
<depend package="wg_robot_description_parser" />
<depend package="planning_models" />
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-04 02:50:06 UTC (rev 7555)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-04 02:50:26 UTC (rev 7556)
@@ -114,7 +114,7 @@
#include <random_utils/random_utils.h>
// Laser projection
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
#include <deque>
#include <cmath>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <vij...@us...> - 2008-12-04 03:30:14
|
Revision: 7565
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7565&view=rev
Author: vijaypradeep
Date: 2008-12-04 03:30:09 +0000 (Thu, 04 Dec 2008)
Log Message:
-----------
Added a ground_truth_position controller for the base
Modified Paths:
--------------
pkg/trunk/nav/fake_localization/CMakeLists.txt
pkg/trunk/nav/fake_localization/manifest.xml
Added Paths:
-----------
pkg/trunk/controllers/pr2_mechanism_controllers/scripts/control_base_position_ground_truth.py
pkg/trunk/nav/fake_localization/ground_truth_controller.cpp
pkg/trunk/nav/fake_localization/ground_truth_controller.launch
pkg/trunk/nav/fake_localization/ground_truth_controller.xml
Added: pkg/trunk/controllers/pr2_mechanism_controllers/scripts/control_base_position_ground_truth.py
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/scripts/control_base_position_ground_truth.py (rev 0)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/scripts/control_base_position_ground_truth.py 2008-12-04 03:30:09 UTC (rev 7565)
@@ -0,0 +1,63 @@
+#!/usr/bin/env python
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in the
+# documentation and/or other materials provided with the distribution.
+# * Neither the name of the Willow Garage, 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: Vijay Pradeep
+# (Derived from pointhead.py)
+
+PKG = "pr2_mechanism_controllers"
+
+import rostools; rostools.update_path(PKG)
+
+import sys
+import os
+import string
+from time import sleep
+
+import rospy
+from std_msgs.msg import PointStamped, Point
+from robot_msgs.msg import JointCmd
+
+def control_base_pose_odom_frame(x,y,w):
+ head_angles = rospy.Publisher('ground_truth_controller/set_cmd', Point)
+ rospy.init_node('base_position_commander', anonymous=True)
+ p = Point(x, y, w) ;
+ sleep(1)
+ head_angles.publish( p )
+ sleep(1)
+
+def usage():
+ return "%s [pos_x] [pos_y] [theta (rad)]"%sys.argv[0]
+
+if __name__ == "__main__":
+
+ if len(sys.argv) ==4:
+ control_base_pose_odom_frame(float(sys.argv[1]), float(sys.argv[2]), float(sys.argv[3]) )
+ else:
+ print usage()
+ sys.exit(1)
+
Property changes on: pkg/trunk/controllers/pr2_mechanism_controllers/scripts/control_base_position_ground_truth.py
___________________________________________________________________
Added: svn:executable
+ *
Modified: pkg/trunk/nav/fake_localization/CMakeLists.txt
===================================================================
--- pkg/trunk/nav/fake_localization/CMakeLists.txt 2008-12-04 03:29:42 UTC (rev 7564)
+++ pkg/trunk/nav/fake_localization/CMakeLists.txt 2008-12-04 03:30:09 UTC (rev 7565)
@@ -2,3 +2,4 @@
include(rosbuild)
rospack(fake_localization)
rospack_add_executable(fake_localization fake_localization.cpp)
+rospack_add_executable(ground_truth_controller ground_truth_controller.cpp)
Added: pkg/trunk/nav/fake_localization/ground_truth_controller.cpp
===================================================================
--- pkg/trunk/nav/fake_localization/ground_truth_controller.cpp (rev 0)
+++ pkg/trunk/nav/fake_localization/ground_truth_controller.cpp 2008-12-04 03:30:09 UTC (rev 7565)
@@ -0,0 +1,179 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+
+#include <ros/node.h>
+#include <ros/time.h>
+#include <std_msgs/PoseWithRatesStamped.h>
+#include <std_msgs/BaseVel.h>
+#include "control_toolbox/base_position_pid.h"
+#include "tf/transform_datatypes.h"
+
+using namespace std ;
+
+namespace fake_localization
+{
+
+class GroundTruthController : public ros::node
+{
+public:
+ std_msgs::PoseWithRatesStamped m_ground_truth_ ; //!< Message on which we receive ground truth info
+ control_toolbox::BasePositionPid base_position_pid_ ; //!< Does the PID math for controlling the robot
+ tf::Vector3 xyt_target_ ; //!< The ground truth pose we want to acheive
+ bool first_time_ ;
+ ros::Time prev_time_ ;
+ std_msgs::Point cmd_ ;
+
+ GroundTruthController() : ros::node("ground_truth_controller")
+ {
+ xyt_target_.setX(0) ;
+ xyt_target_.setY(0) ;
+ xyt_target_.setZ(0) ;
+ }
+
+ ~GroundTruthController() { }
+
+ bool initController()
+ {
+ printf("initController()\n") ;
+
+ string xml_config ;
+ param("~xml_config", xml_config, string("")) ;
+ subscribe("base_pose_ground_truth", m_ground_truth_, &GroundTruthController::updateControl, 1) ;
+ subscribe("~set_cmd", cmd_, &GroundTruthController::setCommandCallback, this, 10) ;
+
+ advertise<std_msgs::BaseVel>("cmd_vel", 1) ;
+
+ // Initialize the BasePositionPid util via xml
+ TiXmlDocument xml ;
+ xml.Parse(xml_config.c_str()) ;
+ TiXmlElement *config = xml.RootElement() ;
+ if (config == NULL)
+ {
+ ROS_WARN("Error opening XML file") ;
+ return false ;
+ }
+ bool result = base_position_pid_.initXml(config) ;
+ if (!result)
+ {
+ ROS_WARN("Error loading BasePositionPid xml") ;
+ return false ;
+ }
+
+ first_time_ = true ;
+
+ return true ;
+ }
+
+ /**
+ * Grabs the current ground truth message and computes the next command, and published the command
+ */
+ void updateControl()
+ {
+ //printf("Got ground truth\n") ;
+
+ if (first_time_)
+ {
+ prev_time_ = m_ground_truth_.header.stamp ;
+ first_time_ = false ;
+ return ;
+ }
+
+ ros::Time cur_time = m_ground_truth_.header.stamp ;
+ ros::Duration time_elapsed = cur_time - prev_time_ ;
+ if (time_elapsed.toSec() < .05)
+ return ;
+
+ tf::Transform ground_truth_pose ;
+
+ tf::PoseMsgToTF(m_ground_truth_.pos, ground_truth_pose) ;
+
+ //! \todo Compute yaw angle in a more stable way
+ double yaw,pitch,roll ;
+ ground_truth_pose.getBasis().getEulerZYX(yaw, pitch, roll) ;
+
+ tf::Vector3 xyt_current(ground_truth_pose.getOrigin().x(), ground_truth_pose.getOrigin().y(), yaw) ;
+
+
+ // Determine next velocity to command
+ tf::Vector3 vel_cmd ;
+ vel_cmd = base_position_pid_.updateControl(xyt_target_, xyt_current, time_elapsed.toSec()) ;
+
+ std_msgs::BaseVel base_vel ;
+ base_vel.vx = vel_cmd.x() ;
+ base_vel.vy = vel_cmd.y() ;
+ base_vel.vw = vel_cmd.z() ;
+
+ publish("cmd_vel", base_vel) ;
+
+ prev_time_ = cur_time ;
+ }
+
+ void setCommandCallback()
+ {
+ setCommand(cmd_.x, cmd_.y, cmd_.z) ;
+ }
+
+ void setCommand(double x, double y, double w)
+ {
+ ROS_INFO("BasePositionControllerNode:: Odom Frame Position Command: %f %f %f\n", x, y, w) ;
+
+ //! \todo Mutex this data type
+ xyt_target_.setX(x) ;
+ xyt_target_.setY(y) ;
+ xyt_target_.setZ(w) ;
+ }
+
+} ;
+
+}
+
+using namespace fake_localization ;
+
+int main(int argc, char** argv)
+{
+ ros::init(argc, argv);
+
+ GroundTruthController controller ;
+ controller.initController() ;
+
+ controller.spin() ;
+
+ ros::fini() ;
+
+ return 0 ;
+
+
+
+}
Added: pkg/trunk/nav/fake_localization/ground_truth_controller.launch
===================================================================
--- pkg/trunk/nav/fake_localization/ground_truth_controller.launch (rev 0)
+++ pkg/trunk/nav/fake_localization/ground_truth_controller.launch 2008-12-04 03:30:09 UTC (rev 7565)
@@ -0,0 +1,7 @@
+
+<launch>
+
+ <node pkg="fake_localization" type="ground_truth_controller" name="ground_truth_controller" args="" output="screen">
+ <param name="xml_config" command="$(find xacro)/xacro.py '$(find fake_localization)/ground_truth_controller.xml'" />
+ </node>
+</launch>
\ No newline at end of file
Added: pkg/trunk/nav/fake_localization/ground_truth_controller.xml
===================================================================
--- pkg/trunk/nav/fake_localization/ground_truth_controller.xml (rev 0)
+++ pkg/trunk/nav/fake_localization/ground_truth_controller.xml 2008-12-04 03:30:09 UTC (rev 7565)
@@ -0,0 +1,5 @@
+<base_position_pid>
+ <pid_x p="2.0" d="0" i="0.00" iClamp="0.1" />
+ <pid_y p="2.0" d="0" i="0.00" iClamp="0.1" />
+ <pid_w p="0.5" d="0" i="0.00" iClamp="0.1" />
+</base_position_pid>
Modified: pkg/trunk/nav/fake_localization/manifest.xml
===================================================================
--- pkg/trunk/nav/fake_localization/manifest.xml 2008-12-04 03:29:42 UTC (rev 7564)
+++ pkg/trunk/nav/fake_localization/manifest.xml 2008-12-04 03:30:09 UTC (rev 7565)
@@ -8,4 +8,5 @@
<depend package="robot_msgs" />
<depend package="tf" />
<depend package="angles" />
+ <depend package="control_toolbox" />
</package>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-12-04 15:13:53
|
Revision: 7574
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7574&view=rev
Author: hsujohnhsu
Date: 2008-12-04 15:13:40 +0000 (Thu, 04 Dec 2008)
Log Message:
-----------
* added simple test for 2dnav stack.
* update initial camera position for tables.world.
Modified Paths:
--------------
pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_tables.launch
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tables.world
Added Paths:
-----------
pkg/trunk/demos/2dnav_gazebo/test/
pkg/trunk/demos/2dnav_gazebo/test/test_2dnav.py
pkg/trunk/demos/2dnav_gazebo/test/test_2dnav.xml
pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_tables_no_x.launch
Added: pkg/trunk/demos/2dnav_gazebo/test/test_2dnav.py
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/test/test_2dnav.py (rev 0)
+++ pkg/trunk/demos/2dnav_gazebo/test/test_2dnav.py 2008-12-04 15:13:40 UTC (rev 7574)
@@ -0,0 +1,266 @@
+#!/usr/bin/env python
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above
+# copyright notice, this list of conditions and the following
+# disclaimer in the documentation and/or other materials provided
+# with the distribution.
+# * Neither the name of the Willow Garage nor the names of its
+# contributors may be used to endorse or promote products derived
+# from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+
+## Gazebo test 2dnav stack
+
+PKG = '2dnav_gazebo'
+NAME = 'test_2dnav'
+
+import math
+import rostools
+rostools.update_path(PKG)
+rostools.update_path('rostest')
+rostools.update_path('std_msgs')
+rostools.update_path('robot_msgs')
+rostools.update_path('rostools')
+rostools.update_path('rospy')
+
+
+import sys, unittest
+import os, os.path, threading, time
+import rospy, rostest, rostools
+from std_msgs.msg import *
+from rostools.msg import *
+
+
+TARGET_DURATION = 2.0
+TARGET_TOL = 1.0
+TEST_TIMEOUT = 90.0
+
+TARGET_X = 25.0
+TARGET_Y = 19.0
+TARGET_T = 0.0
+
+class E:
+ def __init__(self,x,y,z):
+ self.x = x
+ self.y = y
+ self.z = z
+
+ def shortest_euler_distance(self, e_from, e_to):
+ # takes two sets of euler angles, finds minimum transform between the two, FIXME: return some hacked norm for now
+ # start from the euler-from, and apply reverse euler-to transform, see how far we are from 0,0,0
+ r0 = e_from.x
+ p0 = e_from.y
+ y0 = e_from.z
+
+ r1 = math.cos(e_to.z)*r0 + math.sin(e_to.z)*p0
+ p1 = -math.sin(e_to.z)*r0 + math.cos(e_to.z)*p0
+ y1 = y0
+
+ r2 = math.cos(e_to.y)*r1 - math.sin(e_to.y)*y1
+ p2 = p1
+ y2 = math.sin(e_to.y)*r1 + math.cos(e_to.y)*y1
+
+ self.x = r2
+ self.y = math.cos(e_to.x)*p1 + math.sin(e_to.x)*y1
+ self.z = -math.sin(e_to.x)*p1 + math.cos(e_to.x)*y1
+
+class Q:
+ def __init__(self,x,y,z,u):
+ self.x = x
+ self.y = y
+ self.z = z
+ self.u = u
+
+ def normalize(self):
+ s = math.sqrt(self.u * self.u + self.x * self.x + self.y * self.y + self.z * self.z)
+ self.u /= s
+ self.x /= s
+ self.y /= s
+ self.z /= s
+
+ def getEuler(self):
+ self.normalize()
+ squ = self.u
+ sqx = self.x
+ sqy = self.y
+ sqz = self.z
+ # init euler angles
+ vec = E(0,0,0)
+ # Roll
+ vec.x = math.atan2(2 * (self.y*self.z + self.u*self.x), squ - sqx - sqy + sqz);
+ # Pitch
+ vec.y = math.asin(-2 * (self.x*self.z - self.u*self.y));
+ # Yaw
+ vec.z = math.atan2(2 * (self.x*self.y + self.u*self.z), squ + sqx - sqy - sqz);
+ return vec
+
+
+
+class NavStackTest(unittest.TestCase):
+ def __init__(self, *args):
+ super(NavStackTest, self).__init__(*args)
+ self.success = False
+ self.reached_target_vw = False
+ self.duration_start = 0
+
+ self.odom_xi = 0;
+ self.odom_yi = 0;
+ self.odom_ei = E(0,0,0)
+ self.odom_initialized = False;
+
+ self.odom_x = 0;
+ self.odom_y = 0;
+ self.odom_e = E(0,0,0)
+
+ self.p3d_xi = 0;
+ self.p3d_yi = 0;
+ self.p3d_ei = E(0,0,0)
+ self.p3d_initialized = False;
+
+ self.p3d_x = 0;
+ self.p3d_y = 0;
+ self.p3d_e = E(0,0,0)
+
+ def normalize_angle_positive(self, angle):
+ return math.fmod(math.fmod(angle, 2*math.pi) + 2*math.pi, 2*math.pi)
+
+ def normalize_angle(self, angle):
+ anorm = self.normalize_angle_positive(angle)
+ if anorm > math.pi:
+ anorm -= 2*math.pi
+ return anorm
+
+ def shortest_angular_distance(self, angle_from, angle_to):
+ angle_diff = self.normalize_angle_positive(angle_to) - self.normalize_angle_positive(angle_from)
+ if angle_diff > math.pi:
+ angle_diff = -(2*math.pi - angle_diff)
+ return self.normalize_angle(angle_diff)
+
+ def printBaseOdom(self, odom):
+ print "odom received"
+ print "odom pos " + "x: " + str(odom.pos.x)
+ print "odom pos " + "y: " + str(odom.pos.y)
+ print "odom pos " + "t: " + str(odom.pos.th)
+ print "odom vel " + "x: " + str(odom.vel.x)
+ print "odom vel " + "y: " + str(odom.vel.y)
+ print "odom vel " + "t: " + str(odom.vel.th)
+
+ def printBaseP3D(self, p3d):
+ print "base pose ground truth received"
+ print "P3D pose translan: " + "x: " + str(p3d.pos.position.x)
+ print " " + "y: " + str(p3d.pos.position.y)
+ print " " + "z: " + str(p3d.pos.position.z)
+ print "P3D pose rotation: " + "x: " + str(p3d.pos.orientation.x)
+ print " " + "y: " + str(p3d.pos.orientation.y)
+ print " " + "z: " + str(p3d.pos.orientation.z)
+ print " " + "w: " + str(p3d.pos.orientation.w)
+ print "P3D rate translan: " + "x: " + str(p3d.vel.vel.x)
+ print " " + "y: " + str(p3d.vel.vel.y)
+ print " " + "z: " + str(p3d.vel.vel.z)
+ print "P3D rate rotation: " + "x: " + str(p3d.vel.ang_vel.vx)
+ print " " + "y: " + str(p3d.vel.ang_vel.vy)
+ print " " + "z: " + str(p3d.vel.ang_vel.vz)
+
+
+
+ def odomInput(self, odom):
+ #self.printBaseOdom(odom)
+ if self.odom_initialized == False:
+ self.odom_initialized = True
+ self.odom_xi = odom.pos.x
+ self.odom_yi = odom.pos.y
+ self.odom_ei = E(0,0,odom.pos.th)
+ self.odom_x = odom.pos.x - self.odom_xi
+ self.odom_y = odom.pos.y - self.odom_yi
+ self.odom_e.shortest_euler_distance(self.odom_ei, E(0,0,odom.pos.th))
+
+
+ def p3dInput(self, p3d):
+ q = Q(p3d.pos.orientation.x , p3d.pos.orientation.y , p3d.pos.orientation.z , p3d.pos.orientation.w)
+ q.normalize()
+ v = q.getEuler()
+
+ if self.p3d_initialized == False:
+ self.p3d_initialized = True
+ self.p3d_xi = p3d.pos.position.x
+ self.p3d_yi = p3d.pos.position.y
+ self.p3d_ei = E(v.x,v.y,v.z)
+
+ self.p3d_x = p3d.pos.position.x - self.p3d_xi
+ self.p3d_y = p3d.pos.position.y - self.p3d_yi
+ self.p3d_e.shortest_euler_distance(self.p3d_ei,E(v.x,v.y,v.z))
+ #print "p3d initial:" + str(self.p3d_ei.x) + "," + str(self.p3d_ei.y) + "," + str(self.p3d_ei.z) \
+ # + " p3d final:" + str(v.x) + "," + str(v.y) + "," + str(v.z)
+
+
+ def test_2dnav(self):
+ print "LNK\n"
+ #pub_base = rospy.Publisher("cmd_vel", BaseVel)
+ pub_goal = rospy.Publisher("goal", Planner2DGoal) #received by wavefront_player or equivalent
+ rospy.Subscriber("base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
+ rospy.Subscriber("odom", RobotBase2DOdom, self.odomInput)
+ rospy.init_node(NAME, anonymous=True)
+ timeout_t = time.time() + TEST_TIMEOUT
+ # wait for result
+ while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
+ # send goal
+ h = Header();
+ h.stamp = rospy.get_rostime();
+ h.frame_id = "map"
+ pub_goal.publish(Planner2DGoal(h,Pose2DFloat32(TARGET_X,TARGET_Y,TARGET_T),1))
+ time.sleep(1.0)
+ # display what odom thinks
+ #print " odom " + " x: " + str(self.odom_e.x) + " y: " + str(self.odom_e.y) + " t: " + str(self.odom_e.t)
+ # display what ground truth is
+ #print " p3d " + " x: " + str(self.p3d_e.x) + " y: " + str(self.p3d_e.y) + " t: " + str(self.p3d_e.t)
+ # display what the odom error is
+ odom_yaw_error = E(0,0,0)
+ odom_yaw_error.shortest_euler_distance(self.p3d_e,self.odom_e)
+ nav_yaw_error = E(0,0,0)
+ nav_yaw_error.shortest_euler_distance(self.p3d_ei,E(0,0,TARGET_T))
+ nav_yaw_error.shortest_euler_distance(self.p3d_e,nav_yaw_error)
+ print " error " + " odom_x:" + str(self.odom_x - self.p3d_x) \
+ + " odom_y:" + str(self.odom_y - self.p3d_y) \
+ + " odom_e:" + str(odom_yaw_error.x) + "," + str(odom_yaw_error.y) + "," + str(odom_yaw_error.z) \
+ + " nav_x:" + str(self.p3d_x - (TARGET_X - self.p3d_xi )) \
+ + " nav_y:" + str(self.p3d_y - (TARGET_Y - self.p3d_yi )) \
+ + " nav_e:" + str(nav_yaw_error.x) + "," + str(nav_yaw_error.y) + "," + str(nav_yaw_error.z)
+ # check total error
+ odom_error = abs(self.odom_x - self.p3d_x) + abs(self.odom_y - self.p3d_y) \
+ + abs(odom_yaw_error.x) + abs(odom_yaw_error.y) + abs(odom_yaw_error.z)
+ nav_error = abs(self.p3d_x - (TARGET_X - self.p3d_xi )) \
+ + abs(self.p3d_y - (TARGET_Y - self.p3d_yi )) \
+ + abs(nav_yaw_error.x) + abs(nav_yaw_error.y) + abs(nav_yaw_error.z)
+ print "nav error:" + str(nav_error) + " tol:" + str(TARGET_TOL) + " odom error:" + str(odom_error)
+ if nav_error < TARGET_TOL:
+ self.success = True
+
+ self.assert_(self.success)
+
+if __name__ == '__main__':
+ rostest.run(PKG, sys.argv[0], NavStackTest, sys.argv) #, text_mode=True)
+
+
Property changes on: pkg/trunk/demos/2dnav_gazebo/test/test_2dnav.py
___________________________________________________________________
Added: svn:executable
+ *
Added: pkg/trunk/demos/2dnav_gazebo/test/test_2dnav.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/test/test_2dnav.xml (rev 0)
+++ pkg/trunk/demos/2dnav_gazebo/test/test_2dnav.xml 2008-12-04 15:13:40 UTC (rev 7574)
@@ -0,0 +1,30 @@
+<launch>
+ <master auto="start" />
+
+ <include file="$(find pr2_prototype1_gazebo)/pr2_prototype1_tables_no_x.launch"/>
+
+ <!-- Common parameter settings /-->
+ <include file="$(find 2dnav_gazebo)/2dnav-params.xml"/>
+ <param name="/trex/ping_frequency" value="1"/>
+
+ <node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/map_blank.png 0.1" respawn="false" />
+ <node pkg="fake_localization" type="fake_localization" respawn="false" output="screen" />
+ <node pkg="world_3d_map" type="world_3d_map" args="/robotdesc/pr2 scan:=tilt_scan cloud:=full_cloud" respawn="false" />
+
+ <!--node pkg="wavefront_player" type="wavefront_player" args="scan:=base_scan" respawn="false" output="screen" /-->
+ <node pkg="highlevel_controllers" type="move_base_sbpl" args="" respawn="false" />
+
+ <!--
+ <node pkg="highlevel_controllers" type="recharge_controller" args="" respawn="false" />
+ <node pkg="kinematic_planning" type="kinematic_planning" args="robotdesc/pr2"/>
+ <include file="$(find world_3d_map)/run.xml"/>
+ <node pkg="highlevel_controllers" type="move_arm" args="right" respawn="false"/>
+ <node pkg="highlevel_controllers" type="move_arm" args="left" respawn="false" />
+ <node pkg="highlevel_controllers" type="move_end_effector" args="right" respawn="false"/>
+ -->
+
+ <!--node pkg="nav_view" type="nav_view" respawn="false" /-->
+
+ <!-- test -->
+ <test test-name="2dnav_gazebo_test_2dnav" pkg="2dnav_gazebo" type="test_2dnav.py" />
+</launch>
Modified: pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_tables.launch
===================================================================
--- pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_tables.launch 2008-12-04 14:17:54 UTC (rev 7573)
+++ pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_tables.launch 2008-12-04 15:13:40 UTC (rev 7574)
@@ -16,7 +16,7 @@
</node>
<!-- push robotdesc/pr2 to factory and spawn robot in gazebo -->
- <node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2 -5 -15 0 0 0 90" respawn="false" output="screen" /> <!-- load default arm controller -->
+ <node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2 -5 -15 0 0 0 0" respawn="false" output="screen" /> <!-- load default arm controller -->
<!-- use mech.py to spawn all controllers listed in controllers.xml -->
<include file="$(find pr2_prototype1_gazebo)/pr2_prototype1_controllers.launch" />
Added: pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_tables_no_x.launch
===================================================================
--- pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_tables_no_x.launch (rev 0)
+++ pkg/trunk/demos/pr2_prototype1_gazebo/pr2_prototype1_tables_no_x.launch 2008-12-04 15:13:40 UTC (rev 7574)
@@ -0,0 +1,25 @@
+<launch>
+ <!-- this launch file corresponds to robot model in ros-pkg/robot_descriptions/wg_robot_description/pr2 -->
+ <!-- if needed, group tag allows pushing components into namespace via ns="namespace" -->
+ <group name="wg">
+
+ <!-- send pr2.xml to parameter server as a string, allow retrieval by various components whe needs it
+ (Mechanism Control, BaseControllerNode, etc...) -->
+ <include file="$(find wg_robot_description)/pr2_prototype1/send_description.xml" />
+
+ <!-- assign environment variables for gazebo and startup gazebo with argument containing the world file. -->
+ <node pkg="gazebo" type="gazebo" args="-r $(find gazebo_robot_description)/gazebo_worlds/tables.world" respawn="false" output="screen">
+ <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(find boost)/boost/lib:$LD_LIBRARY_PATH" />
+ <env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
+ <env name="OGRE_RESOURCE_PATH" value="$(find ogre)/ogre/lib/OGRE" />
+ <env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
+ </node>
+
+ <!-- push robotdesc/pr2 to factory and spawn robot in gazebo -->
+ <node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2 -5 -15 0 0 0 0" respawn="false" output="screen" /> <!-- load default arm controller -->
+
+ <!-- use mech.py to spawn all controllers listed in controllers.xml -->
+ <include file="$(find pr2_prototype1_gazebo)/pr2_prototype1_controllers.launch" />
+ </group>
+</launch>
+
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tables.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tables.world 2008-12-04 14:17:54 UTC (rev 7573)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tables.world 2008-12-04 15:13:40 UTC (rev 7574)
@@ -44,7 +44,7 @@
<frames>
<row height="100%">
<camera width="100%">
- <xyz>0 0 20</xyz>
+ <xyz>-5 -10 20</xyz>
<rpy>0 90 90</rpy>
</camera>
</row>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-12-05 20:41:33
|
Revision: 7679
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7679&view=rev
Author: hsujohnhsu
Date: 2008-12-05 20:41:29 +0000 (Fri, 05 Dec 2008)
Log Message:
-----------
update initial location of camera and robot.
Modified Paths:
--------------
pkg/trunk/demos/pr2_gazebo/pr2_wg.launch
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/wg.world
Modified: pkg/trunk/demos/pr2_gazebo/pr2_wg.launch
===================================================================
--- pkg/trunk/demos/pr2_gazebo/pr2_wg.launch 2008-12-05 20:35:17 UTC (rev 7678)
+++ pkg/trunk/demos/pr2_gazebo/pr2_wg.launch 2008-12-05 20:41:29 UTC (rev 7679)
@@ -12,7 +12,7 @@
</node>
<!-- push robotdesc/pr2 to factory and spawn robot in gazebo -->
- <node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2" respawn="false" output="screen" /> <!-- load default arm controller -->
+ <node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2 -5 -15 0 0 90" respawn="false" output="screen" /> <!-- load default arm controller -->
<!-- load controllers -->
<include file="$(find pr2_prototype1_gazebo)/pr2_prototype1_controllers.launch" />
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/wg.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/wg.world 2008-12-05 20:35:17 UTC (rev 7678)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/wg.world 2008-12-05 20:41:29 UTC (rev 7679)
@@ -44,7 +44,7 @@
<frames>
<row height="100%">
<camera width="100%">
- <xyz>0 0 20</xyz>
+ <xyz>-6 -8 20</xyz>
<rpy>0 90 90</rpy>
</camera>
</row>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mc...@us...> - 2008-12-05 22:04:01
|
Revision: 7695
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7695&view=rev
Author: mcgann
Date: 2008-12-05 21:53:04 +0000 (Fri, 05 Dec 2008)
Log Message:
-----------
Implemeneted, tested, and integrated hybrid reset policy for cost map per trac:714
Modified Paths:
--------------
pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
pkg/trunk/world_models/costmap_2d/include/costmap_2d/costmap_2d.h
pkg/trunk/world_models/costmap_2d/src/costmap_2d.cpp
pkg/trunk/world_models/costmap_2d/src/test/module-tests.cc
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-12-05 21:49:10 UTC (rev 7694)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-12-05 21:53:04 UTC (rev 7695)
@@ -295,7 +295,7 @@
*/
void MoveBase::updateGoalMsg(){
// Revert to static map on new goal. May result in oscillation, but requested by Eitan for the milestone
- costMap_->revertToStaticMap();
+ costMap_->revertToStaticMap(global_pose_.getOrigin().x(), global_pose_.getOrigin().y());
tf::Stamped<tf::Pose> goalPose, transformedGoalPose;
btQuaternion qt;
@@ -411,7 +411,7 @@
*/
void MoveBase::handlePlanningFailure(){
ROS_DEBUG("No plan found. Handling planning failure");
- costMap_->revertToStaticMap();
+ costMap_->revertToStaticMap(global_pose_.getOrigin().x(), global_pose_.getOrigin().y());
stopRobot();
}
Modified: pkg/trunk/world_models/costmap_2d/include/costmap_2d/costmap_2d.h
===================================================================
--- pkg/trunk/world_models/costmap_2d/include/costmap_2d/costmap_2d.h 2008-12-05 21:49:10 UTC (rev 7694)
+++ pkg/trunk/world_models/costmap_2d/include/costmap_2d/costmap_2d.h 2008-12-05 21:53:04 UTC (rev 7695)
@@ -175,9 +175,12 @@
double getWeight() const {return weight_;}
/**
- * @brief Will reset the cost data to the initiali propagated costs of the static map
+ * @brief Will reset the cost data
+ * @param wx the x position in world coordinates
+ * @param wy the y position in world coordinates
*/
- void revertToStaticMap();
+ void revertToStaticMap(double wx = 0.0, double wy = 0.0);
+
private:
/**
@@ -241,6 +244,8 @@
QUEUE queue_; /**< Used for cost propagation */
double** cachedDistances; /**< Cached distances indexed by dx, dy */
+ const unsigned int kernelWidth_; /**< The width of the kernel matrix, which will be square */
+ unsigned char* kernelData_; /**< kernel data structure for cost map updates around the robot */
};
/**
Modified: pkg/trunk/world_models/costmap_2d/src/costmap_2d.cpp
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/costmap_2d.cpp 2008-12-05 21:49:10 UTC (rev 7694)
+++ pkg/trunk/world_models/costmap_2d/src/costmap_2d.cpp 2008-12-05 21:53:04 UTC (rev 7695)
@@ -79,7 +79,7 @@
inscribedRadius_(toCellDistance(inscribedRadius, circumscribedRadius_, resolution)),
weight_(std::max(0.0, std::min(weight, 1.0))), sq_obstacle_range_(obstacleRange * obstacleRange),
sq_raytrace_range_((raytraceRange / resolution) * (raytraceRange / resolution)),
- staticData_(NULL), xy_markers_(NULL)
+ staticData_(NULL), xy_markers_(NULL), kernelWidth_((circumscribedRadius_ * 2) + 1)
{
if(weight != weight_){
ROS_INFO("Warning - input weight %f is invalid and has been set to %f\n", weight, weight_);
@@ -90,6 +90,7 @@
xy_markers_ = new bool[width_*height_];
memset(xy_markers_, 0, width_ * height_* sizeof(bool));
+ // Set up a cache of distance values for a kernel around the robot
cachedDistances = new double*[inflationRadius_+1];
for (i=0; i<=inflationRadius_; i++) {
cachedDistances[i] = new double[inflationRadius_+1];
@@ -99,6 +100,9 @@
}
}
+ // Allocate memory for a kernel matrix to be used for map updates aruond the robot
+ kernelData_ = new unsigned char[kernelWidth_ * kernelWidth_];
+
setCircumscribedCostLowerBound(computeCost(circumscribedRadius_));
// For the first pass, just clean up the data and get the set of original obstacles.
@@ -140,17 +144,35 @@
}
- void CostMap2D::revertToStaticMap(){
- // Using the original policy since the requested change implemented below performs poorly in practice
- // as the map is accumulating free space and thus the planner does really strange things.
+ void CostMap2D::revertToStaticMap(double wx, double wy){
+ unsigned int mx, my;
+ WC_MC(wx, wy, mx, my);
+
+ // Reset the kernel. A box around the current position. Then copy the current cost data in that region
+ // We can assume the whole kernel is in the global map, because the robot is in the map and the borders of the map
+ // are walls anyway.
+ memset(kernelData_, 0, kernelWidth_ * kernelWidth_);
+ const unsigned int originX = mx - circumscribedRadius_;
+ const unsigned int originY = my - circumscribedRadius_;
+ for (unsigned int i = 0; i < kernelWidth_; i++){
+ for(unsigned int j = 0; j < kernelWidth_; j++){
+ unsigned int kernelIndex = (j * kernelWidth_) + i;
+ unsigned int costMapIndex = (originY + j) * width_ + originX + i;
+ kernelData_[kernelIndex] = costData_[costMapIndex];
+ }
+ }
+
+ // Reset the cost map to the static data
memcpy(costData_, staticData_, width_ * height_);
- /*
- // Revising the policy per Eitan's discussion with Eric where we want to revert to the most relaxed map based on our current perception
- // and the static map.
- unsigned int cellCount = width_ * height_;
- for (unsigned int i = 0; i < cellCount; i++)
- costData_[i] = std::min(costData_[i], staticData_[i]);
- */
+
+ // Now repeat the iteration over the kernel, but this time write the data back
+ for (unsigned int i = 0; i < kernelWidth_; i++){
+ for(unsigned int j = 0; j < kernelWidth_; j++){
+ unsigned int kernelIndex = (j * kernelWidth_) + i;
+ unsigned int costMapIndex = (originY + j) * width_ + originX + i;
+ costData_[costMapIndex] = std::min(costData_[costMapIndex], kernelData_[kernelIndex]);
+ }
+ }
}
/**
Modified: pkg/trunk/world_models/costmap_2d/src/test/module-tests.cc
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/test/module-tests.cc 2008-12-05 21:49:10 UTC (rev 7694)
+++ pkg/trunk/world_models/costmap_2d/src/test/module-tests.cc 2008-12-05 21:53:04 UTC (rev 7695)
@@ -74,6 +74,94 @@
}
/**
+ * Tests the reset method
+ */
+TEST(costmap, testResetForStaticMap){
+ // Define a static map with a large object in the center
+ std::vector<unsigned char> staticMap;
+ for(unsigned int i=0; i<10; i++){
+ for(unsigned int j=0; j<10; j++){
+ staticMap.push_back(CostMap2D::LETHAL_OBSTACLE);
+ }
+ }
+
+ // Allocate the cost map, with a inflation to 3 cells all around
+ CostMap2D map(10, 10, staticMap, RESOLUTION, THRESHOLD, MAX_Z, MAX_Z, MAX_Z, 3, 3, 3);
+
+ // Populate the cost map with a wall around the perimeter. Free space should clear out the room.
+ std_msgs::PointCloud cloud;
+ cloud.set_pts_size(40);
+
+ // Left wall
+ unsigned int ind = 0;
+ for (unsigned int i = 0; i < 10; i++){
+ // Left
+ cloud.pts[ind].x = 0;
+ cloud.pts[ind].y = i;
+ cloud.pts[ind].z = MAX_Z;
+ ind++;
+
+ // Top
+ cloud.pts[ind].x = i;
+ cloud.pts[ind].y = 0;
+ cloud.pts[ind].z = MAX_Z;
+ ind++;
+
+ // Right
+ cloud.pts[ind].x = 9;
+ cloud.pts[ind].y = i;
+ cloud.pts[ind].z = MAX_Z;
+ ind++;
+
+ // Bottom
+ cloud.pts[ind].x = i;
+ cloud.pts[ind].y = 9;
+ cloud.pts[ind].z = MAX_Z;
+ ind++;
+ }
+
+ double wx = 5.0, wy = 5.0;
+ std_msgs::Point p;
+ p.x = wx;
+ p.y = wy;
+ p.z = MAX_Z;
+ Observation obs(p, &cloud);
+ std::vector<Observation> obsBuf;
+ obsBuf.push_back(obs);
+
+ // Update the cost map for this observation
+ map.updateDynamicObstacles(wx, wy, obsBuf);
+
+ // Verify that we know have only 8 * 4 + 4 cells with lethal cost, thus provong that we have correctly cleared
+ // free space
+ unsigned int hitCount = 0;
+ for(unsigned int i=0; i <100; i++){
+ if(map.getMap()[i] == CostMap2D::LETHAL_OBSTACLE)
+ hitCount++;
+ }
+ ASSERT_EQ(hitCount, 36);
+
+ // Veriy that we have 4 free cells
+ hitCount = 0;
+ for(unsigned int i=0; i < 100; i++){
+ if(map.getMap()[i] == 0)
+ hitCount++;
+ }
+ ASSERT_EQ(hitCount, 4);
+
+ // Now if we reset the cost map, we shold retain the free space, and also retain values of INSCRIBED circle
+ // in the region of the circumscribed radius (3 cells)
+ map.revertToStaticMap(wx, wy);
+ unsigned int mx, my;
+ map.WC_MC(wx, wy, mx, my);
+ for(unsigned int x = mx - 3; x <= mx+3; x++){
+ for(unsigned int y = my -3; y <= my + 3; y++){
+ ASSERT_EQ(map.getCost(x, y) < CostMap2D::LETHAL_OBSTACLE, true);
+ }
+ }
+}
+
+/**
* Basic testing for observation buffer
*/
TEST(costmap, test15){
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-12-06 00:11:55
|
Revision: 7707
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7707&view=rev
Author: gerkey
Date: 2008-12-06 00:11:46 +0000 (Sat, 06 Dec 2008)
Log Message:
-----------
added watchdog timeout to rosstage
Modified Paths:
--------------
pkg/trunk/highlevel/test_highlevel_controllers/test/launch_gazebo.xml
pkg/trunk/highlevel/test_highlevel_controllers/test/launch_gazebo_wg_amcl.xml
pkg/trunk/highlevel/test_highlevel_controllers/test/launch_move_base.xml
pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_2.5cm.xml
pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_5cm.xml
pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_amcl_5cm.xml
pkg/trunk/simulators/rosstage/rosstage.cc
Added Paths:
-----------
pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage.xml
Removed Paths:
-------------
pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage.xml
pkg/trunk/highlevel/test_highlevel_controllers/test/stage.xml
Modified: pkg/trunk/highlevel/test_highlevel_controllers/test/launch_gazebo.xml
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/launch_gazebo.xml 2008-12-05 23:48:46 UTC (rev 7706)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/launch_gazebo.xml 2008-12-06 00:11:46 UTC (rev 7707)
@@ -18,7 +18,7 @@
<node pkg="nav_view" type="nav_view" args="odom:=localizedpose" respawn="false"/>
<!-- Now launch controller node required -->
- <include file="$(find highlevel_controllers)/test/launch_move_base.xml"/>
+ <include file="$(find test_highlevel_controllers)/test/launch_move_base.xml"/>
</group>
</launch>
Modified: pkg/trunk/highlevel/test_highlevel_controllers/test/launch_gazebo_wg_amcl.xml
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/launch_gazebo_wg_amcl.xml 2008-12-05 23:48:46 UTC (rev 7706)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/launch_gazebo_wg_amcl.xml 2008-12-06 00:11:46 UTC (rev 7707)
@@ -32,7 +32,7 @@
<node pkg="nav_view" type="nav_view" args="odom:=localizedpose" respawn="false"/>
<!-- Now launch controller node required -->
- <include file="$(find highlevel_controllers)/test/launch_move_base.xml"/>
+ <include file="$(find test_highlevel_controllers)/test/launch_move_base.xml"/>
</group>
</launch>
Modified: pkg/trunk/highlevel/test_highlevel_controllers/test/launch_move_base.xml
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/launch_move_base.xml 2008-12-05 23:48:46 UTC (rev 7706)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/launch_move_base.xml 2008-12-06 00:11:46 UTC (rev 7707)
@@ -19,6 +19,6 @@
<param name="/costmap_2d/circumscribed_radius" value="0.46"/>
<param name="/costmap_2d/inscribed_radius" value="0.325"/>
<param name="/costmap_2d/weight" value="0.1"/>
- <node pkg="highlevel_controllers" type="move_base_sbpl" args="base_scan:=base_scan tilt_scan:=tilt_scan" respawn="true" />
+ <node pkg="highlevel_controllers" type="move_base_sbpl" respawn="false" />
</group>
</launch>
Deleted: pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage.xml
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage.xml 2008-12-05 23:48:46 UTC (rev 7706)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage.xml 2008-12-06 00:11:46 UTC (rev 7707)
@@ -1,8 +0,0 @@
-
-<launch>
- <master auto="start"/>
- <group name="wg">
- <include file="$(find highlevel_controllers)/test/stage.xml"/>
- </group>
-</launch>
-
Copied: pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage.xml (from rev 7668, pkg/trunk/highlevel/test_highlevel_controllers/test/stage.xml)
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage.xml (rev 0)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage.xml 2008-12-06 00:11:46 UTC (rev 7707)
@@ -0,0 +1,28 @@
+<launch>
+ <master auto="start"/>
+ <group name="wg">
+ <node pkg="rosstage" type="rosstage" name="rosstage" args="$(find 2dnav_stage)/willow-pr2.world" respawn="false" >
+ <param name="base_watchdog_timeout" value="0.2"/>
+ </node>
+ <node pkg="map_server" type="map_server" args="$(find 2dnav_stage)/willow-full.pgm 0.1" respawn="false" />
+
+ <!-- TODO: remove this remap after fake_localization is fixed to listen
+ to base_pose_ground_truth, and gazebo is fixed to publish on that topic -->
+ <remap from="base_pose_gazebo_ground_truth" to="base_pose_ground_truth"/>
+ <param name="max_publish_frequency" value="20.0"/>
+ <node pkg="fake_localization" type="fake_localization" respawn="false" />
+ <node pkg="nav_view" type="nav_view" respawn="false"/>
+
+ <!-- Now launch controller node required -->
+ <include file="$(find test_highlevel_controllers)/test/launch_move_base.xml"/>
+
+ <!-- Set parameters for mailing -->
+ <param name="recharge/email_addresses" value="mc...@wi..."/>
+ <param name="recharge/subject_plugin" value="Robot Needs To Be Plugged In"/>
+ <param name="recharge/subject_unplug" value="Robot Needs To Be Unplugged"/>
+ <param name="recharge/body_plugin" value="Hello, could you please plug me in?\nThanks, PR2"/>
+ <param name="recharge/body_unplug" value="Hello, could you please unplug me?\nThanks, PR2"/>
+ <param name="recharge/mail_client" value="mailx -s"/>
+ <node pkg="highlevel_controllers" type="recharge_controller" args="battery_state:=bogus_battery_state" respawn="true" />
+ </group>
+</launch>
Modified: pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_2.5cm.xml
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_2.5cm.xml 2008-12-05 23:48:46 UTC (rev 7706)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_2.5cm.xml 2008-12-06 00:11:46 UTC (rev 7707)
@@ -1,7 +1,9 @@
<launch>
<master auto="start"/>
<group name="wg">
- <node pkg="rosstage" type="rosstage" args="-g $(find 2dnav_stage)/willow-pr2-2.5cm.world" respawn="false" />
+ <node pkg="rosstage" type="rosstage" name="rosstage" args="-g $(find 2dnav_stage)/willow-pr2-2.5cm.world" respawn="false" >
+ <param name="base_watchdog_timeout" value="0.2"/>
+ </node>
<node pkg="map_server" type="map_server" args="$(find 2dnav_stage)/willow-full-0.025.pgm 0.025" respawn="false" />
<!-- TODO: remove this remap after fake_localization is fixed to listen
Modified: pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_5cm.xml
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_5cm.xml 2008-12-05 23:48:46 UTC (rev 7706)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_5cm.xml 2008-12-06 00:11:46 UTC (rev 7707)
@@ -1,7 +1,9 @@
<launch>
<master auto="start"/>
<group name="wg">
- <node pkg="rosstage" type="rosstage" args="$(find 2dnav_stage)/willow-pr2-5cm.world" respawn="false" />
+ <node pkg="rosstage" type="rosstage" name="rosstage" args="$(find 2dnav_stage)/willow-pr2-5cm.world" respawn="false" >
+ <param name="base_watchdog_timeout" value="0.2"/>
+ </node>
<node pkg="map_server" type="map_server" args="$(find 2dnav_stage)/willow-full-0.05.pgm 0.05" respawn="false" />
<!-- TODO: remove this remap after fake_localization is fixed to listen
Modified: pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_amcl_5cm.xml
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_amcl_5cm.xml 2008-12-05 23:48:46 UTC (rev 7706)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/launch_stage_amcl_5cm.xml 2008-12-06 00:11:46 UTC (rev 7707)
@@ -1,7 +1,9 @@
<launch>
<master auto="start"/>
<group name="wg">
- <node pkg="rosstage" type="rosstage" args="$(find 2dnav_stage)/willow-pr2-5cm.world" respawn="false" />
+ <node pkg="rosstage" type="rosstage" name="rosstage" args="$(find 2dnav_stage)/willow-pr2-5cm.world" respawn="false" >
+ <param name="base_watchdog_timeout" value="0.2"/>
+ </node>
<node pkg="map_server" type="map_server" args="$(find 2dnav_stage)/willow-full-0.05.pgm 0.05" respawn="false" />
<param name="pf_laser_max_beams" value="20"/>
<param name="pf_min_samples" value="500"/>
Deleted: pkg/trunk/highlevel/test_highlevel_controllers/test/stage.xml
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/stage.xml 2008-12-05 23:48:46 UTC (rev 7706)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/stage.xml 2008-12-06 00:11:46 UTC (rev 7707)
@@ -1,21 +0,0 @@
-<launch>
- <!-- Sends robot description data to the param server -->
- <param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/pr2/pr2.xml"" />
-
- <node pkg="rosstage" type="rosstage" args="$(find 2dnav-stage)/willow-erratic.world" respawn="false" />
-
- <node pkg="map_server" type="map_server" args="$(find 2dnav-stage)/willow-full.pgm 0.1" respawn="false" />
-
- <!--node pkg="amcl_player" type="amcl_player" respawn="false" /-->
- <remap from="base_pose_gazebo_ground_truth" to="base_pose_ground_truth"/>
- <param name="max_publish_frequency" value="20.0"/>
- <node pkg="fake_localization" type="fake_localization" respawn="false" />
-
- <param name="move_base/frequency" value="20.0"/>
- <param name="move_base/plannerTimeLimit" value="1.0"/>
- <node pkg="highlevel_controllers" type="move_base_sbpl" respawn="false" />
-
- <node pkg="highlevel_controllers" type="recharge_controller" respawn="false" />
-
- <node pkg="nav_view" type="nav_view" respawn="true"/>
-</launch>
Modified: pkg/trunk/simulators/rosstage/rosstage.cc
===================================================================
--- pkg/trunk/simulators/rosstage/rosstage.cc 2008-12-05 23:48:46 UTC (rev 7706)
+++ pkg/trunk/simulators/rosstage/rosstage.cc 2008-12-06 00:11:46 UTC (rev 7707)
@@ -116,6 +116,13 @@
tf::TransformBroadcaster tf;
+ // Last time that we received a velocity command
+ ros::Time base_last_cmd;
+ ros::Duration base_watchdog_timeout;
+
+ // Current simulation time
+ ros::Time sim_time;
+
public:
// Constructor; stage itself needs argc/argv. fname is the .world file
// that stage should load.
@@ -161,6 +168,7 @@
this->lock.lock();
this->positionmodel->SetSpeed(this->velMsg.vx, this->velMsg.vy, this->velMsg.vw);
+ this->base_last_cmd = this->sim_time;
this->lock.unlock();
}
@@ -171,6 +179,12 @@
this->lasermodel = NULL;
this->positionmodel = NULL;
+ this->sim_time.fromSec(0.0);
+ this->base_last_cmd.fromSec(0.0);
+ double t;
+ param("~base_watchdog_timeout", t, 0.2);
+ this->base_watchdog_timeout.fromSec(t);
+
// initialize libstage
Stg::Init( &argc, &argv );
@@ -229,9 +243,12 @@
// Let the simulator update (it will sleep if there's time)
this->world->Update();
- ros::Time sim_time;
- sim_time.fromSec(world->SimTimeNow() / 1e6);
+ this->sim_time.fromSec(world->SimTimeNow() / 1e6);
+ if((this->base_watchdog_timeout.toSec() > 0.0) &&
+ ((this->sim_time - this->base_last_cmd) >= this->base_watchdog_timeout))
+ this->positionmodel->SetSpeed(0.0, 0.0, 0.0);
+
// Get latest laser data
Stg::stg_laser_sample_t* samples = this->lasermodel->GetSamples();
if(samples)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2008-12-06 02:36:40
|
Revision: 7719
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7719&view=rev
Author: tfoote
Date: 2008-12-06 02:36:34 +0000 (Sat, 06 Dec 2008)
Log Message:
-----------
results from changing ros::Time constructor and all uses of it I can find
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_position_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp
pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp
pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h
pkg/trunk/hardware_test/self_test/include/self_test/self_test.h
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
pkg/trunk/nav/amcl_player/cli.cpp
pkg/trunk/nav/nav_view_sdl/nav_view.cpp
pkg/trunk/nav/wavefront_player/cli.cpp
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
pkg/trunk/util/logsetta/imu/imu_extract.cpp
pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp
pkg/trunk/util/logsetta/odom/odom_extract.cpp
pkg/trunk/util/tf/include/tf/tf.h
pkg/trunk/util/tf/src/cache.cpp
pkg/trunk/util/tf/src/transform_listener.cpp
pkg/trunk/vision/calib_converter/src/calib_converter.cpp
pkg/trunk/vision/stereo_view/stereo_view.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp
pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_position_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_position_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -311,7 +311,7 @@
int ticks=0;
static const double interval=1e-2;
const int max_ticks = int(cmd.timeout/interval);
- ros::Duration d=ros::Duration(interval);
+ ros::Duration d=ros::Duration().fromSec(interval);
while(!(c_->goalAchieved() || ticks >= max_ticks))
{
d.sleep();
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -160,7 +160,7 @@
void BasePositionControllerNode::setPoseCommand(std_msgs::PoseStamped cmd)
{
std_msgs::PoseStamped pose_odom ; // Stores the pose in the odometric frame
- cmd.header.stamp = ros::Time(0.0) ; // Transform using the latest transform
+ cmd.header.stamp = ros::Time(0) ; // Transform using the latest transform
tf_.transformPose(odom_frame_name_, cmd, pose_odom) ;
tf::Quaternion orientation_odom ; // Orientation in the odometric frame
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -222,11 +222,11 @@
point.setX(head_track_point_.point.x);
point.setY(head_track_point_.point.y);
point.setZ(head_track_point_.point.z);
- point.stamp_ =0.0;
+ point.stamp_ =0;
point.frame_id_ = head_track_point_.header.frame_id;
std::string pan_parent;
- TF.getParent("head_pan_link", 0.0, pan_parent);
+ TF.getParent("head_pan_link", 0, pan_parent);
std::string tilt_parent("head_pan_link");
// Pan angle
@@ -282,12 +282,12 @@
point.setX(frame_track_point_.point.x);
point.setY(frame_track_point_.point.y);
point.setZ(frame_track_point_.point.z);
- point.stamp_ = 0.0;//get the latest transform
+ point.stamp_ = 0;//get the latest transform
point.frame_id_ = frame_track_point_.header.frame_id;
try
{
- TF.lookupTransform(point.frame_id_,"head_pan_link",ros::Time(0.0),frame);
+ TF.lookupTransform(point.frame_id_,"head_pan_link",ros::Time(0),frame);
}
catch(tf::TransformException& ex)
{
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -304,7 +304,7 @@
try
{
- TF.lookupTransform(point.frame_id_,"head_pan",ros::Time(0.0),frame);
+ TF.lookupTransform(point.frame_id_,"head_pan",ros::Time(0),frame);
}
catch(tf::TransformException& ex)
{
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -85,7 +85,7 @@
sleep(4);
ros::Time start_time = ros::Time::now();
- ros::Duration sleep_time(0.01);
+ ros::Duration sleep_time = ros::Duration().fromSec(0.01);
/* while(!done)
{
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -121,7 +121,7 @@
: robot_(NULL), pos_publisher_(NULL), TF(*ros::node::instance(), false) , loop_count_(0)
{
assert(ros::node::instance());
- TF.setExtrapolationLimit(ros::Duration(10.0e-3));
+ TF.setExtrapolationLimit(ros::Duration().fromSec(10.0e-3));
}
CartesianOrientationControllerNode::~CartesianOrientationControllerNode()
@@ -179,7 +179,7 @@
{
if (pos_publisher_->trylock())
{
- pos_publisher_->msg_.header.stamp = robot_->hw_->current_time_;
+ pos_publisher_->msg_.header.stamp.fromSec(robot_->hw_->current_time_);
pos_publisher_->msg_.header.frame_id = c_.rootFrame();
tf::Quaternion q;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -120,7 +120,7 @@
: robot_(NULL), pos_publisher_(NULL), TF(*ros::node::instance(), false) , loop_count_(0)
{
assert(ros::node::instance());
- TF.setExtrapolationLimit(ros::Duration(10.0e-3));
+ TF.setExtrapolationLimit(ros::Duration(10000000));
}
CartesianPositionControllerNode::~CartesianPositionControllerNode()
@@ -179,7 +179,7 @@
{
if (pos_publisher_->trylock())
{
- pos_publisher_->msg_.header.stamp = robot_->hw_->current_time_;
+ pos_publisher_->msg_.header.stamp.fromSec(robot_->hw_->current_time_);
pos_publisher_->msg_.header.frame_id = c_.rootFrame();
tf::Point p;
Modified: pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp
===================================================================
--- pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/drivers/cam/dc1394_cam_server/src/dc1394_cam_server/dc1394_cam_server.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -412,7 +412,7 @@
{
dc1394_cam::FrameSet fs = cd.cam->getFrames(DC1394_CAPTURE_POLICY_POLL);
- ros::Time ts = ros::Time::now() + ros::Duration(-.125);
+ ros::Time ts = ros::Time::now() + ros::Duration().fromSec(-.125);
if (fs.size() > 0)
{
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -104,7 +104,7 @@
PointCloudAssembler() : ros::node("point_cloud_assembler"), tf_(*this)
{
- tf_.setExtrapolationLimit(ros::Duration(1.0)) ;
+ tf_.setExtrapolationLimit(ros::Duration().fromSec(1.0)) ;
advertise_service("build_cloud", &PointCloudAssembler::buildCloud, this, 0) ; // Don't spawn threads so that we can avoid dealing with mutexing [for now]
subscribe("scan", scan_, &PointCloudAssembler::scans_callback, 40) ;
Modified: pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
===================================================================
--- pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -296,7 +296,7 @@
// broadcast most recent estimate to TransformArray
Stamped<Transform> tmp;
- my_filter_.getEstimate(0.0, tmp);
+ my_filter_.getEstimate(0, tmp);
odom_broadcaster_.sendTransform(Stamped<Transform>(tmp.inverse(), tmp.stamp_, "odom_combined", "base_footprint"));
#ifdef __EKF_DEBUG_FILE__
Modified: pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp
===================================================================
--- pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -68,7 +68,7 @@
virtual void processData() = 0;
virtual bool loadData(std::string filename) {
- if (!mLp.open(filename, ros::Time(0.0))) return false;
+ if (!mLp.open(filename, ros::Time(0))) return false;
mLp.addHandler<OctreeLearningMsg>(std::string("grasp_learning_bus"),
©Msg<OctreeLearningMsg>, (void*)this, true);
mNewMsg = false;
Modified: pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h
===================================================================
--- pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h 2008-12-06 02:36:34 UTC (rev 7719)
@@ -66,7 +66,7 @@
((ros::node*)(node_))->advertise<robot_msgs::DiagnosticMessage>("/diagnostics", 1);
node_->param("~diagnostic_period", period_, 1.0);
- next_time_ = ros::Time::now() + ros::Duration(period_);
+ next_time_ = ros::Time::now() + ros::Duration().fromSec(period_);
}
void addUpdater(void (T::*f)(robot_msgs::DiagnosticStatus&))
@@ -112,7 +112,7 @@
}
node_->param("~diagnostic_period", period_, 1.0);
- next_time_ = ros::Time::now() + ros::Duration(period_);
+ next_time_ = ros::Time::now() + ros::Duration().fromSec(period_);
}
double getPeriod()
Modified: pkg/trunk/hardware_test/self_test/include/self_test/self_test.h
===================================================================
--- pkg/trunk/hardware_test/self_test/include/self_test/self_test.h 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/hardware_test/self_test/include/self_test/self_test.h 2008-12-06 02:36:34 UTC (rev 7719)
@@ -130,7 +130,7 @@
while (!ready)
{
- if (!testing_condition.timed_wait(ros::Duration(5.0)))
+ if (!testing_condition.timed_wait(ros::Duration().fromSec(5.0)))
{
printf("Timed out waiting to run self test.\n");
waiting = false;
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-12-06 02:36:34 UTC (rev 7719)
@@ -190,7 +190,7 @@
void waitForState(void)
{
while (m_node->ok() && (m_haveState ^ loadedRobot()))
- ros::Duration(0.05).sleep();
+ ros::Duration().fromSec(0.05).sleep();
}
protected:
Modified: pkg/trunk/nav/amcl_player/cli.cpp
===================================================================
--- pkg/trunk/nav/amcl_player/cli.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/nav/amcl_player/cli.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -31,8 +31,8 @@
ros::init(argc, argv);
AmclCLI amcl_cli;
ros::Time t_start(ros::Time::now());
- while (amcl_cli.ok() && ros::Time::now() - t_start < 2.0 && !amcl_cli.done)
- ros::Duration(0.1).sleep();
+ while (amcl_cli.ok() && ros::Time::now() - t_start < ros::Duration().fromSec(2.0) && !amcl_cli.done)
+ ros::Duration().fromSec(0.1).sleep();
if (!amcl_cli.done)
printf("failed\n");
ros::fini();
Modified: pkg/trunk/nav/nav_view_sdl/nav_view.cpp
===================================================================
--- pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -355,7 +355,7 @@
tf::Stamped<tf::Pose> robotPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time(0.0);
+ robotPose.stamp_ = ros::Time(0);
tf::Stamped<tf::Pose> mapPose ;
tf.transformPose("map", robotPose, mapPose );
Modified: pkg/trunk/nav/wavefront_player/cli.cpp
===================================================================
--- pkg/trunk/nav/wavefront_player/cli.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/nav/wavefront_player/cli.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -32,7 +32,7 @@
{
wf_goal.enable = 0;
publish("goal", wf_goal);
- ros::Duration(0.5).sleep(); // hack to try and wait for the message to go
+ ros::Duration().fromSec(0.5).sleep(); // hack to try and wait for the message to go
}
virtual void peer_subscribe(const std::string &topic_name,
ros::pub_sub_conn * const psc)
@@ -57,8 +57,8 @@
WavefrontCLI wf_cli(atof(argv[1]), atof(argv[2]), atof(argv[3]));
ros::Time t_start(ros::Time::now());
while (wf_cli.ok() && wf_cli.state != WavefrontCLI::WF_DONE &&
- ros::Time::now() - t_start < max_secs)
- ros::Duration(0.1).sleep();
+ ros::Time::now() - t_start < ros::Duration().fromSec(max_secs))
+ ros::Duration().fromSec(0.1).sleep();
if (wf_cli.ok() && wf_cli.state != WavefrontCLI::WF_DONE) // didn't get there
{
printf("timeout\n");
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-06 02:36:34 UTC (rev 7719)
@@ -279,7 +279,7 @@
ang_eps(DTOR(4.0)),
cycletime(0.1),
laser_maxrange(4.0),
- laser_buffer_time(3.0),
+ laser_buffer_time(3000000000LL),
lookahead_maxdist(2.0),
lookahead_distweight(5.0),
tvmin(0.2),
@@ -288,8 +288,7 @@
avmax(DTOR(80.0)),
amin(DTOR(10.0)),
amax(DTOR(40.0)),
- tf(*this, true, (uint64_t)10000000000ULL)// cache for 10 sec, no extrapolation
- //tf(*this, true, (uint64_t)200000000ULL, (uint64_t)200000000ULL) //nanoseconds
+ tf(*this, true, 10000000000ULL) // cache for 10 sec, no extrapolation
{
// Initialize global pose. Will be set in control loop based on actual data.
///\todo does this need to be initialized? global_pose.setIdentity();
Modified: pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
===================================================================
--- pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -125,7 +125,7 @@
for (int i = 1; i < argc; i++)
files.push_back(argv[i]);
- player.open(files, ros::Time(0.0));
+ player.open(files, ros::Time(0));
player.addHandler<std_msgs::RobotBase2DOdom>(string("*"), &odom_callback, NULL);
player.addHandler<std_msgs::LaserScan>(string("*"), &scan_callback, NULL);
Modified: pkg/trunk/util/logsetta/imu/imu_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/imu/imu_extract.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/logsetta/imu/imu_extract.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -57,7 +57,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0.0));
+ player.open(std::string(argv[1]), ros::Time(0));
int count;
Modified: pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -57,7 +57,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0.0));
+ player.open(std::string(argv[1]), ros::Time(0));
int count;
Modified: pkg/trunk/util/logsetta/odom/odom_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/odom/odom_extract.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/logsetta/odom/odom_extract.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -62,7 +62,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0.0));
+ player.open(std::string(argv[1]), ros::Time(0));
int count;
Modified: pkg/trunk/util/tf/include/tf/tf.h
===================================================================
--- pkg/trunk/util/tf/include/tf/tf.h 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/tf/include/tf/tf.h 2008-12-06 02:36:34 UTC (rev 7719)
@@ -80,9 +80,9 @@
{
public:
/************* Constants ***********************/
- static const unsigned int MAX_GRAPH_DEPTH = 100; //!< The maximum number of time to recurse before assuming the tree has a loop.
- static const int64_t DEFAULT_CACHE_TIME = 10 * 1000000000ULL; //!< The default amount of time to cache data
- static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0; //!< The default amount of time to extrapolate
+ static const unsigned int MAX_GRAPH_DEPTH = 100UL; //!< The maximum number of time to recurse before assuming the tree has a loop.
+ static const int64_t DEFAULT_CACHE_TIME = 10ULL * 1000000000ULL; //!< The default amount of time to cache data
+ static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL; //!< The default amount of time to extrapolate
/** Constructor
@@ -91,7 +91,7 @@
*
*/
Transformer(bool interpolating = true,
- ros::Duration cache_time_ = ros::Duration(DEFAULT_CACHE_TIME));
+ ros::Duration cache_time_ = ros::Duration().fromNSec(DEFAULT_CACHE_TIME));
virtual ~Transformer(void);
/** \brief Clear all data */
Modified: pkg/trunk/util/tf/src/cache.cpp
===================================================================
--- pkg/trunk/util/tf/src/cache.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/tf/src/cache.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -88,7 +88,7 @@
}
//If time == 0 return the latest
- if (target_time == ros::Time(0.0))
+ if (target_time == ros::Time(0))
{
one = storage_.front();
mode = ONE_VALUE;
Modified: pkg/trunk/util/tf/src/transform_listener.cpp
===================================================================
--- pkg/trunk/util/tf/src/transform_listener.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/util/tf/src/transform_listener.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -202,7 +202,7 @@
// Extract transforms for the beginning and end of the laser scan
ros::Time start_time = scanIn.header.stamp ;
- ros::Time end_time = scanIn.header.stamp + ros::Duration(scanIn.get_ranges_size()*scanIn.time_increment) ;
+ ros::Time end_time = scanIn.header.stamp + ros::Duration().fromSec(scanIn.get_ranges_size()*scanIn.time_increment) ;
tf::Stamped<tf::Transform> start_transform ;
tf::Stamped<tf::Transform> end_transform ;
Modified: pkg/trunk/vision/calib_converter/src/calib_converter.cpp
===================================================================
--- pkg/trunk/vision/calib_converter/src/calib_converter.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/vision/calib_converter/src/calib_converter.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -81,7 +81,7 @@
// -- Load the messages.
- lp.open(fullname, ros::Time(0.0));
+ lp.open(fullname, ros::Time(0));
lp.addHandler<std_msgs::ImageArray>(string("videre/images"), ©Msg<std_msgs::ImageArray>, (void*)(&image_msg), true);
lp.addHandler<std_msgs::String>(string("videre/cal_params"), ©Msg<std_msgs::String>, (void*)(&calparams), true);
lp.addHandler<std_msgs::PointCloud>(string("full_cloud"), ©Msg<std_msgs::PointCloud>, (void*)(&cloud), true);
Modified: pkg/trunk/vision/stereo_view/stereo_view.cpp
===================================================================
--- pkg/trunk/vision/stereo_view/stereo_view.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/vision/stereo_view/stereo_view.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -78,7 +78,7 @@
StereoView() : ros::node("stereo_view"),
lcal(this), rcal(this), lcalimage(NULL), rcalimage(NULL),
- sync(this, &StereoView::image_cb_all, ros::Duration(0.05), &StereoView::image_cb_timeout),
+ sync(this, &StereoView::image_cb_all, ros::Duration().fromSec(0.05), &StereoView::image_cb_timeout),
subscribe_color_(false), calib_color_(false), recompand_(false)
{
cvNamedWindow("left", CV_WINDOW_AUTOSIZE);
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -69,8 +69,8 @@
, vis_panel_( panel )
, needs_reset_( false )
, new_ros_time_( false )
-, wall_clock_begin_( 0.0 )
-, ros_time_begin_( 0.0 )
+, wall_clock_begin_( 0 )
+, ros_time_begin_( 0 )
{
initializeCommon();
registerFactories( this );
@@ -234,8 +234,8 @@
resetDisplays();
tf_->clear();
- ros_time_begin_ = ros::Time( 0.0 );
- wall_clock_begin_ = ros::Time( 0.0 );
+ ros_time_begin_ = ros::Time( 0 );
+ wall_clock_begin_ = ros::Time( 0 );
}
static float time_update_timer = 0.0f;
Modified: pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp
===================================================================
--- pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -13,7 +13,7 @@
cout << "Loading messages... "; flush(cout);
- lp.open(file, ros::Time(0.0));
+ lp.open(file, ros::Time(0));
lp.addHandler<std_msgs::ImageArray>(string("videre/images"), ©Msg<std_msgs::ImageArray>, (void*)(&images_msg_), true);
lp.addHandler<std_msgs::ImageArray>(string("labeled_images"), ©Msg<std_msgs::ImageArray>, (void*)(&labeled_images_msg_), true);
lp.addHandler<std_msgs::PointCloud>(ptcld_topic_, ©Msg<std_msgs::PointCloud>, (void*)(&cloud_), true);
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-06 02:22:14 UTC (rev 7718)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-06 02:36:34 UTC (rev 7719)
@@ -227,7 +227,8 @@
void publishDataThread(void)
{
- ros::Duration *d = new ros::Duration(1.0/m_maxPublishFrequency);
+ ros::Duration *d = new ros::Duration();
+ d->fromSec(1.0/m_maxPublishFrequency);
/* Pump out buffered, filtered point clouds and clear the buffer */
while (m_active)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tpr...@us...> - 2008-12-06 03:28:48
|
Revision: 7721
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7721&view=rev
Author: tpratkanis
Date: 2008-12-06 03:28:44 +0000 (Sat, 06 Dec 2008)
Log Message:
-----------
Make world_3d_map create point clouds: a change needed for fixing arm demos.
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-12-06 02:51:27 UTC (rev 7720)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-12-06 03:28:44 UTC (rev 7721)
@@ -88,7 +88,7 @@
public:
- NodeRobotModel(ros::node *node, const std::string &robot_model) : m_tf(*node, true, 1 * 1000000000ULL, 0ULL)
+ NodeRobotModel(ros::node *node, const std::string &robot_model) : m_tf(*node, true, 1 * 1000000000ULL, 1000000000ULL)
{
m_urdf = NULL;
m_kmodel = NULL;
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-06 02:51:27 UTC (rev 7720)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-06 03:28:44 UTC (rev 7721)
@@ -147,7 +147,7 @@
/* Set up the transform client */
double laser_x_offset;
param("laser_x_offset", laser_x_offset, 0.275);
- m_tf.setWithEulers("base_laser", "base", laser_x_offset, 0.0, 0.0, 0.0, 0.0, 0.0, 0);
+ m_tf.setWithEulers("base_laser", "base_link", laser_x_offset, 0.0, 0.0, 0.0, 0.0, 0.0, 0);
/* create a thread that handles the publishing of the data */
m_publishingThread = ros::thread::member_thread::startMemberFunctionThread<World3DMap>(this, &World3DMap::publishDataThread);
@@ -193,7 +193,7 @@
{
if(!m_robotState)
{
- //ROS_WARN("Ignoring state update because I haven't yet received the robot description");
+ ROS_WARN("Ignoring state update because I haven't yet received the robot description");
return;
}
//m_robotState->print();
@@ -224,17 +224,64 @@
m_projector.projectLaser(m_baseScanMsg, local_cloud, m_baseLaserMaxRange);
processData(local_cloud);
}
-
+
+
void publishDataThread(void)
{
ros::Duration *d = new ros::Duration();
d->fromSec(1.0/m_maxPublishFrequency);
+
+ /* while everything else is running (map building) check if
+ there are any updates to send, but do so at most at the
+ maximally allowed frequency of sending data */
+ while (m_active)
+ {
+ d->sleep();
- /* Pump out buffered, filtered point clouds and clear the buffer */
+ m_worldDataMutex.lock();
+ if (m_active && m_currentWorld.size() > 0)
+ {
+ std_msgs::PointCloud toPublish;
+ toPublish.header = m_currentWorld.back()->header;
+
+ unsigned int npts = 0;
+ for (unsigned int i = 0 ; i < m_currentWorld.size() ; ++i)
+ npts += m_currentWorld[i]->get_pts_size();
+
+ toPublish.set_pts_size(npts);
+
+ unsigned int j = 0;
+ for (unsigned int i = 0 ; i < m_currentWorld.size() ; ++i)
+ {
+ unsigned int n = m_currentWorld[i]->get_pts_size();
+ for (unsigned int k = 0 ; k < n ; ++k)
+ toPublish.pts[j++] = m_currentWorld[i]->pts[k];
+ }
+
+ toPublish.set_pts_size(j);
+ if (ok())
+ {
+ if (m_verbose)
+ ROS_INFO("Publishing a point cloud with %u points\n", toPublish.get_pts_size());
+ publish("world_3d_map", toPublish);
+ }
+ }
+ m_worldDataMutex.unlock();
+ }
+ delete d;
+ }
+
+ /*void publishDataThread(void)
+ {
+ ros::Duration *d = new ros::Duration(1.0/m_maxPublishFrequency);
+
+ /* Pump out buffered, filtered point clouds and clear the buffer
while (m_active)
{
+ ROS_INFO("Loop\n");
for(unsigned int i = 0; i < m_currentWorld.size(); i++){
std_msgs::PointCloud* p = m_currentWorld[i];
+ ROS_INFO("Publish\n");
publish("world_3d_map", *p);
delete p;
}
@@ -245,7 +292,7 @@
}
delete d;
- }
+ }*/
void addSelfSeeBodies(void)
{
@@ -309,6 +356,7 @@
void processData(const std_msgs::PointCloud& local_cloud)
{
if (!m_acceptScans){
+ ROS_INFO("Rejecting scans\n");
return;
}
@@ -320,11 +368,6 @@
const std_msgs::PointCloud& point_cloud = point_clouds_.front();
- //make sure that we don't fall to far in the past
- if(ros::Time::now() - point_cloud.header.stamp > ros::Duration(9, 0)){
- point_clouds_.pop_front();
- continue;
- }
std_msgs::PointCloud map_cloud;
@@ -340,7 +383,7 @@
}
catch(libTF::TransformReference::ExtrapolateException& ex)
{
- //ROS_ERROR("Extrapolation exception: %s\n", ex.what());
+ ROS_ERROR("Extrapolation exception: %s\n", ex.what());
break;
}
catch(libTF::TransformReference::ConnectivityException& ex)
@@ -406,7 +449,7 @@
copy->pts[j++] = cloud.pts[k];
copy->set_pts_size(j);
- ROS_DEBUG("Filter 0 discarded %d points (%d left) \n", n - j, j);
+ ROS_INFO("Filter 0 discarded %d points (%d left) \n", n - j, j);
return copy;
}
@@ -443,7 +486,7 @@
}
}
- ROS_DEBUG("Filter 1 discarded %d points (%d left) \n", n - j, j);
+ ROS_INFO("Filter 1 discarded %d points (%d left) \n", n - j, j);
copy->set_pts_size(j);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <rdi...@us...> - 2008-12-06 18:39:21
|
Revision: 7733
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7733&view=rev
Author: rdiankov
Date: 2008-12-06 18:39:11 +0000 (Sat, 06 Dec 2008)
Log Message:
-----------
progress towards openrave session server
Modified Paths:
--------------
pkg/trunk/3rdparty/openrave/Makefile
pkg/trunk/openrave_planning/openraveros/src/openraveros.h
pkg/trunk/openrave_planning/openraveros/src/rosserver.h
pkg/trunk/openrave_planning/openraveros/src/session.h
pkg/trunk/openrave_planning/openraveros/srv/body_enable.srv
pkg/trunk/openrave_planning/openraveros/srv/body_setjointvalues.srv
pkg/trunk/openrave_planning/openraveros/srv/env_checkcollision.srv
pkg/trunk/openrave_planning/openraveros/srv/env_createproblem.srv
pkg/trunk/openrave_planning/openraveros/srv/env_loadplugin.srv
pkg/trunk/openrave_planning/openraveros/srv/env_loadscene.srv
pkg/trunk/openrave_planning/openraveros/srv/env_plot.srv
pkg/trunk/openrave_planning/openraveros/srv/env_raycollision.srv
pkg/trunk/openrave_planning/openraveros/srv/env_set.srv
pkg/trunk/openrave_planning/openraveros/srv/env_triangulate.srv
pkg/trunk/openrave_planning/openraveros/srv/env_wait.srv
pkg/trunk/openrave_planning/openraveros/srv/openrave_session.srv
pkg/trunk/openrave_planning/openraveros/srv/planner_init.srv
pkg/trunk/openrave_planning/openraveros/srv/problem_sendcommand.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_controllersend.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_controllerset.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_sensorsend.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_setactivevalues.srv
pkg/trunk/openrave_planning/orrosplanning/src/orrosplanningmain.cpp
Modified: pkg/trunk/3rdparty/openrave/Makefile
===================================================================
--- pkg/trunk/3rdparty/openrave/Makefile 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/3rdparty/openrave/Makefile 2008-12-06 18:39:11 UTC (rev 7733)
@@ -2,7 +2,7 @@
SVN_DIR = openrave_svn
# Should really specify a revision
-SVN_REVISION = -r 527
+SVN_REVISION = -r 532
SVN_URL = https://openrave.svn.sourceforge.net/svnroot/openrave
include $(shell rospack find mk)/svn_checkout.mk
Modified: pkg/trunk/openrave_planning/openraveros/src/openraveros.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/openraveros.h 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/src/openraveros.h 2008-12-06 18:39:11 UTC (rev 7733)
@@ -39,6 +39,7 @@
#include <boost/typeof/std/vector.hpp>
#include <boost/typeof/std/list.hpp>
#include <boost/typeof/std/map.hpp>
+#include <boost/typeof/std/set.hpp>
#include <boost/typeof/std/string.hpp>
#define FOREACH(it, v) for(BOOST_TYPEOF(v)::iterator it = (v).begin(); it != (v).end(); (it)++)
@@ -50,6 +51,7 @@
#include <vector>
#include <list>
#include <map>
+#include <set>
#include <string>
#define FOREACH(it, v) for(typeof((v).begin()) it = (v).begin(); it != (v).end(); (it)++)
Modified: pkg/trunk/openrave_planning/openraveros/src/rosserver.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/rosserver.h 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/src/rosserver.h 2008-12-06 18:39:11 UTC (rev 7733)
@@ -28,6 +28,16 @@
class ROSServer : public RaveServerBase
{
+ class LockEnvironment
+ {
+ public:
+ LockEnvironment(ROSServer* pserv) : _pserv(pserv) { _pserv->_penv->LockPhysics(true); }
+ ~LockEnvironment() { _pserv->_penv->LockPhysics(false); }
+
+ private:
+ ROSServer* _pserv;
+ };
+
public:
ROSServer(boost::shared_ptr<EnvironmentBase> penv) : RaveServerBase(penv.get()), _nNextFigureId(1), _nNextPlannerId(1) {
_penv = penv;
@@ -60,15 +70,9 @@
virtual void Reset()
{
-
-// pthread_mutex_lock(&_mutexWorker);
-// listWorkers.clear();
-// pthread_mutex_unlock(&_mutexWorker);
-// pthread_cond_signal(&_condWorker);
-//
-// FOREACH(it, s_mapFigureIds)
-// g_Environ.closegraph(it->second);
-// s_mapFigureIds.clear();
+ FOREACH(it, _mapFigureIds)
+ _penv->closegraph(it->second);
+ _mapFigureIds.clear();
// destroy environment specific state: problems, planners, figures
_mapplanners.clear();
@@ -95,17 +99,86 @@
return false;
}
- // called from threads other than the main worker to wait until
- virtual void SyncWithWorkerThread()
+ bool body_destroy_srv(body_destroy::request& req, body_destroy::response& res)
{
+ KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+
+ LockEnvironment envlock(this);
+ return _penv->RemoveKinBody(pbody,true);
}
- bool body_destroy_srv(body_destroy::request& req, body_destroy::response& res);
- bool body_enable_srv(body_enable::request& req, body_enable::response& res);
- bool body_getaabb_srv(body_getaabb::request& req, body_getaabb::response& res);
- bool body_getaabbs_srv(body_getaabbs::request& req, body_getaabbs::response& res);
- bool body_getdof_srv(body_getdof::request& req, body_getdof::response& res);
- bool body_getlinks_srv(body_getlinks::request& req, body_getlinks::response& res);
+ bool body_enable_srv(body_enable::request& req, body_enable::response& res)
+ {
+ KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+
+ LockEnvironment envlock(this);
+ pbody->Enable(req.enable);
+ return true;
+ }
+
+ bool body_getaabb_srv(body_getaabb::request& req, body_getaabb::response& res)
+ {
+ KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+
+ LockEnvironment envlock(this);
+ OpenRAVE::AABB ab = pbody->ComputeAABB();
+ res.box.center[0] = ab.pos.x; res.box.center[1] = ab.pos.y; res.box.center[2] = ab.pos.z;
+ res.box.extents[0] = ab.extents.x; res.box.extents[1] = ab.extents.y; res.box.extents[2] = ab.extents.z;
+ return true;
+ }
+
+ bool body_getaabbs_srv(body_getaabbs::request& req, body_getaabbs::response& res)
+ {
+ KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+
+ LockEnvironment envlock(this);
+ res.set_boxes_size(pbody->GetLinks().size()); int index = 0;
+ FOREACHC(itlink, pbody->GetLinks()) {
+ OpenRAVE::AABB ab = (*itlink)->ComputeAABB();
+ openraveros::AABB& resbox = res.boxes[index++];
+ resbox.center[0] = ab.pos.x; resbox.center[1] = ab.pos.y; resbox.center[2] = ab.pos.z;
+ resbox.extents[0] = ab.extents.x; resbox.extents[1] = ab.extents.y; resbox.extents[2] = ab.extents.z;
+ }
+ }
+
+ bool body_getdof_srv(body_getdof::request& req, body_getdof::response& res)
+ {
+ KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+ LockEnvironment envlock(this);
+ res.dof = pbody->GetDOF();
+ return true;
+ }
+
+ bool body_getlinks_srv(body_getlinks::request& req, body_getlinks::response& res)
+ {
+ KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+
+ LockEnvironment envlock(this);
+ vector<Transform> vtrans; pbody->GetBodyTransformations(vtrans);
+
+ res.set_links_size(vtrans.size()); int index = 0;
+ FOREACH(ittrans, vtrans) {
+ TransformMatrix tm = TransformMatrix(*ittrans);
+ AffineTransformMatrix& am = res.links[index++];
+ am.transform[0] = tm.m[0]; am.transform[3] = tm.m[1]; am.transform[6] = tm.m[2];
+ am.transform[1] = tm.m[4]; am.transform[4] = tm.m[5]; am.transform[7] = tm.m[6];
+ am.transform[2] = tm.m[8]; am.transform[5] = tm.m[9]; am.transform[8] = tm.m[10];
+ am.transform[9] = tm.trans.x; am.transform[10] = tm.trans.y; am.transform[11] = tm.trans.z;
+ }
+ }
+
bool body_setjointvalues_srv(body_setjointvalues::request& req, body_setjointvalues::response& res);
bool body_settransform_srv(body_settransform::request& req, body_settransform::response& res);
bool env_checkcollision_srv(env_checkcollision::request& req, env_checkcollision::response& res);
Modified: pkg/trunk/openrave_planning/openraveros/src/session.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/session.h 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/src/session.h 2008-12-06 18:39:11 UTC (rev 7733)
@@ -56,6 +56,7 @@
public:
SessionServer() {
+ _pParentEnvironment.reset(CreateEnvironment());
}
virtual ~SessionServer() {
Destroy();
@@ -194,6 +195,7 @@
private:
map<int,SessionState> _mapsessions;
boost::mutex _mutexsession;
+ boost::shared_ptr<EnvironmentBase> _pParentEnvironment;
SessionState getstate(int sessionid)
{
@@ -222,21 +224,23 @@
id = rand();
SessionState state;
- state._penv.reset(CreateEnvironment());
state._pserver.reset(new ROSServer(state._penv));
if( req.clone_sessionid ) {
// clone the environment from clone_sessionid
SessionState state = getstate(req.clone_sessionid);
- if( !state._penv ) {
- RAVEPRINT(L"failed to find session %d\n", req.clone_sessionid);
- }
- else {
- // clone
-
- }
+ if( !state._penv )
+ ROS_INFO("failed to find session %d\n", req.clone_sessionid);
+ else
+ state._penv.reset(state._penv->CloneSelf(req.clone_options));
}
+ if( !state._penv ) {
+ // cloning from parent
+ ROS_DEBUG("cloning from parent\n");
+ state._penv.reset(_pParentEnvironment->CloneSelf(0));
+ }
+
_mapsessions[id] = state;
res.sessionid = id;
@@ -284,6 +288,11 @@
};
// check that message constants match OpenRAVE constants
+BOOST_STATIC_ASSERT(EnvironmentBase::Clone_Bodies==openrave_session::request::CloneBodies);
+BOOST_STATIC_ASSERT(EnvironmentBase::Clone_Viewer==openrave_session::request::CloneViewer);
+BOOST_STATIC_ASSERT(EnvironmentBase::Clone_Simulation==openrave_session::request::CloneSimulation);
+BOOST_STATIC_ASSERT(EnvironmentBase::Clone_RealControllers==openrave_session::request::CloneRealControllers);
+
BOOST_STATIC_ASSERT(ActiveDOFs::DOF_X==RobotBase::DOF_X);
BOOST_STATIC_ASSERT(ActiveDOFs::DOF_Y==RobotBase::DOF_Y);
BOOST_STATIC_ASSERT(ActiveDOFs::DOF_Z==RobotBase::DOF_Z);
Modified: pkg/trunk/openrave_planning/openraveros/srv/body_enable.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/body_enable.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/body_enable.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -3,5 +3,5 @@
string sessionname
int32 sessionid
uint32 bodyid
-byte enable
+uint8 enable
---
Modified: pkg/trunk/openrave_planning/openraveros/srv/body_setjointvalues.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/body_setjointvalues.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/body_setjointvalues.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -5,5 +5,5 @@
uint32 bodyid
float32[] jointvalues
# optional array specifying the indices to set
-byte[] indices
+uint8[] indices
---
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_checkcollision.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_checkcollision.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_checkcollision.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -5,7 +5,7 @@
uint32 bodyid
# the link of the body to check collision again, if -1 check all links
-byte linkid
+uint8 linkid
uint32[] excludedbodyids
@@ -13,15 +13,15 @@
float32 tolerance
# optional collision checker options, affects what information is sent back
-byte options
+uint8 options
-byte CO_Distance=1
-byte CO_UseTolerance=2
-byte CO_Contacts=4
-byte CO_RayAnyHit=8
+uint8 CO_Distance=1
+uint8 CO_UseTolerance=2
+uint8 CO_Contacts=4
+uint8 CO_RayAnyHit=8
---
-byte collision
+uint8 collision
uint32 collidingbodyid
Contact[] contacts
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_createproblem.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_createproblem.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_createproblem.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -7,6 +7,6 @@
string args
# if true, will destroy any problems with similar types (default is 1)
-byte destroyduplicates
+uint8 destroyduplicates
---
uint32 problemid
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_loadplugin.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_loadplugin.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_loadplugin.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -5,4 +5,4 @@
# absolute path of plugin recommended
string filename
---
-byte success
+uint8 success
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_loadscene.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_loadscene.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_loadscene.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -5,4 +5,4 @@
# absolute path of scene recommended, specifying an empty string resets the entire scene
string filename
---
-byte success
+uint8 success
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_plot.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_plot.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_plot.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -14,10 +14,10 @@
# [0,1] transparency of object (0 is opaque)
float32 transparency
-byte drawtype
+uint8 drawtype
-byte Draw_Point=0 # default
-byte Draw_LineStrip=1
-byte Draw_LineList=2
-byte Draw_TriList=3
-byte Draw_Sphere=4
+uint8 Draw_Point=0 # default
+uint8 Draw_LineStrip=1
+uint8 Draw_LineList=2
+uint8 Draw_TriList=3
+uint8 Draw_Sphere=4
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_raycollision.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_raycollision.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_raycollision.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -8,9 +8,9 @@
uint32 bodyid
# if 1 will also return the contacts points of each of the rays (default is 0)
-byte request_contacts
+uint8 request_contacts
---
# collision - N dim vector that is 1 for colliding rays and 0 otherwise
-byte[] collision
+uint8[] collision
Contact[] contacts
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_set.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_set.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_set.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -12,16 +12,16 @@
uint32 Set_Viewer=64
# validity depending on setmask
-byte sim_action
-byte SimAction_Start=1
-byte SimAction_Stop=2
-byte SimAction_Timestep=3
+uint8 sim_action
+uint8 SimAction_Start=1
+uint8 SimAction_Stop=2
+uint8 SimAction_Timestep=3
float32 sim_timestep
string physicsengine
string collisionchecker
string viewer
float32[3] gravity
-byte publishanytime
-byte debuglevel
+uint8 publishanytime
+uint8 debuglevel
---
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_triangulate.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_triangulate.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_triangulate.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -5,7 +5,7 @@
# if 1, will only triangulate the bodies pointed to by ids
# if 0, will triangulate all objects except the bodies pointed to by ids (default)
# To triangulate everything, just set inclusive to 0 and have empty bodyids
-byte inclusive
+uint8 inclusive
uint32[] bodyids
---
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_wait.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_wait.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_wait.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -13,4 +13,4 @@
---
# will return with success set to 0 if robot did not finish its commands by the timeout.
-byte success
+uint8 success
Modified: pkg/trunk/openrave_planning/openraveros/srv/openrave_session.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/openrave_session.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/openrave_session.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -9,9 +9,12 @@
int32 clone_sessionid
# mask of Clone* options
-byte clone_options
+uint8 clone_options
-byte CloneBodies=1 # copy all bodies
+uint8 CloneBodies=1 # copy all bodies
+uint8 CloneViewer=2 # copy current viewer
+uint8 CloneSimulation=4 # copy simulation settings
+uint8 CloneRealControllers=8 # copy real robot controllers
---
int32 sessionid
Modified: pkg/trunk/openrave_planning/openraveros/srv/planner_init.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/planner_init.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/planner_init.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -6,4 +6,4 @@
uint32 robotid
PlannerParameters params
---
-byte success
+uint8 success
Modified: pkg/trunk/openrave_planning/openraveros/srv/problem_sendcommand.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/problem_sendcommand.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/problem_sendcommand.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -10,7 +10,7 @@
# If 1, the SendCommand is called in the main thread, in sync
# with the rest of the primitives. If 0, called in a different thread. (default is 1)
-byte sync
+uint8 sync
---
# the concatenated output of all the problems that the command is sent to
string output
Modified: pkg/trunk/openrave_planning/openraveros/srv/robot_controllersend.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/robot_controllersend.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/robot_controllersend.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -8,4 +8,4 @@
string cmd
---
# 1 if command was accepted, 0 if not
-byte success
+uint8 success
Modified: pkg/trunk/openrave_planning/openraveros/srv/robot_controllerset.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/robot_controllerset.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/robot_controllerset.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -10,4 +10,4 @@
# the arguments to ControllerBase::Init
string controllerargs
---
-byte success
+uint8 success
Modified: pkg/trunk/openrave_planning/openraveros/srv/robot_sensorsend.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/robot_sensorsend.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/robot_sensorsend.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -10,7 +10,7 @@
uint32 sensorindex
string cmd
---
-byte success
+uint8 success
# output of the command
string out
Modified: pkg/trunk/openrave_planning/openraveros/srv/robot_setactivevalues.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/robot_setactivevalues.srv 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/openraveros/srv/robot_setactivevalues.srv 2008-12-06 18:39:11 UTC (rev 7733)
@@ -6,5 +6,5 @@
float32[] values
# indices into the active degree of freedom table
-byte[] indices
+uint8[] indices
---
Modified: pkg/trunk/openrave_planning/orrosplanning/src/orrosplanningmain.cpp
===================================================================
--- pkg/trunk/openrave_planning/orrosplanning/src/orrosplanningmain.cpp 2008-12-06 08:48:48 UTC (rev 7732)
+++ pkg/trunk/openrave_planning/orrosplanning/src/orrosplanningmain.cpp 2008-12-06 18:39:11 UTC (rev 7733)
@@ -73,4 +73,8 @@
return true;
}
+void DECL_STDCALL(DestroyPlugin, ())
+{
}
+
+}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-12-06 19:38:34
|
Revision: 7735
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7735&view=rev
Author: gerkey
Date: 2008-12-06 19:38:30 +0000 (Sat, 06 Dec 2008)
Log Message:
-----------
Fixed for new sbpl header layout
Modified Paths:
--------------
pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp
pkg/trunk/motion_planning/sbpl_util/src/environment_wrap.cpp
pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.cpp
pkg/trunk/motion_planning/sbpl_util/src/t3dobst.cpp
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp 2008-12-06 19:02:58 UTC (rev 7734)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp 2008-12-06 19:38:30 UTC (rev 7735)
@@ -68,8 +68,7 @@
#include <environment_wrap.h>
#include <plan_wrap.h>
-//sbpl headers file
-#include <headers.h>
+#include <sbpl/headers.h>
#include <err.h>
Modified: pkg/trunk/motion_planning/sbpl_util/src/environment_wrap.cpp
===================================================================
--- pkg/trunk/motion_planning/sbpl_util/src/environment_wrap.cpp 2008-12-06 19:02:58 UTC (rev 7734)
+++ pkg/trunk/motion_planning/sbpl_util/src/environment_wrap.cpp 2008-12-06 19:38:30 UTC (rev 7735)
@@ -34,7 +34,7 @@
#include "environment_wrap.h"
#include <costmap_2d/costmap_2d.h>
-#include <headers.h>
+#include <sbpl/headers.h>
using namespace std;
Modified: pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.cpp
===================================================================
--- pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.cpp 2008-12-06 19:02:58 UTC (rev 7734)
+++ pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.cpp 2008-12-06 19:38:30 UTC (rev 7735)
@@ -34,7 +34,7 @@
#include "sbpl_util.hh"
#include "environment_wrap.h"
-#include <headers.h>
+#include <sbpl/headers.h>
#include <sys/time.h>
#include <sys/resource.h>
#include <errno.h>
Modified: pkg/trunk/motion_planning/sbpl_util/src/t3dobst.cpp
===================================================================
--- pkg/trunk/motion_planning/sbpl_util/src/t3dobst.cpp 2008-12-06 19:02:58 UTC (rev 7734)
+++ pkg/trunk/motion_planning/sbpl_util/src/t3dobst.cpp 2008-12-06 19:38:30 UTC (rev 7735)
@@ -36,8 +36,7 @@
#include "footprint.h"
#include <costmap_2d/costmap_2d.h>
-// for sbpl... not a greatly descriptive name
-#include <headers.h>
+#include <sbpl/headers.h>
#include <iostream>
#include <err.h>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2008-12-07 00:41:02
|
Revision: 7737
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7737&view=rev
Author: tfoote
Date: 2008-12-07 00:40:54 +0000 (Sun, 07 Dec 2008)
Log Message:
-----------
disambiguating all time and duration constructors
Modified Paths:
--------------
pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp
pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp
pkg/trunk/drivers/imu/imu_node/imu_node.cc
pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp
pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation.cpp
pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp
pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp
pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
pkg/trunk/highlevel/highlevel_controllers/src/VelocityControllers.cpp
pkg/trunk/nav/amcl_player/amcl_player.cc
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/nav/nav_view_sdl/nav_view.cpp
pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
pkg/trunk/nav/slam_gmapping/src/tftest.cpp
pkg/trunk/nav/wavefront_player/wavefront_player.cc
pkg/trunk/trajectory_rollout/src/governor_node.cpp
pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
pkg/trunk/util/logsetta/imu/imu_extract.cpp
pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp
pkg/trunk/util/logsetta/odom/odom_extract.cpp
pkg/trunk/util/tf/include/tf/time_cache.h
pkg/trunk/util/tf/include/tf/transform_datatypes.h
pkg/trunk/util/tf/include/tf/transform_listener.h
pkg/trunk/util/tf/src/cache.cpp
pkg/trunk/util/tf/src/tf.cpp
pkg/trunk/util/tf/test/testBroadcaster.cpp
pkg/trunk/vision/calib_converter/src/calib_converter.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/map_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/particle_cloud_2d_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/planning_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/poly_line_2d_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/tf_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/tools/pose_tool.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/visualization_manager.cpp
pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp
pkg/trunk/visualization/scene_labeler/include/scene_labeler.h
pkg/trunk/visualization/scene_labeler/src/scene_labeler/scene_labeler_stereo.cpp
pkg/trunk/world_models/costmap_2d/src/basic_observation_buffer.cc
Modified: pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -105,7 +105,7 @@
string output_topic_ ; // Topic name for publishing our SensorKinematics metapacket
SensorKinematicsGrabber() : ros::node("sensor_kinematics_grabber"),
- dcam_sync_(this, &SensorKinematicsGrabber::dcamCallback, ros::Duration(0.05), &SensorKinematicsGrabber::dcamCallbackTimeout)
+ dcam_sync_(this, &SensorKinematicsGrabber::dcamCallback, ros::Duration().fromSec(0.05), &SensorKinematicsGrabber::dcamCallbackTimeout)
{
param("~subscribe_color", subscribe_color_, false);
param("~output_topic", output_topic_, string("sensor_kinematics"));
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -160,7 +160,7 @@
void BasePositionControllerNode::setPoseCommand(std_msgs::PoseStamped cmd)
{
std_msgs::PoseStamped pose_odom ; // Stores the pose in the odometric frame
- cmd.header.stamp = ros::Time(0) ; // Transform using the latest transform
+ cmd.header.stamp = ros::Time() ; // Transform using the latest transform
tf_.transformPose(odom_frame_name_, cmd, pose_odom) ;
tf::Quaternion orientation_odom ; // Orientation in the odometric frame
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -222,11 +222,11 @@
point.setX(head_track_point_.point.x);
point.setY(head_track_point_.point.y);
point.setZ(head_track_point_.point.z);
- point.stamp_ =0;
+ point.stamp_ = ros::Time();
point.frame_id_ = head_track_point_.header.frame_id;
std::string pan_parent;
- TF.getParent("head_pan_link", 0, pan_parent);
+ TF.getParent("head_pan_link", ros::Time(), pan_parent);
std::string tilt_parent("head_pan_link");
// Pan angle
@@ -282,12 +282,12 @@
point.setX(frame_track_point_.point.x);
point.setY(frame_track_point_.point.y);
point.setZ(frame_track_point_.point.z);
- point.stamp_ = 0;//get the latest transform
+ point.stamp_ = ros::Time();//get the latest transform
point.frame_id_ = frame_track_point_.header.frame_id;
try
{
- TF.lookupTransform(point.frame_id_,"head_pan_link",ros::Time(0),frame);
+ TF.lookupTransform(point.frame_id_,"head_pan_link",ros::Time(),frame);
}
catch(tf::TransformException& ex)
{
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -304,7 +304,7 @@
try
{
- TF.lookupTransform(point.frame_id_,"head_pan",ros::Time(0),frame);
+ TF.lookupTransform(point.frame_id_,"head_pan",ros::Time(),frame);
}
catch(tf::TransformException& ex)
{
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -120,7 +120,7 @@
: robot_(NULL), pos_publisher_(NULL), TF(*ros::node::instance(), false) , loop_count_(0)
{
assert(ros::node::instance());
- TF.setExtrapolationLimit(ros::Duration(10000000));
+ TF.setExtrapolationLimit(ros::Duration().fromNSec(10000000));
}
CartesianPositionControllerNode::~CartesianPositionControllerNode()
Modified: pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp
===================================================================
--- pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -287,7 +287,7 @@
"mono", "uint16",
stcam->stIm->imDisp );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish("~disparity", img_);
stereo_info_.has_disparity = true;
@@ -297,7 +297,7 @@
if (do_calc_points_)
{
- cloud_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ cloud_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
cloud_.header.frame_id = "stereo";
cloud_.pts.resize(stcam->stIm->numPts);
cloud_.chan.resize(1);
@@ -323,7 +323,7 @@
publish("~cloud", cloud_);
}
- stereo_info_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ stereo_info_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
stereo_info_.height = stcam->stIm->imHeight;
stereo_info_.width = stcam->stIm->imWidth;
@@ -360,7 +360,7 @@
"mono", "byte",
img_data->imRaw );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_raw"), img_);
cam_info_.has_image = true;
} else {
@@ -373,7 +373,7 @@
img_data->imHeight, img_data->imWidth, 1,
"mono", "byte",
img_data->im );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image"), img_);
cam_info_.has_image = true;
} else {
@@ -387,7 +387,7 @@
"rgba", "byte",
img_data->imColor );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_color"), img_);
cam_info_.has_image_color = true;
} else {
@@ -400,7 +400,7 @@
img_data->imHeight, img_data->imWidth, 1,
"mono", "byte",
img_data->imRect );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_rect"), img_);
cam_info_.has_image_rect = true;
} else {
@@ -413,7 +413,7 @@
img_data->imHeight, img_data->imWidth, 3,
"rgb", "byte",
img_data->imRectColor );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_rect_color"), img_);
cam_info_.has_image_rect_color = true;
} else {
@@ -426,14 +426,14 @@
img_data->imHeight, img_data->imWidth, 4,
"rgba", "byte",
img_data->imRectColor );
- img_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ img_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
publish(base_name + std::string("image_rect_color"), img_);
cam_info_.has_image_rect_color = true;
} else {
cam_info_.has_image_rect_color = false;
}
- cam_info_.header.stamp = ros::Time(cam_->camIm->im_time * 1000);
+ cam_info_.header.stamp = ros::Time().fromNSec(cam_->camIm->im_time * 1000);
cam_info_.height = img_data->imHeight;
cam_info_.width = img_data->imWidth;
Modified: pkg/trunk/drivers/imu/imu_node/imu_node.cc
===================================================================
--- pkg/trunk/drivers/imu/imu_node/imu_node.cc 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/drivers/imu/imu_node/imu_node.cc 2008-12-07 00:40:54 UTC (rev 7737)
@@ -225,7 +225,7 @@
tf::PoseTFToMsg(pose, reading.pos);
- reading.header.stamp = ros::Time(time);
+ reading.header.stamp = ros::Time().fromNSec(time);
reading.header.frame_id = frameid_;
publish("imu_data", reading);
Modified: pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp
===================================================================
--- pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/drivers/laser/hokuyo_node/hokuyo_node.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -307,7 +307,7 @@
scan_msg_.range_max = scan_.config.max_range;
scan_msg_.ranges = scan_.ranges;
scan_msg_.intensities = scan_.intensities;
- scan_msg_.header.stamp = ros::Time((uint64_t)scan_.system_time_stamp);
+ scan_msg_.header.stamp = ros::Time().fromNSec((uint64_t)scan_.system_time_stamp);
scan_msg_.header.frame_id = frameid_;
publish("scan", scan_msg_);
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -149,7 +149,7 @@
std_msgs::PoseStamped pose_msg ;
- pose_msg.header.stamp = ros::Time(0.0) ;
+ pose_msg.header.stamp = ros::Time() ;
pose_msg.header.frame_id = frame_id_ ;
tf::PointTFToMsg(pose_result.getOrigin(), pose_msg.pose.position) ;
Modified: pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation.cpp
===================================================================
--- pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -288,7 +288,7 @@
{
// pose
Stamped<Transform> tmp;
- transformer_.lookupTransform("base_footprint","odom", 0.0, tmp);
+ transformer_.lookupTransform("base_footprint","odom", ros::Time(), tmp);
PoseTFToMsg(tmp, estimate.pose);
// header
Modified: pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
===================================================================
--- pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -296,7 +296,7 @@
// broadcast most recent estimate to TransformArray
Stamped<Transform> tmp;
- my_filter_.getEstimate(0, tmp);
+ my_filter_.getEstimate(ros::Time(), tmp);
odom_broadcaster_.sendTransform(Stamped<Transform>(tmp.inverse(), tmp.stamp_, "odom_combined", "base_footprint"));
#ifdef __EKF_DEBUG_FILE__
Modified: pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp
===================================================================
--- pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/grasp_module/grasp_learner/src/voxel_processor.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -68,7 +68,7 @@
virtual void processData() = 0;
virtual bool loadData(std::string filename) {
- if (!mLp.open(filename, ros::Time(0))) return false;
+ if (!mLp.open(filename, ros::Time())) return false;
mLp.addHandler<OctreeLearningMsg>(std::string("grasp_learning_bus"),
©Msg<OctreeLearningMsg>, (void*)this, true);
mNewMsg = false;
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/test/groundtruthtransform.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -21,7 +21,7 @@
tf::Stamped<tf::Pose> robotPose, globalPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time((uint64_t)0ULL);
+ robotPose.stamp_ = ros::Time();
try {
this->tf.transformPose("map", robotPose, globalPose);
} catch(tf::LookupException& ex) {
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -221,7 +221,7 @@
tf::Stamped<tf::Pose> robotPose, globalPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time((uint64_t)0ULL);
+ robotPose.stamp_ = ros::Time();
try{
tf_.transformPose("map", robotPose, globalPose);
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -264,7 +264,7 @@
tf::Stamped<tf::Pose> robotPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time((uint64_t)0ULL);
+ robotPose.stamp_ = ros::Time();
try{
tf_.transformPose("map", robotPose, global_pose_);
@@ -302,7 +302,7 @@
qt.setEulerZYX(goalMsg.goal.th, 0, 0);
goalPose.setData(btTransform(qt, btVector3(goalMsg.goal.x, goalMsg.goal.y, 0)));
goalPose.frame_id_ = goalMsg.header.frame_id;
- goalPose.stamp_ = ros::Time((uint64_t)0ULL);
+ goalPose.stamp_ = ros::Time();
try{
tf_.transformPose("map", goalPose, transformedGoalPose);
@@ -382,8 +382,8 @@
try
{
- tf::Stamped<btVector3> v_in(btVector3(odomMsg_.vel.x, odomMsg_.vel.y, 0), ros::Time((uint64_t)0ULL), odomMsg_.header.frame_id), v_out;
- tf_.transformVector("base_link", ros::Time((uint64_t)0ULL), v_in, odomMsg_.header.frame_id, v_out);
+ tf::Stamped<btVector3> v_in(btVector3(odomMsg_.vel.x, odomMsg_.vel.y, 0), ros::Time(), odomMsg_.header.frame_id), v_out;
+ tf_.transformVector("base_link", ros::Time(), v_in, odomMsg_.header.frame_id, v_out);
base_odom_.vel.x = v_in.x();
base_odom_.vel.y = v_in.y();
base_odom_.vel.th = odomMsg_.vel.th;
@@ -823,7 +823,8 @@
*/
void MoveBase::mapUpdateLoop()
{
- ros::Duration *d = new ros::Duration(1.0/map_update_frequency_);
+ ros::Duration *d = new ros::Duration();
+ d->fromSec(1.0/map_update_frequency_);
while (active_){
//Avoids laser race conditions.
Modified: pkg/trunk/highlevel/highlevel_controllers/src/VelocityControllers.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/VelocityControllers.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/highlevel/highlevel_controllers/src/VelocityControllers.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -30,7 +30,7 @@
btQuaternion qt(currentVel.vw, 0, 0);
robot_vel.setData(btTransform(qt, btVector3(currentVel.vx, currentVel.vy, 0)));
robot_vel.frame_id_ = "base_link";
- robot_vel.stamp_ = ros::Time((uint64_t)0ULL);
+ robot_vel.stamp_ = ros::Time();
//do we need to resize our map?
double origin_x, origin_y;
Modified: pkg/trunk/nav/amcl_player/amcl_player.cc
===================================================================
--- pkg/trunk/nav/amcl_player/amcl_player.cc 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/amcl_player/amcl_player.cc 2008-12-07 00:40:54 UTC (rev 7737)
@@ -749,7 +749,7 @@
{
tf::Stamped<tf::Pose> ident (btTransform(btQuaternion(0,0,0),
btVector3(0,0,0)),
- ros::Time((uint64_t)0ull), laserMsg.header.frame_id);
+ ros::Time(), laserMsg.header.frame_id);
tf::Stamped<btTransform> laser_pose;
try
{
@@ -792,7 +792,7 @@
laser_scans.pop_front();
- double timestamp = scan.header.stamp.to_double();
+ double timestamp = scan.header.stamp.toSec();
//printf("I: %.6f %.3f %.3f %.3f\n",
//timestamp, x, y, yaw);
@@ -875,7 +875,7 @@
pdata.vel.pa = this->odomMsg.vel.th;
pdata.stall = this->odomMsg.stall;
- double timestamp = this->odomMsg.header.stamp.to_double();
+ double timestamp = this->odomMsg.header.stamp.toSec();
this->Driver::Publish(this->position2d_addr,
PLAYER_MSGTYPE_DATA,
Modified: pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
===================================================================
--- pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -431,7 +431,7 @@
{
try
{
- tf::Stamped<tf::Pose> robot_pose(btTransform(btQuaternion(0,0,0), btVector3(0,0,0)), ros::Time((uint64_t)0ULL), "base_link");
+ tf::Stamped<tf::Pose> robot_pose(btTransform(btQuaternion(0,0,0), btVector3(0,0,0)), ros::Time(), "base_link");
tf::Stamped<tf::Pose> map_pose;
tf_client_->transformPose("map", robot_pose, map_pose);
Modified: pkg/trunk/nav/nav_view_sdl/nav_view.cpp
===================================================================
--- pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/nav_view_sdl/nav_view.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -355,7 +355,7 @@
tf::Stamped<tf::Pose> robotPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time(0);
+ robotPose.stamp_ = ros::Time();
tf::Stamped<tf::Pose> mapPose ;
tf.transformPose("map", robotPose, mapPose );
Modified: pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/slam_gmapping/src/slam_gmapping.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -57,7 +57,7 @@
/// not urgent for a robot like the PR2, where odometry is being
/// published several times faster than laser scans.
tf_ = new tf::TransformListener(*node_, true, 10000000000ULL);
- tf_->setExtrapolationLimit((int64_t) 200000000ULL );
+ tf_->setExtrapolationLimit( ros::Duration().fromSec(0.2));
ROS_ASSERT(tf_);
gsp_laser_ = NULL;
Modified: pkg/trunk/nav/slam_gmapping/src/tftest.cpp
===================================================================
--- pkg/trunk/nav/slam_gmapping/src/tftest.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/slam_gmapping/src/tftest.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -10,7 +10,7 @@
node_ = new ros::node("test");
tf_ = new tf::TransformListener(*node_, true,
10000000000ULL);
- tf_->setExtrapolationLimit( ros::Duration((int64_t)200000000ULL));
+ tf_->setExtrapolationLimit( ros::Duration().fromSec(0.2));
node_->subscribe("base_scan", scan_, &Test::laser_cb, this, -1);
}
Modified: pkg/trunk/nav/wavefront_player/wavefront_player.cc
===================================================================
--- pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/nav/wavefront_player/wavefront_player.cc 2008-12-07 00:40:54 UTC (rev 7737)
@@ -279,7 +279,7 @@
ang_eps(DTOR(4.0)),
cycletime(0.1),
laser_maxrange(4.0),
- laser_buffer_time(3000000000LL),
+ laser_buffer_time(ros::Duration().fromSec(3)),
lookahead_maxdist(2.0),
lookahead_distweight(5.0),
tvmin(0.2),
@@ -571,7 +571,7 @@
tf::Stamped<tf::Pose> robotPose;
robotPose.setIdentity();
robotPose.frame_id_ = "base_link";
- robotPose.stamp_ = ros::Time((uint64_t)0ULL); // request most recent pose
+ robotPose.stamp_ = ros::Time(); // request most recent pose
//robotPose.time = laserMsg.header.stamp.sec * (uint64_t)1000000000ULL +
// laserMsg.header.stamp.nsec; ///HACKE FIXME we should be able to get time somewhere else
try
Modified: pkg/trunk/trajectory_rollout/src/governor_node.cpp
===================================================================
--- pkg/trunk/trajectory_rollout/src/governor_node.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/trajectory_rollout/src/governor_node.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -48,7 +48,7 @@
{
robot_vel_.setIdentity();
robot_vel_.frame_id_ = "base_link";
- robot_vel_.stamp_ = ros::Time(uint64_t(0ULL));
+ robot_vel_.stamp_ = ros::Time();
//so we can draw the local path
advertise<std_msgs::Polyline2D>("local_path", 10);
@@ -68,7 +68,7 @@
btQuaternion qt(odom_msg_.vel.th, 0, 0);
robot_vel_.setData(btTransform(qt, btVector3(odom_msg_.vel.x, odom_msg_.vel.y, 0)));
robot_vel_.frame_id_ = "base_link";
- robot_vel_.stamp_ = ros::Time((uint64_t)0ULL);
+ robot_vel_.stamp_ = ros::Time();
//give robot_vel_ back
vel_lock.unlock();
@@ -99,7 +99,7 @@
tf::Stamped<tf::Pose> robot_pose, global_pose;
robot_pose.setIdentity();
robot_pose.frame_id_ = "base_link";
- robot_pose.stamp_ = ros::Time((uint64_t)0ULL);
+ robot_pose.stamp_ = ros::Time();
try
{
Modified: pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
===================================================================
--- pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -125,7 +125,7 @@
for (int i = 1; i < argc; i++)
files.push_back(argv[i]);
- player.open(files, ros::Time(0));
+ player.open(files, ros::Time());
player.addHandler<std_msgs::RobotBase2DOdom>(string("*"), &odom_callback, NULL);
player.addHandler<std_msgs::LaserScan>(string("*"), &scan_callback, NULL);
Modified: pkg/trunk/util/logsetta/imu/imu_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/imu/imu_extract.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/logsetta/imu/imu_extract.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -57,7 +57,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0));
+ player.open(std::string(argv[1]), ros::Time());
int count;
Modified: pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/logsetta/localize_extract/localize_extract.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -57,7 +57,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0));
+ player.open(std::string(argv[1]), ros::Time());
int count;
Modified: pkg/trunk/util/logsetta/odom/odom_extract.cpp
===================================================================
--- pkg/trunk/util/logsetta/odom/odom_extract.cpp 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/logsetta/odom/odom_extract.cpp 2008-12-07 00:40:54 UTC (rev 7737)
@@ -62,7 +62,7 @@
ros::record::Player player;
- player.open(std::string(argv[1]), ros::Time(0));
+ player.open(std::string(argv[1]), ros::Time());
int count;
Modified: pkg/trunk/util/tf/include/tf/time_cache.h
===================================================================
--- pkg/trunk/util/tf/include/tf/time_cache.h 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/tf/include/tf/time_cache.h 2008-12-07 00:40:54 UTC (rev 7737)
@@ -69,8 +69,8 @@
static const int64_t DEFAULT_MAX_EXTRAPOLATION_TIME = 0LL; //!< default max extrapolation of 0 nanoseconds \todo remove and make not optional??
- TimeCache(bool interpolating = true, ros::Duration max_storage_time = ros::Duration(DEFAULT_MAX_STORAGE_TIME),
- ros::Duration max_extrapolation_time = ros::Duration(DEFAULT_MAX_EXTRAPOLATION_TIME)):
+ TimeCache(bool interpolating = true, ros::Duration max_storage_time = ros::Duration().fromNSec(DEFAULT_MAX_STORAGE_TIME),
+ ros::Duration max_extrapolation_time = ros::Duration().fromNSec(DEFAULT_MAX_EXTRAPOLATION_TIME)):
interpolating_(interpolating),
max_storage_time_(max_storage_time),
max_extrapolation_time_(max_extrapolation_time)
Modified: pkg/trunk/util/tf/include/tf/transform_datatypes.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_datatypes.h 2008-12-06 23:11:03 UTC (rev 7736)
+++ pkg/trunk/util/tf/include/tf/transform_datatypes.h 2008-12-07 00:40:54 UTC (rev 7737)
@@ -66,7 +66,7 @@
std::string frame_id_;
std::string parent_id_; ///only used for transform
- Stamped() :stamp_ ((uint64_t)0ULL),frame_id_ ("NO_ID"), parent_id_("NOT A TRANSFORM"){}; //Default constructor used only for preallocation
+ Stamped() :frame_id_ ("NO_ID"), parent_id_("NOT A TRANSFORM"){}; //Default constructor used only for preallocation
Stamped(const T& input, const ros::Time& timestamp, const std::string & frame_id, const std::string & parent_id = "NOT A TRANSFORM"):
T (input), stamp_ ( timestamp ), frame_id_ (frame_id), parent_id_(parent_id){ };
@@ -88,7 +88,7 @@
/** \brief convert QuaternionStamped msg to Stamped<Quaternion> */
static inline void QuaternionStampedMsgToTF(const std_msgs::QuaternionStamped & msg, Stamped<Quaterni...
[truncated message content] |
|
From: <rdi...@us...> - 2008-12-07 09:37:27
|
Revision: 7748
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7748&view=rev
Author: rdiankov
Date: 2008-12-07 09:37:19 +0000 (Sun, 07 Dec 2008)
Log Message:
-----------
openrave session server finished (not fully tested with a client yet, but all planned functionality is there)
Modified Paths:
--------------
pkg/trunk/3rdparty/openrave/Makefile
pkg/trunk/openrave_planning/openraveros/msg/ActiveDOFs.msg
pkg/trunk/openrave_planning/openraveros/msg/AffineTransformMatrix.msg
pkg/trunk/openrave_planning/openraveros/msg/AttachedSensor.msg
pkg/trunk/openrave_planning/openraveros/msg/BodyInfo.msg
pkg/trunk/openrave_planning/openraveros/msg/Manipulator.msg
pkg/trunk/openrave_planning/openraveros/msg/RobotInfo.msg
pkg/trunk/openrave_planning/openraveros/msg/Trajectory.msg
pkg/trunk/openrave_planning/openraveros/msg/TrajectoryPoint.msg
pkg/trunk/openrave_planning/openraveros/src/openraveros.h
pkg/trunk/openrave_planning/openraveros/src/rosserver.h
pkg/trunk/openrave_planning/openraveros/src/session.h
pkg/trunk/openrave_planning/openraveros/srv/body_destroy.srv
pkg/trunk/openrave_planning/openraveros/srv/body_enable.srv
pkg/trunk/openrave_planning/openraveros/srv/body_getaabb.srv
pkg/trunk/openrave_planning/openraveros/srv/body_getaabbs.srv
pkg/trunk/openrave_planning/openraveros/srv/body_getdof.srv
pkg/trunk/openrave_planning/openraveros/srv/body_getlinks.srv
pkg/trunk/openrave_planning/openraveros/srv/body_setjointvalues.srv
pkg/trunk/openrave_planning/openraveros/srv/body_settransform.srv
pkg/trunk/openrave_planning/openraveros/srv/env_checkcollision.srv
pkg/trunk/openrave_planning/openraveros/srv/env_closefigures.srv
pkg/trunk/openrave_planning/openraveros/srv/env_createbody.srv
pkg/trunk/openrave_planning/openraveros/srv/env_createrobot.srv
pkg/trunk/openrave_planning/openraveros/srv/env_getbodies.srv
pkg/trunk/openrave_planning/openraveros/srv/env_getbody.srv
pkg/trunk/openrave_planning/openraveros/srv/env_getrobots.srv
pkg/trunk/openrave_planning/openraveros/srv/env_loadplugin.srv
pkg/trunk/openrave_planning/openraveros/srv/env_loadscene.srv
pkg/trunk/openrave_planning/openraveros/srv/env_plot.srv
pkg/trunk/openrave_planning/openraveros/srv/env_raycollision.srv
pkg/trunk/openrave_planning/openraveros/srv/env_triangulate.srv
pkg/trunk/openrave_planning/openraveros/srv/env_wait.srv
pkg/trunk/openrave_planning/openraveros/srv/planner_init.srv
pkg/trunk/openrave_planning/openraveros/srv/problem_sendcommand.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_controllersend.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_controllerset.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_getactivevalues.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_sensorgetdata.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_sensorsend.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_setactivedofs.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_setactivevalues.srv
pkg/trunk/openrave_planning/openraveros/srv/robot_starttrajectory.srv
Added Paths:
-----------
pkg/trunk/openrave_planning/openraveros/srv/body_getjointvalues.srv
Removed Paths:
-------------
pkg/trunk/openrave_planning/openraveros/srv/robot_getactivedof.srv
Modified: pkg/trunk/3rdparty/openrave/Makefile
===================================================================
--- pkg/trunk/3rdparty/openrave/Makefile 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/3rdparty/openrave/Makefile 2008-12-07 09:37:19 UTC (rev 7748)
@@ -2,7 +2,7 @@
SVN_DIR = openrave_svn
# Should really specify a revision
-SVN_REVISION = -r 532
+SVN_REVISION = -r 536
SVN_URL = https://openrave.svn.sourceforge.net/svnroot/openrave
include $(shell rospack find mk)/svn_checkout.mk
Modified: pkg/trunk/openrave_planning/openraveros/msg/ActiveDOFs.msg
===================================================================
--- pkg/trunk/openrave_planning/openraveros/msg/ActiveDOFs.msg 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/msg/ActiveDOFs.msg 2008-12-07 09:37:19 UTC (rev 7748)
@@ -1,11 +1,17 @@
# specifies the active degrees of freedom of the robot
-byte[] activedofs
-byte affinedofs
+# mask of active base degrees of freedom
+uint8 affine
+
+# active joints
+uint8[] joints
+
+float32[3] rotationaxis
+
# mask for affine dofs
-byte DOF_X = 1
-byte DOF_Y = 2
-byte DOF_Z = 4
-byte DOF_RotationAxis = 8
-byte DOF_Rotation3D = 16
-byte DOF_RotationQuat = 32
+uint8 DOF_X = 1
+uint8 DOF_Y = 2
+uint8 DOF_Z = 4
+uint8 DOF_RotationAxis = 8
+uint8 DOF_Rotation3D = 16
+uint8 DOF_RotationQuat = 32
Modified: pkg/trunk/openrave_planning/openraveros/msg/AffineTransformMatrix.msg
===================================================================
--- pkg/trunk/openrave_planning/openraveros/msg/AffineTransformMatrix.msg 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/msg/AffineTransformMatrix.msg 2008-12-07 09:37:19 UTC (rev 7748)
@@ -3,4 +3,4 @@
# [0] [3] [6] [9]
# [1] [4] [7] [10]
# [2] [5] [8] [11]
-float32[12] transform
\ No newline at end of file
+float32[12] m
Modified: pkg/trunk/openrave_planning/openraveros/msg/AttachedSensor.msg
===================================================================
--- pkg/trunk/openrave_planning/openraveros/msg/AttachedSensor.msg 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/msg/AttachedSensor.msg 2008-12-07 09:37:19 UTC (rev 7748)
@@ -4,10 +4,13 @@
string name
# zero-based index of link sensor is attached to
-byte attachedlink
+int8 attachedlink
# 3x4 matrix of the relative transform of the sensor frame with respect to the link frame
AffineTransformMatrix trelative
+# 3x4 matrix of the global transform of the sensor (ie, with link transform applied)
+AffineTransformMatrix tglobal
+
# type of sensor
string type
Modified: pkg/trunk/openrave_planning/openraveros/msg/BodyInfo.msg
===================================================================
--- pkg/trunk/openrave_planning/openraveros/msg/BodyInfo.msg 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/msg/BodyInfo.msg 2008-12-07 09:37:19 UTC (rev 7748)
@@ -1,6 +1,16 @@
# information about a body
-uint32 bodyid
+int32 bodyid
+# current transformation
+AffineTransformMatrix transform
+
+# degrees of freedom (number of joints)
+uint8 dof
+
+# enabled status
+uint8 enabled
+
+
# filename used to create body geometry
string filename
@@ -10,25 +20,17 @@
# type of body
string type
-# current transformation
-AffineTransformMatrix transform
-
-# degrees of freedom (number of joints)
-byte dof
-
-# enabled status
-byte enabled
-
float32[] jointvalues
AffineTransformMatrix[] links
string[] linknames
-# request information bitmasks, also holds robot specific request information
-uint16 Req_Transform=1
-uint16 Req_JointValues=2
-uint16 Req_Links=4
-uint16 Req_LinkNames=8
-uint16 Req_JointLimits=16
-uint16 Req_RobotManipulators=32
-uint16 Req_RobotSensors=64
-uint16 Req_RobotActiveDOFs=128
+# joint limits
+float32[] lowerlimit
+float32[] upperlimit
+
+# request information bitmasks, also holds robot specific request information (lower 8 bits)
+uint16 Req_JointValues=1
+uint16 Req_Links=2
+uint16 Req_LinkNames=4
+uint16 Req_JointLimits=8
+uint16 Req_Names=16 # if set, fills filename, name, and type
\ No newline at end of file
Modified: pkg/trunk/openrave_planning/openraveros/msg/Manipulator.msg
===================================================================
--- pkg/trunk/openrave_planning/openraveros/msg/Manipulator.msg 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/msg/Manipulator.msg 2008-12-07 09:37:19 UTC (rev 7748)
@@ -1,19 +1,19 @@
# information specific to a manipulator for a robot
# zero-based index of base link that manipulator is attached to
-byte baselink
+int8 baselink
# zero-based index of link defining the end-effector
-byte eelink
+int8 eelink
# 3x4 matrix of the grasp frame relative to the end-effector link
AffineTransformMatrix tgrasp
# zero-based hand joint indices
-byte[] handjoints
+uint8[] handjoints
# zero-based arm joints indices (from base to end-effector)
-byte[] armjoints
+uint8[] armjoints
# name of ik solver using
string iksolvername
Modified: pkg/trunk/openrave_planning/openraveros/msg/RobotInfo.msg
===================================================================
--- pkg/trunk/openrave_planning/openraveros/msg/RobotInfo.msg 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/msg/RobotInfo.msg 2008-12-07 09:37:19 UTC (rev 7748)
@@ -3,4 +3,14 @@
BodyInfo bodyinfo
Manipulator[] manips
AttachedSensor[] sensors
-ActiveDOFs dofs
+
+# total active dof
+uint8 activedof
+
+# information about the active dofs
+ActiveDOFs active
+
+# upper 8 bits
+uint16 Req_Manipulators=256
+uint16 Req_Sensors=512
+uint16 Req_ActiveDOFs=1024
Modified: pkg/trunk/openrave_planning/openraveros/msg/Trajectory.msg
===================================================================
--- pkg/trunk/openrave_planning/openraveros/msg/Trajectory.msg 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/msg/Trajectory.msg 2008-12-07 09:37:19 UTC (rev 7748)
@@ -1,2 +1,2 @@
TrajectoryPoint[] points
-ActiveDOFs dofs
+ActiveDOFs active
Modified: pkg/trunk/openrave_planning/openraveros/msg/TrajectoryPoint.msg
===================================================================
--- pkg/trunk/openrave_planning/openraveros/msg/TrajectoryPoint.msg 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/msg/TrajectoryPoint.msg 2008-12-07 09:37:19 UTC (rev 7748)
@@ -2,6 +2,6 @@
float32[] position
# optional
-float32[] velocities
+float32[] velocity
AffineTransformMatrix transform
float32 timestamp
Modified: pkg/trunk/openrave_planning/openraveros/src/openraveros.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/openraveros.h 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/src/openraveros.h 2008-12-07 09:37:19 UTC (rev 7748)
@@ -74,6 +74,26 @@
#define stricmp strcasecmp
#endif
+inline std::wstring _ravembstowcs(const char* pstr)
+{
+ size_t len = mbstowcs(NULL, pstr, 0);
+ std::wstring w; w.resize(len);
+ mbstowcs(&w[0], pstr, len);
+ return w;
+}
+
+inline std::string _stdwcstombs(const wchar_t* pname)
+{
+ std::string s;
+ size_t len = wcstombs(NULL, pname, 0);
+ if( len != (size_t)-1 ) {
+ s.resize(len);
+ wcstombs(&s[0], pname, len);
+ }
+
+ return s;
+}
+
#include <openrave-core.h>
#include <ros/node.h>
@@ -88,6 +108,7 @@
#include <openraveros/body_getaabb.h>
#include <openraveros/body_getaabbs.h>
#include <openraveros/body_getdof.h>
+#include <openraveros/body_getjointvalues.h>
#include <openraveros/body_getlinks.h>
#include <openraveros/body_setjointvalues.h>
#include <openraveros/body_settransform.h>
@@ -113,7 +134,6 @@
#include <openraveros/problem_sendcommand.h>
#include <openraveros/robot_controllersend.h>
#include <openraveros/robot_controllerset.h>
-#include <openraveros/robot_getactivedof.h>
#include <openraveros/robot_getactivevalues.h>
#include <openraveros/robot_sensorgetdata.h>
#include <openraveros/robot_sensorsend.h>
Modified: pkg/trunk/openrave_planning/openraveros/src/rosserver.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/rosserver.h 2008-12-07 08:15:41 UTC (rev 7747)
+++ pkg/trunk/openrave_planning/openraveros/src/rosserver.h 2008-12-07 09:37:19 UTC (rev 7748)
@@ -31,17 +31,27 @@
class LockEnvironment
{
public:
- LockEnvironment(ROSServer* pserv) : _pserv(pserv) { _pserv->_penv->LockPhysics(true); }
- ~LockEnvironment() { _pserv->_penv->LockPhysics(false); }
+ LockEnvironment(ROSServer* pserv) : _pserv(pserv) { _pserv->GetEnv()->LockPhysics(true); }
+ ~LockEnvironment() { _pserv->GetEnv()->LockPhysics(false); }
private:
ROSServer* _pserv;
};
+ class FIGURE
+ {
+ public:
+ FIGURE(EnvironmentBase* penv, void* handle) : _handle(handle) {}
+ ~FIGURE() { _penv->closegraph(_handle); }
+ private:
+ EnvironmentBase* _penv;
+ void* _handle;
+ };
+
public:
- ROSServer(boost::shared_ptr<EnvironmentBase> penv) : RaveServerBase(penv.get()), _nNextFigureId(1), _nNextPlannerId(1) {
- _penv = penv;
+ ROSServer(EnvironmentBase* penv) : RaveServerBase(penv), _nNextFigureId(1), _nNextPlannerId(1), _nNextProblemId(1) {
_bThreadDestroyed = false;
+ _bCloseClient = false;
_fSimulationTimestep = 0.01;
_vgravity = Vector(0,0,-9.8f);
}
@@ -51,11 +61,12 @@
virtual void Destroy()
{
+ _bCloseClient = true;
Reset();
- _penv->SetCollisionChecker(NULL);
- _penv->SetPhysicsEngine(NULL);
- _penv->AttachViewer(NULL);
+ GetEnv()->SetCollisionChecker(NULL);
+ GetEnv()->SetPhysicsEngine(NULL);
+ GetEnv()->AttachViewer(NULL);
// have to maintain a certain destruction order
_pphysics.reset();
@@ -66,12 +77,12 @@
_threadviewer.join();
_pviewer.reset();
}
+
+ _bCloseClient = false;
}
virtual void Reset()
{
- FOREACH(it, _mapFigureIds)
- _penv->closegraph(it->second);
_mapFigureIds.clear();
// destroy environment specific state: problems, planners, figures
@@ -96,22 +107,22 @@
virtual bool IsClosing()
{
- return false;
+ return _bCloseClient;
}
bool body_destroy_srv(body_destroy::request& req, body_destroy::response& res)
{
- KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
if( pbody == NULL )
return false;
LockEnvironment envlock(this);
- return _penv->RemoveKinBody(pbody,true);
+ return GetEnv()->RemoveKinBody(pbody,true);
}
bool body_enable_srv(body_enable::request& req, body_enable::response& res)
{
- KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
if( pbody == NULL )
return false;
@@ -122,7 +133,7 @@
bool body_getaabb_srv(body_getaabb::request& req, body_getaabb::response& res)
{
- KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
if( pbody == NULL )
return false;
@@ -135,12 +146,12 @@
bool body_getaabbs_srv(body_getaabbs::request& req, body_getaabbs::response& res)
{
- KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
if( pbody == NULL )
return false;
LockEnvironment envlock(this);
- res.set_boxes_size(pbody->GetLinks().size()); int index = 0;
+ res.boxes.resize(pbody->GetLinks().size()); int index = 0;
FOREACHC(itlink, pbody->GetLinks()) {
OpenRAVE::AABB ab = (*itlink)->ComputeAABB();
openraveros::AABB& resbox = res.boxes[index++];
@@ -151,77 +162,631 @@
bool body_getdof_srv(body_getdof::request& req, body_getdof::response& res)
{
- KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
if( pbody == NULL )
return false;
- LockEnvironment envlock(this);
res.dof = pbody->GetDOF();
return true;
}
+ bool body_getjointvalues_srv(body_getjointvalues::request& req, body_getjointvalues::response& res)
+ {
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+ LockEnvironment envlock(this);
+
+ if( req.indices.size() > 0 ) {
+ vector<dReal> vtemp;
+ pbody->GetJointValues(vtemp);
+
+ res.values.resize(req.indices.size());
+ for(size_t i = 0; i < req.indices.size(); ++i) {
+ ROS_ASSERT( req.indices[i] < vtemp.size() );
+ res.values[i] = vtemp[req.indices[i]];
+ }
+ }
+ else {
+ vector<dReal> vtemp;
+ pbody->GetJointValues(vtemp);
+
+ res.values.resize(vtemp.size());
+ for(size_t i = 0; i < req.indices.size(); ++i)
+ res.values[i] = vtemp[i];
+ }
+
+ return true;
+ }
+
bool body_getlinks_srv(body_getlinks::request& req, body_getlinks::response& res)
{
- KinBody* pbody = _penv->GetBodyFromNetworkId(req.bodyid);
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
if( pbody == NULL )
return false;
LockEnvironment envlock(this);
vector<Transform> vtrans; pbody->GetBodyTransformations(vtrans);
- res.set_links_size(vtrans.size()); int index = 0;
- FOREACH(ittrans, vtrans) {
- TransformMatrix tm = TransformMatrix(*ittrans);
- AffineTransformMatrix& am = res.links[index++];
- am.transform[0] = tm.m[0]; am.transform[3] = tm.m[1]; am.transform[6] = tm.m[2];
- am.transform[1] = tm.m[4]; am.transform[4] = tm.m[5]; am.transform[7] = tm.m[6];
- am.transform[2] = tm.m[8]; am.transform[5] = tm.m[9]; am.transform[8] = tm.m[10];
- am.transform[9] = tm.trans.x; am.transform[10] = tm.trans.y; am.transform[11] = tm.trans.z;
+ res.links.resize(vtrans.size()); int index = 0;
+ FOREACH(ittrans, vtrans)
+ res.links[index++] = GetAffineTransform(*ittrans);
+
+ return true;
+ }
+
+ bool body_setjointvalues_srv(body_setjointvalues::request& req, body_setjointvalues::response& res)
+ {
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+
+ if( pbody->GetDOF() == 0 )
+ return false;
+
+ LockEnvironment envlock(this);
+ vector<dReal> vvalues;
+
+ if( req.indices.size() > 0 ) {
+ if( req.indices.size() != req.jointvalues.size() ) {
+ RAVELOG_WARNA("indices (%d) different size than joint values (%d)\n", req.indices.size(), req.jointvalues.size());
+ return false;
+ }
+
+ pbody->GetJointValues(vvalues);
+ for(uint32_t i = 0; i < req.indices.size(); ++i)
+ vvalues[req.indices[i]] = req.jointvalues[i];
}
+ else {
+ if( pbody->GetDOF() != (int)req.jointvalues.size() ) {
+ RAVELOG_WARNA("body dof (%d) not equal to jointvalues (%d)", pbody->GetDOF(), req.jointvalues.size());
+ return false;
+ }
+
+ vvalues.reserve(req.jointvalues.size());
+ FOREACHC(it,req.jointvalues)
+ vvalues.push_back(*it);
+ }
+
+ pbody->SetJointValues(NULL, NULL, &vvalues[0], true);
+
+ if( pbody->IsRobot() ) {
+ // if robot, should turn off any trajectory following
+ RobotBase* probot = (RobotBase*)pbody;
+ if( probot->GetController() != NULL ) {
+ probot->GetJointValues(vvalues); // reget the values since they'll go through the joint limits
+ probot->GetController()->SetDesired(&vvalues[0]);
+ }
+ }
+
+ return true;
}
- bool body_setjointvalues_srv(body_setjointvalues::request& req, body_setjointvalues::response& res);
- bool body_settransform_srv(body_settransform::request& req, body_settransform::response& res);
- bool env_checkcollision_srv(env_checkcollision::request& req, env_checkcollision::response& res);
- bool env_closefigures_srv(env_closefigures::request& req, env_closefigures::response& res);
- bool env_createbody_srv(env_createbody::request& req, env_createbody::response& res);
- bool env_createplanner_srv(env_createplanner::request& req, env_createplanner::response& res);
- bool env_createproblem_srv(env_createproblem::request& req, env_createproblem::response& res);
- bool env_createrobot_srv(env_createrobot::request& req, env_createrobot::response& res);
- bool env_destroyproblem_srv(env_destroyproblem::request& req, env_destroyproblem::response& res);
- bool env_getbodies_srv(env_getbodies::request& req, env_getbodies::response& res);
- bool env_getbody_srv(env_getbody::request& req, env_getbody::response& res);
- bool env_getrobots_srv(env_getrobots::request& req, env_getrobots::response& res);
- bool env_loadplugin_srv(env_loadplugin::request& req, env_loadplugin::response& res);
- bool env_loadscene_srv(env_loadscene::request& req, env_loadscene::response& res);
- bool env_plot_srv(env_plot::request& req, env_plot::response& res);
- bool env_raycollision_srv(env_raycollision::request& req, env_raycollision::response& res);
+ bool body_settransform_srv(body_settransform::request& req, body_settransform::response& res)
+ {
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+
+ TransformMatrix tm;
+ tm.m[0] = req.transform.m[0]; tm.m[1] = req.transform.m[3]; tm.m[2] = req.transform.m[6];
+ tm.m[4] = req.transform.m[1]; tm.m[5] = req.transform.m[4]; tm.m[6] = req.transform.m[7];
+ tm.m[8] = req.transform.m[2]; tm.m[9] = req.transform.m[5]; tm.m[10] = req.transform.m[8];
+ tm.trans.x = req.transform.m[9]; tm.trans.y = req.transform.m[10]; tm.trans.z = req.transform.m[11];
+
+ Transform t = tm;
+ LockEnvironment envlock(this);
+ pbody->SetTransform(tm);
+
+ if( pbody->IsRobot() ) {
+ RobotBase* probot = (RobotBase*)pbody;
+ if( probot->GetController() != NULL )
+ probot->GetController()->SetPath(NULL);
+ }
+
+ return true;
+ }
+
+ bool env_checkcollision_srv(env_checkcollision::request& req, env_checkcollision::response& res)
+ {
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+
+ set<KinBody*> setignore;
+ FOREACH(it, req.excludedbodyids) {
+ KinBody* pbody = GetEnv()->GetBodyFromNetworkId(req.bodyid);
+ if( pbody == NULL )
+ return false;
+ setignore.insert(pbody);
+ }
+
+ COLLISIONREPORT report;
+ {
+ LockEnvironment envlock(this);
+ int oldopts = GetEnv()->GetCollisionOptions();
+ if( !GetEnv()->SetCollisionOptions(req.options) )
+ RAVELOG_WARNA("failed to set collision options\n");
+
+ set<KinBody::Link*> empty;
+ if( req.linkid < 0 )
+ res.collision = GetEnv()->CheckCollision(pbody, setignore, empty, &report);
+ else {
+ if( req.linkid >= (int)pbody->GetLinks().size() )
+ return false;
+ res.collision = GetEnv()->CheckCollision(pbody->GetLinks()[req.linkid], setignore, empty, &report);
+ }
+
+ GetEnv()->SetCollisionOptions(oldopts);
+ }
+
+ res.collidingbodyid = 0;
+
+ if( res.collision ) {
+ KinBody::Link* plinkcol = report.plink1;
+ if( report.plink2 && report.plink2->GetParent() != pbody ) {
+ ROS_ASSERT(report.plink1->GetParent() == pbody);
+ plinkcol = report.plink2;
+ }
+
+ if( plinkcol != NULL ) {
+ res.collidingbodyid = plinkcol->GetParent()->GetNetworkId();
+ res.collidinglink = plinkcol->GetIndex();
+ }
+
+ RAVELOG_INFOA("collision %S:%S with %S:%S\n",
+ report.plink1?report.plink1->GetParent()->GetName():L"(NULL",
+ report.plink1?report.plink1->GetName():L"(NULL)",
+ report.plink2?report.plink2->GetParent()->GetName():L"(NULL)",
+ report.plink2?report.plink2->GetName():L"(NULL)");
+ }
+
+ if( req.options & CO_Distance )
+ res.mindist = report.minDistance;
+ if( req.options & CO_Contacts ) {
+ res.contacts.resize(report.contacts.size()); int index = 0;
+ FOREACHC(itc, report.contacts) {
+ openraveros::Contact& c = res.contacts[index++];
+ c.position[0] = itc->pos.x; c.position[1] = itc->pos.y; c.position[2] = itc->pos.z;
+ c.normal[0] = itc->norm.x; c.normal[1] = itc->norm.y; c.normal[2] = itc->norm.z;
+ }
+ }
+
+ return true;
+ }
+
+ bool env_closefigures_srv(env_closefigures::request& req, env_closefigures::response& res)
+ {
+ bool bSuccess = true;
+
+ if( req.figureids.size() > 0 ) {
+ FOREACH(itid, req.figureids) {
+ if( !_mapFigureIds.erase(*itid) )
+ bSuccess = false;
+ }
+ }
+ else // destroy everything
+ _mapFigureIds.clear();
+
+ return bSuccess;
+ }
+
+ bool env_createbody_srv(env_createbody::request& req, env_createbody::response& res)
+ {
+ LockEnvironment envlock(this);
+ KinBody* pbody = GetEnv()->CreateKinBody();
+
+ if( req.file.size() > 0 ) {
+ if( !pbody->Init(req.file.c_str(), NULL) )
+ return false;
+ }
+
+ pbody->SetName(req.name.c_str());
+
+ if( !GetEnv()->AddKinBody(pbody) )
+ return false;
+
+ res.bodyid = pbody->GetNetworkId();
+ return true;
+ }
+
+ bool env_createplanner_srv(env_createplanner::request& req, env_createplanner::response& res)
+ {
+ boost::shared_ptr<PlannerBase> pplanner(GetEnv()->CreatePlanner(req.plannertype.c_str()));
+ if( !pplanner )
+ return false;
+
+ _mapplanners[++_nNextPlannerId] = pplanner;
+ res.plannerid = _nNextPlannerId;
+ return true;
+ }
+
+ bool env_createproblem_srv(env_createproblem::request& req, env_createproblem::response& res)
+ {
+ boost::shared_ptr<ProblemInstance> pproblem(GetEnv()->CreateProblem(req.problemtype.c_str()));
+ if( !pproblem )
+ return false;
+
+ if( req.destroyduplicates ) {
+ map<int, boost::shared_ptr<ProblemInstance> >::iterator itprob = _mapproblems.begin();
+ while(itprob != _mapproblems.end()) {
+ if( stricmp(itprob->second->GetXMLId(), req.problemtype.c_str()) == 0 ) {
+ RAVELOG_INFOA("deleting duplicate problem %s\n", req.problemtype.c_str());
+ if( !GetEnv()->RemoveProblem(itprob->second.get()) )
+ RAVELOG_WARNA("failed to remove problem %s\n", itprob->second->GetXMLId());
+
+ _mapproblems.erase(itprob++);
+ }
+ else
+ ++itprob;
+ }
+ }
+
+ if( !GetEnv()->LoadProblem(pproblem.get(), req.args.c_str()) )
+ return false;
+
+ _mapproblems[++_nNextProblemId] = pproblem;
+ res.problemid = _nNextProblemId;
+ return true;
+ }
+
+ bool env_createrobot_srv(env_createrobot::request& req, env_createrobot::response& res)
+ {
+ RobotBase* probot = GetEnv()->CreateRobot(req.type.c_str());
+ if( !probot )
+ return false;
+
+ if( req.file.size() > 0 ) {
+ if( !probot->Init(req.file.c_str(), NULL) )
+ return false;
+ }
+
+ probot->SetName(req.name.c_str());
+
+ if( !GetEnv()->AddRobot(probot) )
+ return false;
+
+ res.bodyid = probot->GetNetworkId();
+ return true;
+ }
+
+ bool env_destroyproblem_srv(env_destroyproblem::request& req, env_destroyproblem::response& res)
+ {
+ map<int, boost::shared_ptr<ProblemInstance> >::iterator itprob = _mapproblems.find(req.problemid);
+ if( itprob == _mapproblems.end() )
+ return false;
+
+ if( !GetEnv()->RemoveProblem(itprob->second.get()) )
+ RAVELOG_WARNA("failed to remove problem\n");
+
+ _mapproblems.erase(itprob);
+ return true;
+ }
+
+ void FillKinBodyInfo(KinBody* pbody, BodyInfo& info, uint32_t options)
+ {
+ info.bodyid = pbody->GetDOF();
+ info.transform = GetAffineTransform(pbody->GetTransform());
+ info.enabled = pbody->IsEnabled();
+
+ if( options & BodyInfo::Req_JointValues ) {
+ vector<dReal> vvalues; pbody->GetJointValues(vvalues);
+ info.jointvalues.resize(vvalues.size());
+ for(size_t i = 0; i < vvalues.size(); ++i)
+ info.jointvalues[i] = vvalues[i];
+ }
+ if( options & BodyInfo::Req_Links ) {
+ vector<Transform> vlinks; pbody->GetBodyTransformations(vlinks);
+ info.links.resize(vlinks.size());
+ for(size_t i = 0; i < vlinks.size(); ++i)
+ info.links[i] = GetAffineTransform(vlinks[i]);
+ }
+ if( options & BodyInfo::Req_LinkNames ) {
+ info.linknames.resize(pbody->GetLinks().size());
+ for(size_t i = 0; i < info.linknames.size(); ++i)
+ info.linknames[i] = _stdwcstombs(pbody->GetLinks()[i]->GetName());
+ }
+ if( options & BodyInfo::Req_JointLimits ) {
+ vector<dReal> vlower, vupper;
+ pbody->GetJointLimits(vlower,vupper);
+ ROS_ASSERT( vlower.size() == vupper.size() );
+ info.lowerlimit.resize(vlower.size());
+ info.upperlimit.resize(vupper.size());
+ for(size_t i = 0; i < vlower.size(); ++i) {
+ info.lowerlimit[i] = vlower[i];...
[truncated message content] |
|
From: <pof...@us...> - 2008-12-07 14:57:40
|
Revision: 7752
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7752&view=rev
Author: poftwaresatent
Date: 2008-12-07 14:57:36 +0000 (Sun, 07 Dec 2008)
Log Message:
-----------
sbpl_util:
* number of state expansions added to planner stats (resolve #672)
mp_benchmarks:
* no more Valgrind in mkhtml-inc.sh (resolve #671)
* measuring and summarizing the number of state expansions and their speed (resolve #672)
* storing stats of planning failures as well as successes
highlevel_controllers:
* adapted move_base_sbpl to changes in sbpl_util
Modified Paths:
--------------
pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp
pkg/trunk/motion_planning/mp_benchmarks/mkhtml-inc.sh
pkg/trunk/motion_planning/mp_benchmarks/src/mpbench-incremental.cpp
pkg/trunk/motion_planning/mp_benchmarks/src/mpbench.cpp
pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.cpp
pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.hh
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp 2008-12-07 14:25:44 UTC (rev 7751)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_base_sbpl.cpp 2008-12-07 14:57:36 UTC (rev 7752)
@@ -345,6 +345,7 @@
&statsEntry.actual_time_wall_sec,
&statsEntry.actual_time_user_sec,
&statsEntry.actual_time_system_sec,
+ &statsEntry.number_of_expands,
&statsEntry.solution_cost,
&statsEntry.solution_epsilon,
&solutionStateIDs);
Modified: pkg/trunk/motion_planning/mp_benchmarks/mkhtml-inc.sh
===================================================================
--- pkg/trunk/motion_planning/mp_benchmarks/mkhtml-inc.sh 2008-12-07 14:25:44 UTC (rev 7751)
+++ pkg/trunk/motion_planning/mp_benchmarks/mkhtml-inc.sh 2008-12-07 14:57:36 UTC (rev 7752)
@@ -92,11 +92,13 @@
echo "extracting basename for $allopts"
basename=`$MPBENCH $allopts -X`
- echo "<a href=\" $basename.txt \"> log </a> <a href=\" cons-$basename.txt \"> cons </a> <a href=\" vg-$basename.txt \"> vg </a> <a href=\" $basename.png \"> png </a><br>" >> index.html
+ echo "<a href=\" $basename.txt \"> log </a> <a href=\" cons-$basename.txt \"> cons </a> <a href=\" $basename.png \"> png </a><br>" >> index.html
+## echo "<a href=\" $basename.txt \"> log </a> <a href=\" cons-$basename.txt \"> cons </a> <a href=\" vg-$basename.txt \"> vg </a> <a href=\" $basename.png \"> png </a><br>" >> index.html
echo "<a href=\" $basename.png \"><img src=\" small-$basename.png \" alt=\" $basename.png \"></a><br>" >> index.html
echo "running with $allopts -W"
- valgrind --log-file-exactly=vg-$basename.txt $MPBENCH $allopts -W 2>&1 | tee cons-$basename.txt
- chmod a+r vg-$basename.txt
+## valgrind --log-file-exactly=vg-$basename.txt $MPBENCH $allopts -W 2>&1 | tee cons-$basename.txt
+## chmod a+r vg-$basename.txt
+ $MPBENCH $allopts -W 2>&1 | tee cons-$basename.txt
cat $basename.html >> index.html
Modified: pkg/trunk/motion_planning/mp_benchmarks/src/mpbench-incremental.cpp
===================================================================
--- pkg/trunk/motion_planning/mp_benchmarks/src/mpbench-incremental.cpp 2008-12-07 14:25:44 UTC (rev 7751)
+++ pkg/trunk/motion_planning/mp_benchmarks/src/mpbench-incremental.cpp 2008-12-07 14:57:36 UTC (rev 7752)
@@ -81,11 +81,10 @@
static planList_t planList;
typedef map<waypoint_plan_t const *, SBPLPlannerStatsEntry> successStats_t;
-////typedef map<size_t, SBPLPlannerStatsEntry> failureStats_t;
+typedef map<size_t, SBPLPlannerStatsEntry> failureStats_t;
static successStats_t successStats;
-////static failureStats_t failureStats;
+static failureStats_t failureStats;
-
int main(int argc, char ** argv)
{
if (0 != atexit(cleanup))
@@ -588,6 +587,7 @@
double cumul_actual_time_wall(0);
double cumul_actual_time_user(0);
double cumul_actual_time_system(0);
+ ssize_t cumul_expands(0);
for (size_t jj(0); true; ++jj) {
// Handle the first iteration specially.
@@ -609,13 +609,24 @@
&statsEntry.actual_time_wall_sec,
&statsEntry.actual_time_user_sec,
&statsEntry.actual_time_system_sec,
+ &statsEntry.number_of_expands,
&statsEntry.solution_cost,
&statsEntry.solution_epsilon,
&solution);
+ // forget about this task if we got a planning failure
+ if ((1 != statsEntry.status) // planners should provide status
+ || (1 >= solution.size()) // but sometimes they do not
+ ) {
+ statsEntry.logStream(*logos, " FAILURE", " ");
+ *logos << flush;
+ failureStats.insert(make_pair(ii, statsEntry));
+ break;
+ }
+
// A little hack to make the initial solution appear as if it
// had used exactly the allocated time. Actually, it gets
- // allocated a practically inifinite amount of time, which is
+ // allocated a practically infinite amount of time, which is
// not useful for cumulating in the statistics. Also, it seems
// that SBPLPlanner uses wall time, not user time, to limit its
// search.
@@ -623,20 +634,8 @@
if (0 == jj)
statsEntry.allocated_time_sec = statsEntry.actual_time_wall_sec;
- // forget about this task if we got a planning failure
- if ((1 != statsEntry.status) // planners should provide status
- || (1 >= solution.size()) // but sometimes they do not
- ) {
- statsEntry.allocated_time_sec = cumul_allocated_time;
- statsEntry.actual_time_wall_sec = cumul_actual_time_wall;
- statsEntry.actual_time_user_sec = cumul_actual_time_user;
- statsEntry.actual_time_system_sec = cumul_actual_time_system;
- statsEntry.logStream(*logos, " FAILURE (below are cumulated times)", " ");
- *logos << flush;
- //// do NOT add to overall stats because of cumulated times
- // plannerStats.push_back(statsEntry);
- break;
- }
+ if (0 < statsEntry.number_of_expands)
+ cumul_expands += statsEntry.number_of_expands;
// detect whether we got the same result as before, in which
// case we're done
@@ -648,7 +647,8 @@
statsEntry.actual_time_wall_sec = cumul_actual_time_wall;
statsEntry.actual_time_user_sec = cumul_actual_time_user;
statsEntry.actual_time_system_sec = cumul_actual_time_system;
- statsEntry.logStream(*logos, " FINAL: epsilon did not change (below are cumulated times)", " ");
+ statsEntry.number_of_expands = cumul_expands;
+ statsEntry.logStream(*logos, " FINAL: epsilon did not change (below are cumulated times and expands)", " ");
*logos << flush;
//// do NOT add to overall stats because of cumulated times
// plannerStats.push_back(statsEntry);
@@ -669,7 +669,8 @@
statsEntry.actual_time_wall_sec = cumul_actual_time_wall;
statsEntry.actual_time_user_sec = cumul_actual_time_user;
statsEntry.actual_time_system_sec = cumul_actual_time_system;
- statsEntry.logStream(*logos, " FINAL: path states did not change (below are cumulated times)", " ");
+ statsEntry.number_of_expands = cumul_expands;
+ statsEntry.logStream(*logos, " FINAL: path states did not change (below are cumulated times and expands)", " ");
*logos << flush;
//// do NOT add to overall stats because of cumulated times
// plannerStats.push_back(statsEntry);
@@ -747,9 +748,12 @@
cout << "sorry, could not open file " << htmlFilename << "\n";
return;
}
+
+ //////////////////////////////////////////////////
+ // cumulated state expansions
htmlOs << "<table border=\"1\" cellpadding=\"2\">\n"
- << "<tr><th colspan=\"5\">consumed planning time (wall clock)</th></tr>\n"
+ << "<tr><th colspan=\"5\">cumulated state expansions</th></tr>\n"
<< "<tr><td>task</td><td>init</td><td>final</td><td>delta</td><td>% delta</td></tr>\n";
for (planList_t::const_iterator ip(planList.begin()); ip != planList.end(); ++ip) {
htmlOs << "<tr><td>" << ip->first << "</td>";
@@ -765,6 +769,103 @@
htmlOs << "<td colspan=\"4\"><em>error: no stats for initial solution</em></td></tr>\n";
continue;
}
+ if (1 == bundle.size()) {
+ htmlOs << "<td colspan=\"2\">" << initialStats->second.number_of_expands << "</td>"
+ << "<td colspan=\"2\">N/A</td></tr>\n";
+ continue;
+ }
+ ssize_t cumul_expands(initialStats->second.number_of_expands);
+ bool error(false);
+ for (++ib; ib != bundle.end(); ++ib) {
+ successStats_t::const_iterator stats(successStats.find(ib->get()));
+ if (successStats.end() == stats) {
+ error = true;
+ break;
+ }
+ cumul_expands += stats->second.number_of_expands;
+ }
+ if (error) {
+ htmlOs << "<td colspan=\"3\"><em>error: missing stats</em></td></tr>\n";
+ continue;
+ }
+ ssize_t const delta_expands(cumul_expands - initialStats->second.number_of_expands);
+ htmlOs << "<td>" << initialStats->second.number_of_expands << "</td>"
+ << "<td>" << cumul_expands << "</td>"
+ << "<td>" << delta_expands << "</td>"
+ << "<td>" << 1.0e2 * delta_expands / initialStats->second.number_of_expands
+ << "</td></tr>\n";
+ }
+
+ //////////////////////////////////////////////////
+ // expansions per second
+
+ htmlOs << "<table border=\"1\" cellpadding=\"2\">\n"
+ << "<tr><th colspan=\"5\">expansions speed [1/s] (wall clock)</th></tr>\n"
+ << "<tr><td>task</td><td>init</td><td>final</td><td>delta</td><td>% delta</td></tr>\n";
+ for (planList_t::const_iterator ip(planList.begin()); ip != planList.end(); ++ip) {
+ htmlOs << "<tr><td>" << ip->first << "</td>";
+ planBundle_t const & bundle(ip->second);
+ if (bundle.empty()) {
+ htmlOs << "<td colspan=\"4\"><em>no solution</em></td></tr>\n";
+ continue;
+ }
+ planBundle_t::const_iterator ib(bundle.begin());
+ waypoint_plan_t const * initialPlan(ib->get());
+ successStats_t::const_iterator initialStats(successStats.find(initialPlan));
+ if (successStats.end() == initialStats) {
+ htmlOs << "<td colspan=\"4\"><em>error: no stats for initial solution</em></td></tr>\n";
+ continue;
+ }
+ double cumul_time(initialStats->second.actual_time_wall_sec);
+ double cumul_expands(initialStats->second.number_of_expands);
+ double const init_speed(cumul_expands / cumul_time);
+ if (1 == bundle.size()) {
+ htmlOs << "<td colspan=\"2\">" << init_speed << "</td>"
+ << "<td colspan=\"2\">N/A</td></tr>\n";
+ continue;
+ }
+ bool error(false);
+ for (++ib; ib != bundle.end(); ++ib) {
+ successStats_t::const_iterator stats(successStats.find(ib->get()));
+ if (successStats.end() == stats) {
+ error = true;
+ break;
+ }
+ cumul_time += stats->second.actual_time_wall_sec;
+ cumul_expands += stats->second.number_of_expands;
+ }
+ if (error) {
+ htmlOs << "<td colspan=\"3\"><em>error: missing stats</em></td></tr>\n";
+ continue;
+ }
+ double const final_speed(cumul_expands / cumul_time);
+ double const delta_speed(final_speed - init_speed);
+ htmlOs << "<td>" << init_speed << "</td>"
+ << "<td>" << final_speed << "</td>"
+ << "<td>" << delta_speed << "</td>"
+ << "<td>" << 1.0e2 * delta_speed / init_speed
+ << "</td></tr>\n";
+ }
+
+ //////////////////////////////////////////////////
+ // consumed planning time
+
+ htmlOs << "<tr><th colspan=\"5\">consumed planning time (wall clock)</th></tr>\n"
+ << "<tr><td>task</td><td>init</td><td>final</td><td>delta</td><td>% delta</td></tr>\n";
+ for (planList_t::const_iterator ip(planList.begin()); ip != planList.end(); ++ip) {
+ htmlOs << "<tr><td>" << ip->first << "</td>";
+ planBundle_t const & bundle(ip->second);
+ if (bundle.empty()) {
+ htmlOs << "<td colspan=\"4\"><em>no solution</em></td></tr>\n";
+ continue;
+ }
+ planBundle_t::const_iterator ib(bundle.begin());
+ waypoint_plan_t const * initialPlan(ib->get());
+ successStats_t::const_iterator initialStats(successStats.find(initialPlan));
+ if (successStats.end() == initialStats) {
+ htmlOs << "<td colspan=\"4\"><em>error: no stats for initial solution</em></td></tr>\n";
+ continue;
+ }
double cumul(initialStats->second.actual_time_wall_sec);
if (1 == bundle.size()) {
htmlOs << "<td colspan=\"2\">" << timeStr(cumul) << "</td>"
@@ -792,6 +893,9 @@
<< "</td></tr>\n";
}
+ //////////////////////////////////////////////////
+ // epsilon
+
htmlOs << "<tr><th colspan=\"5\">epsilon</th></tr>\n"
<< "<tr><td>task</td><td>init</td><td>final</td><td>delta</td><td>% delta</td></tr>\n";
for (planList_t::const_iterator ip(planList.begin()); ip != planList.end(); ++ip) {
@@ -826,6 +930,9 @@
<< "<td>" << 1.0e2 * delta / initialStats->second.solution_epsilon << "</td></tr>\n";
}
+ //////////////////////////////////////////////////
+ // plan length
+
htmlOs << "<tr><th colspan=\"5\">plan length [m]</th></tr>\n"
<< "<tr><td>task</td><td>init</td><td>final</td><td>delta</td><td>% delta</td></tr>\n";
for (planList_t::const_iterator ip(planList.begin()); ip != planList.end(); ++ip) {
@@ -860,6 +967,9 @@
<< "<td>" << 1.0e2 * delta / initialStats->second.plan_length_m
<< "</td></tr>\n";
}
+
+ //////////////////////////////////////////////////
+ // plan tangent change
htmlOs << "<tr><th colspan=\"5\">plan tangent change [deg]</th></tr>\n"
<< "<tr><td>task</td><td>init</td><td>final</td><td>delta</td><td>% delta</td></tr>\n";
Modified: pkg/trunk/motion_planning/mp_benchmarks/src/mpbench.cpp
===================================================================
--- pkg/trunk/motion_planning/mp_benchmarks/src/mpbench.cpp 2008-12-07 14:25:44 UTC (rev 7751)
+++ pkg/trunk/motion_planning/mp_benchmarks/src/mpbench.cpp 2008-12-07 14:57:36 UTC (rev 7752)
@@ -606,6 +606,7 @@
&statsEntry.actual_time_wall_sec,
&statsEntry.actual_time_user_sec,
&statsEntry.actual_time_system_sec,
+ &statsEntry.number_of_expands,
&statsEntry.solution_cost,
&statsEntry.solution_epsilon,
&solutionStateIDs);
Modified: pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.cpp
===================================================================
--- pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.cpp 2008-12-07 14:25:44 UTC (rev 7751)
+++ pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.cpp 2008-12-07 14:57:36 UTC (rev 7752)
@@ -163,6 +163,7 @@
double * actual_time_wall_sec,
double * actual_time_user_sec,
double * actual_time_system_sec,
+ ssize_t * number_of_expands,
int * solution_cost,
double * solution_epsilon,
vector<int>* solution_stateIDs_V) throw(no_planner_selected)
@@ -184,12 +185,13 @@
gettimeofday(&t_started, 0);
int const status(planner_->replan(allocated_time_sec, solution_stateIDs_V, solution_cost));
-
+
struct rusage ru_finished;
struct timeval t_finished;
getrusage(RUSAGE_SELF, &ru_finished);
gettimeofday(&t_finished, 0);
+ *number_of_expands = planner_->get_n_expands();
*solution_epsilon = planner_->get_solution_eps();
*actual_time_wall_sec =
@@ -299,6 +301,7 @@
<< prefix << "time actual (wall) [ms]: " << 1.0e3 * actual_time_wall_sec << "\n"
<< prefix << "time actual (user) [ms]: " << 1.0e3 * actual_time_user_sec << "\n"
<< prefix << "time actual (system) [ms]: " << 1.0e3 * actual_time_system_sec << "\n"
+ << prefix << "number of expands: " << number_of_expands << "\n"
<< prefix << "solution cost: " << solution_cost << "\n"
<< prefix << "solution epsilon: " << solution_epsilon << "\n"
<< prefix << "status (1 == SUCCESS): " << status << "\n"
Modified: pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.hh
===================================================================
--- pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.hh 2008-12-07 14:25:44 UTC (rev 7751)
+++ pkg/trunk/motion_planning/sbpl_util/src/sbpl_util.hh 2008-12-07 14:57:36 UTC (rev 7752)
@@ -113,6 +113,7 @@
double actual_time_system_sec; /**< the amount of time actually used for planning (system time) */
int status; /**< return value of replan() (i.e. success == 1, or -42 if replan() never got called) */
+ ssize_t number_of_expands; /**< number of state expansions, or -1 if not available */
int solution_cost; /**< cost of the solution, as given by replan() */
double solution_epsilon; /**< the "epsilon" value used to compute the solution */
double plan_length_m; /**< cumulated Euclidean distance between planned waypoints */
@@ -194,6 +195,8 @@
double * actual_time_user_sec,
/** out: how much time was actually used by the planner (system time) */
double * actual_time_system_sec,
+ /** out: number of state expansions (or -1 if not available) */
+ ssize_t * number_of_expands,
/** out: the cost of the planned path */
int * solution_cost,
/** out: the epsilon-value of the planned path */
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2008-12-09 08:19:09
|
Revision: 7796
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7796&view=rev
Author: tfoote
Date: 2008-12-09 08:19:00 +0000 (Tue, 09 Dec 2008)
Log Message:
-----------
removing rosTF from planning_node_util and disabling build of world_3d_map for now until it can be ported to the new tf
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
pkg/trunk/motion_planning/planning_node_util/manifest.xml
pkg/trunk/world_models/world_3d_map/manifest.xml
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Added Paths:
-----------
pkg/trunk/world_models/world_3d_map/ROS_BUILD_BLACKLIST
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-12-09 04:36:16 UTC (rev 7795)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-12-09 08:19:00 UTC (rev 7796)
@@ -48,7 +48,7 @@
#include <urdf/URDF.h>
#include <planning_models/kinematic.h>
#include <std_msgs/RobotBase2DOdom.h>
-#include <rosTF/rosTF.h>
+#include <tf/transform_listener.h>
#include <cmath>
#include <robot_msgs/MechanismState.h>
@@ -88,8 +88,9 @@
public:
- NodeRobotModel(ros::node *node, const std::string &robot_model) : m_tf(*node, true, 1 * 1000000000ULL, 1000000000ULL)
+ NodeRobotModel(ros::node *node, const std::string &robot_model) : m_tf(*node, true, 1000000000ULL)
{
+ m_tf.setExtrapolationLimit(ros::Duration().fromSec(10));
m_urdf = NULL;
m_kmodel = NULL;
m_kmodelSimple = NULL;
@@ -198,46 +199,46 @@
void localizedPoseCallback(void)
{
bool success = true;
- libTF::TFPose2D pose;
- pose.x = m_localizedPose.pos.x;
- pose.y = m_localizedPose.pos.y;
- pose.yaw = m_localizedPose.pos.th;
- pose.time = m_localizedPose.header.stamp.to_ull();
- pose.frame = m_localizedPose.header.frame_id;
-
+ tf::Stamped<tf::Pose> pose (tf::Transform(tf::Quaternion(m_localizedPose.pos.th, 0, 0),
+ tf::Point(m_localizedPose.pos.x,
+ m_localizedPose.pos.y, 0)),
+ m_localizedPose.header.stamp,
+ m_localizedPose.header.frame_id);
try
{
- pose = m_tf.transformPose2D("map", pose);
+ m_tf.transformPose("map", pose, pose);
}
- catch(libTF::TransformReference::LookupException& ex)
+ catch(tf::LookupException& ex)
{
- fprintf(stderr, "Discarding pose: from %s, Transform reference lookup exception: %s\n", pose.frame.c_str(), ex.what());
+ fprintf(stderr, "Discarding pose: from %s, Transform reference lookup exception: %s\n", pose.frame_id_.c_str(), ex.what());
success = false;
}
- catch(libTF::TransformReference::ExtrapolateException& ex)
+ catch(tf::ExtrapolationException& ex)
{
- fprintf(stderr, "Discarding pose: from %s, Extrapolation exception: %s\n", pose.frame.c_str(), ex.what());
+ fprintf(stderr, "Discarding pose: from %s, Extrapolation exception: %s\n", pose.frame_id_.c_str(), ex.what());
success = false;
}
- catch(libTF::TransformReference::ConnectivityException& ex)
+ catch(tf::ConnectivityException& ex)
{
- fprintf(stderr, "Discarding pose: from %s, Connectivity exception: %s\n", pose.frame.c_str(), ex.what());
+ fprintf(stderr, "Discarding pose: from %s, Connectivity exception: %s\n", pose.frame_id_.c_str(), ex.what());
success = false;
}
- catch(...)
+ catch(tf::TransformException)
{
- fprintf(stderr, "Discarding pose: from %s, Exception in pose computation\n", pose.frame.c_str());
+ fprintf(stderr, "Discarding pose: from %s, Exception in pose computation\n", pose.frame_id_.c_str());
success = false;
}
if (success)
{
- if (isfinite(pose.x))
- m_basePos[0] = pose.x;
- if (isfinite(pose.y))
- m_basePos[1] = pose.y;
- if (isfinite(pose.yaw))
- m_basePos[2] = pose.yaw;
+ if (isfinite(pose.getOrigin().x()))
+ m_basePos[0] = pose.getOrigin().x();
+ if (isfinite(pose.getOrigin().y()))
+ m_basePos[1] = pose.getOrigin().y();
+ double yaw, pitch, roll;
+ pose.getBasis().getEulerZYX(yaw, pitch, roll);
+ if (isfinite(yaw))
+ m_basePos[2] = yaw;
m_haveBasePos = true;
baseUpdate();
}
@@ -292,7 +293,7 @@
m_haveState = m_haveBasePos && m_haveMechanismState;
}
- rosTFClient m_tf;
+ tf::TransformListener m_tf;
ros::node *m_node;
std_msgs::RobotBase2DOdom m_localizedPose;
bool m_haveBasePos;
Modified: pkg/trunk/motion_planning/planning_node_util/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/manifest.xml 2008-12-09 04:36:16 UTC (rev 7795)
+++ pkg/trunk/motion_planning/planning_node_util/manifest.xml 2008-12-09 08:19:00 UTC (rev 7796)
@@ -11,7 +11,7 @@
<depend package="roscpp"/>
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
- <depend package="rosTF"/>
+ <depend package="tf"/>
<depend package="wg_robot_description_parser"/>
<depend package="planning_models"/>
<depend package="collision_space"/>
Added: pkg/trunk/world_models/world_3d_map/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/world_models/world_3d_map/ROS_BUILD_BLACKLIST (rev 0)
+++ pkg/trunk/world_models/world_3d_map/ROS_BUILD_BLACKLIST 2008-12-09 08:19:00 UTC (rev 7796)
@@ -0,0 +1,3 @@
+blacklisting this for I am trying to convert to the new tf. This is on the list to be reworked with a better sense of persistance. If you need this back soon let me know.
+
+--Tully
\ No newline at end of file
Modified: pkg/trunk/world_models/world_3d_map/manifest.xml
===================================================================
--- pkg/trunk/world_models/world_3d_map/manifest.xml 2008-12-09 04:36:16 UTC (rev 7795)
+++ pkg/trunk/world_models/world_3d_map/manifest.xml 2008-12-09 08:19:00 UTC (rev 7796)
@@ -5,7 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp" />
<depend package="std_msgs" />
-<depend package="rosTF" />
+<depend package="tf" /> <!-- Code not changed from rosTF yet -->
<depend package="laser_scan" />
<depend package="random_utils" />
<depend package="wg_robot_description_parser" />
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-09 04:36:16 UTC (rev 7795)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-12-09 08:19:00 UTC (rev 7796)
@@ -140,15 +140,6 @@
m_acceptScans = false;
random_utils::init(&m_rng);
- /// @todo Find a way to make this work for pr2, with mechanism control,
- /// but not break for STAIR. Somebody needs to be periodically
- /// publishing the base->base_laser Tx. Or else we need a more standard
- /// way of retrieving such Txs;
- /* Set up the transform client */
- double laser_x_offset;
- param("laser_x_offset", laser_x_offset, 0.275);
- m_tf.setWithEulers("base_laser", "base_link", laser_x_offset, 0.0, 0.0, 0.0, 0.0, 0.0, 0);
-
/* create a thread that handles the publishing of the data */
m_publishingThread = ros::thread::member_thread::startMemberFunctionThread<World3DMap>(this, &World3DMap::publishDataThread);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2008-12-09 08:54:13
|
Revision: 7797
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7797&view=rev
Author: tfoote
Date: 2008-12-09 08:54:08 +0000 (Tue, 09 Dec 2008)
Log Message:
-----------
removing all dependencies on rosTF. Temporarily moving old message formats into tf before converting to new type only.
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
pkg/trunk/demos/2dnav_gazebo/manifest.xml
pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/util/tf/include/tf/message_notifier.h
pkg/trunk/util/tf/include/tf/transform_broadcaster.h
pkg/trunk/util/tf/include/tf/transform_listener.h
pkg/trunk/util/tf/manifest.xml
pkg/trunk/util/tf/src/transform_listener.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/robot_model_display.cpp
Added Paths:
-----------
pkg/trunk/util/tf/msg/TransformArray.msg
pkg/trunk/util/tf/msg/TransformDH.msg
pkg/trunk/util/tf/msg/TransformEuler.msg
pkg/trunk/util/tf/msg/TransformMatrix.msg
pkg/trunk/util/tf/msg/TransformQuaternion.msg
Removed Paths:
-------------
pkg/trunk/util/rosTF/msg/TransformArray.msg
pkg/trunk/util/rosTF/msg/TransformDH.msg
pkg/trunk/util/rosTF/msg/TransformEuler.msg
pkg/trunk/util/rosTF/msg/TransformMatrix.msg
pkg/trunk/util/rosTF/msg/TransformQuaternion.msg
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h 2008-12-09 08:54:08 UTC (rev 7797)
@@ -59,8 +59,7 @@
#include <misc_utils/realtime_publisher.h>
-#include <rosTF/rosTF.h>
-#include <rosTF/TransformEuler.h>
+#include <tf/TransformArray.h>
#include <pthread.h>
@@ -476,7 +475,7 @@
misc_utils::RealtimePublisher <std_msgs::RobotBase2DOdom>* publisher_ ; //!< Publishes the odometry msg from the update() realtime loop
- misc_utils::RealtimePublisher <rosTF::TransformArray>* transform_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
+ misc_utils::RealtimePublisher <tf::TransformArray>* transform_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
misc_utils::RealtimePublisher <pr2_msgs::Odometer>* odometer_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2008-12-09 08:54:08 UTC (rev 7797)
@@ -13,7 +13,6 @@
<depend package="robot_mechanism_controllers" />
<depend package="rospy" />
<depend package="libTF" />
- <depend package="rosTF" />
<depend package="std_msgs" />
<depend package="pr2_msgs" />
<depend package="robot_kinematics" />
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2008-12-09 08:54:08 UTC (rev 7797)
@@ -810,7 +810,7 @@
{
double x=0,y=0,yaw=0,vx,vy,vyaw;
this->getOdometry(x,y,yaw,vx,vy,vyaw);
- rosTF::TransformEuler &out = transform_publisher_->msg_.eulers[0];
+ tf::TransformEuler &out = transform_publisher_->msg_.eulers[0];
out.header.stamp.from_double(time);
out.header.frame_id = "odom";
out.parent = "base_footprint";
@@ -822,7 +822,7 @@
out.yaw = angles::normalize_angle(-yaw);
- rosTF::TransformEuler &out2 = transform_publisher_->msg_.eulers[1];
+ tf::TransformEuler &out2 = transform_publisher_->msg_.eulers[1];
out2.header.stamp.from_double(time);
out2.header.frame_id = "base_footprint";
out2.parent = "base_link";
@@ -936,7 +936,7 @@
if (transform_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete transform_publisher_ ;
- transform_publisher_ = new misc_utils::RealtimePublisher <rosTF::TransformArray> ("TransformArray", 5) ;
+ transform_publisher_ = new misc_utils::RealtimePublisher <tf::TransformArray> ("TransformArray", 5) ;
node->param<double>("base_controller/odom_publish_rate",odom_publish_rate_,100);
Modified: pkg/trunk/demos/2dnav_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/manifest.xml 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/demos/2dnav_gazebo/manifest.xml 2008-12-09 08:54:08 UTC (rev 7797)
@@ -15,7 +15,7 @@
<depend package="teleop_arm_keyboard"/>
<depend package="laser_view"/>
<depend package="pr2_gui"/>
- <depend package="world_3d_map"/>
+ <!--depend package="world_3d_map"/ Commented due to breaking 12/9/08 Tully-->
<depend package="highlevel_controllers"/>
<depend package="executive_trex_pr2"/>
<depend package="robot_pose_ekf"/>
Modified: pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
===================================================================
--- pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h 2008-12-09 08:54:08 UTC (rev 7797)
@@ -51,7 +51,7 @@
#include <robot_srvs/SpawnController.h>
#include <robot_srvs/KillController.h>
#include <robot_msgs/MechanismState.h>
-#include "rosTF/TransformArray.h"
+#include "tf/TransformArray.h"
typedef controller::Controller* (*ControllerAllocator)();
@@ -129,7 +129,7 @@
const char* const mechanism_state_topic_;
misc_utils::RealtimePublisher<robot_msgs::MechanismState> publisher_;
- misc_utils::RealtimePublisher<rosTF::TransformArray> transform_publisher_;
+ misc_utils::RealtimePublisher<tf::TransformArray> transform_publisher_;
AdvertisedServiceGuard list_controllers_guard_, list_controller_types_guard_,
spawn_controller_guard_, kill_controller_guard_;
Modified: pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-12-09 08:54:08 UTC (rev 7797)
@@ -304,7 +304,7 @@
tf::Vector3 pos = mc_->state_->link_states_[i].rel_frame_.getOrigin();
tf::Quaternion quat = mc_->state_->link_states_[i].rel_frame_.getRotation();
- rosTF::TransformQuaternion &out = transform_publisher_.msg_.quaternions[ti++];
+ tf::TransformQuaternion &out = transform_publisher_.msg_.quaternions[ti++];
out.header.stamp.fromSec(mc_->hw_->current_time_);
out.header.frame_id = mc_->model_.links_[i]->name_;
Deleted: pkg/trunk/util/rosTF/msg/TransformArray.msg
===================================================================
--- pkg/trunk/util/rosTF/msg/TransformArray.msg 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/rosTF/msg/TransformArray.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -1,5 +0,0 @@
-Header header
-TransformEuler[] eulers
-TransformQuaternion[] quaternions
-TransformDH[] dhparams
-TransformMatrix[] matrices
Deleted: pkg/trunk/util/rosTF/msg/TransformDH.msg
===================================================================
--- pkg/trunk/util/rosTF/msg/TransformDH.msg 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/rosTF/msg/TransformDH.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -1,6 +0,0 @@
-Header header
-string parent
-float64 length
-float64 twist
-float64 offset
-float64 angle
\ No newline at end of file
Deleted: pkg/trunk/util/rosTF/msg/TransformEuler.msg
===================================================================
--- pkg/trunk/util/rosTF/msg/TransformEuler.msg 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/rosTF/msg/TransformEuler.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -1,8 +0,0 @@
-Header header
-string parent
-float64 x
-float64 y
-float64 z
-float64 yaw
-float64 pitch
-float64 roll
Deleted: pkg/trunk/util/rosTF/msg/TransformMatrix.msg
===================================================================
--- pkg/trunk/util/rosTF/msg/TransformMatrix.msg 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/rosTF/msg/TransformMatrix.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -1,3 +0,0 @@
-Header header
-string parent
-float64[] matrix #always 16 elements a 4x4 matrix unwrapped as row major
\ No newline at end of file
Deleted: pkg/trunk/util/rosTF/msg/TransformQuaternion.msg
===================================================================
--- pkg/trunk/util/rosTF/msg/TransformQuaternion.msg 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/rosTF/msg/TransformQuaternion.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -1,9 +0,0 @@
-Header header
-string parent
-float64 xt
-float64 yt
-float64 zt
-float64 xr
-float64 yr
-float64 zr
-float64 w
Modified: pkg/trunk/util/tf/include/tf/message_notifier.h
===================================================================
--- pkg/trunk/util/tf/include/tf/message_notifier.h 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/tf/include/tf/message_notifier.h 2008-12-09 08:54:08 UTC (rev 7797)
@@ -42,7 +42,7 @@
#include <boost/thread.hpp>
/// \todo remove backward compatability
-#include "rosTF/TransformArray.h"
+#include "tf/TransformArray.h"
namespace tf
{
@@ -446,7 +446,7 @@
Message message_; ///< The incoming message
tfMessage transforms_message_; ///< The incoming TF transforms message
- rosTF::TransformArray old_transforms_message_; ///< The incoming old TF (rosTF) TransformArray message
+ tf::TransformArray old_transforms_message_; ///< The incoming old TF (rosTF) TransformArray message
bool destructing_; ///< Used to notify the worker thread that it needs to shutdown
boost::thread* thread_handle_; ///< Thread handle for the worker thread
Modified: pkg/trunk/util/tf/include/tf/transform_broadcaster.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_broadcaster.h 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/tf/include/tf/transform_broadcaster.h 2008-12-09 08:54:08 UTC (rev 7797)
@@ -37,7 +37,7 @@
#include "tf/tf.h"
#include "tf/tfMessage.h"
///\todo only for backwards compatabilty, remove!
-#include "rosTF/TransformArray.h"
+#include "tf/TransformArray.h"
namespace tf
{
@@ -54,7 +54,7 @@
{
node_.advertise<tfMessage>("/tf_message", 100);
///\todo remove when no longer backwards compatable
- node_.advertise<rosTF::TransformArray>("TransformArray", 100);
+ node_.advertise<tf::TransformArray>("TransformArray", 100);
};
/** \brief Send a Stamped<Transform> with parent parent_id
* The stamped data structure includes frame_id, and time, and parent_id already. */
@@ -67,7 +67,7 @@
///\todo removed for non collision with backwards compatability node_.publish("/tf_message", message);
///\todo only for backwards compatabilty, remove!
- rosTF::TransformArray tfArray;
+ tf::TransformArray tfArray;
tfArray.set_quaternions_size(1);
tfArray.quaternions[0].header.frame_id = transform.frame_id_;
@@ -99,7 +99,7 @@
///\todo removed for non collision with backwards compatability node_.publish("/tf_message", message);
///\todo only for backwards compatabilty, remove!
- rosTF::TransformArray tfArray;
+ tf::TransformArray tfArray;
tfArray.set_quaternions_size(1);
tfArray.quaternions[0].header.frame_id = frame_id;
Modified: pkg/trunk/util/tf/include/tf/transform_listener.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-09 08:54:08 UTC (rev 7797)
@@ -39,7 +39,7 @@
#include "ros/node.h"
/// \todo remove backward compatability only
-#include "rosTF/TransformArray.h"
+#include "tf/TransformArray.h"
// end remove
namespace tf{
@@ -52,7 +52,7 @@
/// \todo remove backward compatability only
//Temporary storage for callbacks(todo check threadsafe? make scoped in call?)
- rosTF::TransformArray tfArrayIn;
+ tf::TransformArray tfArrayIn;
public:
/**@brief Constructor for transform listener
Modified: pkg/trunk/util/tf/manifest.xml
===================================================================
--- pkg/trunk/util/tf/manifest.xml 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/tf/manifest.xml 2008-12-09 08:54:08 UTC (rev 7797)
@@ -16,7 +16,6 @@
<depend package="roscpp"/>
<depend package="bullet"/>
<depend package="laser_scan"/>
-<depend package="rosTF"/> <!-- For backwards compatibility only Fixme remove /-->
<depend package="boost"/>
<export>
<cpp cflags="-I${prefix}/include -I${prefix}/msg/cpp" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -ltf"/>
Copied: pkg/trunk/util/tf/msg/TransformArray.msg (from rev 2888, pkg/trunk/util/rosTF/msg/TransformArray.msg)
===================================================================
--- pkg/trunk/util/tf/msg/TransformArray.msg (rev 0)
+++ pkg/trunk/util/tf/msg/TransformArray.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -0,0 +1,5 @@
+Header header ### DO NOT USE THIS MESSAGE IT"S BEING PHASED OUT
+TransformEuler[] eulers
+TransformQuaternion[] quaternions
+TransformDH[] dhparams
+TransformMatrix[] matrices
Copied: pkg/trunk/util/tf/msg/TransformDH.msg (from rev 3240, pkg/trunk/util/rosTF/msg/TransformDH.msg)
===================================================================
--- pkg/trunk/util/tf/msg/TransformDH.msg (rev 0)
+++ pkg/trunk/util/tf/msg/TransformDH.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -0,0 +1,6 @@
+Header header # DO NO USE MESSAGE
+string parent
+float64 length
+float64 twist
+float64 offset
+float64 angle
\ No newline at end of file
Copied: pkg/trunk/util/tf/msg/TransformEuler.msg (from rev 3240, pkg/trunk/util/rosTF/msg/TransformEuler.msg)
===================================================================
--- pkg/trunk/util/tf/msg/TransformEuler.msg (rev 0)
+++ pkg/trunk/util/tf/msg/TransformEuler.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -0,0 +1,8 @@
+Header header # DO NOT USE MESSAGE
+string parent
+float64 x
+float64 y
+float64 z
+float64 yaw
+float64 pitch
+float64 roll
Copied: pkg/trunk/util/tf/msg/TransformMatrix.msg (from rev 3240, pkg/trunk/util/rosTF/msg/TransformMatrix.msg)
===================================================================
--- pkg/trunk/util/tf/msg/TransformMatrix.msg (rev 0)
+++ pkg/trunk/util/tf/msg/TransformMatrix.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -0,0 +1,3 @@
+Header header # DO NOT USE MESSAGE
+string parent
+float64[] matrix #always 16 elements a 4x4 matrix unwrapped as row major
\ No newline at end of file
Copied: pkg/trunk/util/tf/msg/TransformQuaternion.msg (from rev 3240, pkg/trunk/util/rosTF/msg/TransformQuaternion.msg)
===================================================================
--- pkg/trunk/util/tf/msg/TransformQuaternion.msg (rev 0)
+++ pkg/trunk/util/tf/msg/TransformQuaternion.msg 2008-12-09 08:54:08 UTC (rev 7797)
@@ -0,0 +1,9 @@
+Header header #DO NOT USE MESSAGE
+string parent
+float64 xt
+float64 yt
+float64 zt
+float64 xr
+float64 yr
+float64 zr
+float64 w
Modified: pkg/trunk/util/tf/src/transform_listener.cpp
===================================================================
--- pkg/trunk/util/tf/src/transform_listener.cpp 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/util/tf/src/transform_listener.cpp 2008-12-09 08:54:08 UTC (rev 7797)
@@ -280,7 +280,7 @@
{
///\todo Use error reporting
std::string temp = ex.what();
- printf("Failure to set recieved transform %s to %s with error: %s\n", msg_in_.transforms[i].header.frame_id.c_str(), msg_in_.transforms[i].parent_id.c_str(), temp.c_str());
+ ROS_ERROR("Failure to set recieved transform %s to %s with error: %s\n", msg_in_.transforms[i].header.frame_id.c_str(), msg_in_.transforms[i].parent_id.c_str(), temp.c_str());
}
}
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/robot_model_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/robot_model_display.cpp 2008-12-09 08:19:00 UTC (rev 7796)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/robot_model_display.cpp 2008-12-09 08:54:08 UTC (rev 7797)
@@ -33,8 +33,8 @@
#include "properties/property.h"
#include "properties/property_manager.h"
+#include "ros/node.h"
#include "urdf/URDF.h"
-#include "rosTF/rosTF.h"
#include <OgreSceneNode.h>
#include <OgreSceneManager.h>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2008-12-09 11:01:18
|
Revision: 7805
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7805&view=rev
Author: tfoote
Date: 2008-12-09 11:01:14 +0000 (Tue, 09 Dec 2008)
Log Message:
-----------
moving libTF to deprecated to be clear it's unsupported, but I'm not actively going to remove it like rosTF
Added Paths:
-----------
pkg/trunk/deprecated/libTF/
Removed Paths:
-------------
pkg/trunk/util/libTF/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-12-09 22:21:08
|
Revision: 7835
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7835&view=rev
Author: hsujohnhsu
Date: 2008-12-09 22:21:04 +0000 (Tue, 09 Dec 2008)
Log Message:
-----------
* collisions are reported through ROS topic base_bumper for now.
* udpate bumper and ros_bumper plugin to report collision.
* implemented contact sensor and bumper controller for base as an example.
* patched gazebo to return geom name and contact geom name as well.
Modified Paths:
--------------
pkg/trunk/3rdparty/gazebo/gazebo_patch.diff
pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Bumper.hh
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Bumper.cc
pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.py
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml
Modified: pkg/trunk/3rdparty/gazebo/gazebo_patch.diff
===================================================================
--- pkg/trunk/3rdparty/gazebo/gazebo_patch.diff 2008-12-09 22:19:32 UTC (rev 7834)
+++ pkg/trunk/3rdparty/gazebo/gazebo_patch.diff 2008-12-09 22:21:04 UTC (rev 7835)
@@ -1834,6 +1834,83 @@
Ogre::HardwarePixelBufferSharedPtr mBuffer;
std::ostringstream sstream;
Ogre::ImageCodec::ImageData *imgData;
+Index: server/sensors/contact/ContactSensor.hh
+===================================================================
+--- server/sensors/contact/ContactSensor.hh (revision 7168)
++++ server/sensors/contact/ContactSensor.hh (working copy)
+@@ -68,6 +68,12 @@
+ /// \brief Return a contact state
+ public: uint8_t GetContactState(unsigned int index) const;
+
++ /// \brief Return contact geometry name
++ public: std::string GetContactGeomName(unsigned int index) const;
++
++ /// \brief Return geometry name
++ public: std::string GetGeomName(unsigned int index) const;
++
+ /// \brief Reset the contact states
+ public: void ResetContactStates();
+
+@@ -93,9 +99,11 @@
+ /// Geom name parameter
+ private: std::vector< ParamT<std::string> *> geomNamesP;
+
++ private: std::vector<std::string> geomNames;
+ private: uint8_t *contactStates;
+ private: double *contactTimes;
+ private: unsigned int contactCount;
++ private: std::vector<std::string> contactNames;
+ };
+ /// \}
+ /// \}
+Index: server/sensors/contact/ContactSensor.cc
+===================================================================
+--- server/sensors/contact/ContactSensor.cc (revision 7168)
++++ server/sensors/contact/ContactSensor.cc (working copy)
+@@ -107,6 +107,26 @@
+ }
+
+ //////////////////////////////////////////////////////////////////////////////
++/// Return the contact geom name
++std::string ContactSensor::GetContactGeomName(unsigned int index) const
++{
++ if (index < this->contactCount)
++ return this->contactNames[index];
++
++ return std::string("");
++}
++
++//////////////////////////////////////////////////////////////////////////////
++/// Return the self geom name
++std::string ContactSensor::GetGeomName(unsigned int index) const
++{
++ if (index < this->contactCount)
++ return this->geomNamesP[index]->GetValue();
++
++ return std::string("");
++}
++
++//////////////////////////////////////////////////////////////////////////////
+ /// Reset the contact states
+ void ContactSensor::ResetContactStates()
+ {
+@@ -138,6 +158,8 @@
+ this->contactCount = this->geomNamesP.size();
+ this->contactTimes = new double[ this->contactCount ];
+ this->contactStates = new uint8_t[ this->contactCount ];
++ for (unsigned int i=0; i< this->contactCount; i++)
++ this->contactNames.push_back("");
+
+ memset(this->contactStates,0, sizeof(uint8_t) * this->contactCount);
+ memset(this->contactStates,0, sizeof(double) * this->contactCount);
+@@ -206,6 +228,7 @@
+ {
+ this->contactStates[i] = 1;
+ this->contactTimes[i] = Simulator::Instance()->GetRealTime();
++ this->contactNames[i] = **(*iter)==g1->GetName()? g2->GetName() : g1->GetName();
+ }
+ }
+
Index: server/sensors/ray/RaySensor.hh
===================================================================
--- server/sensors/ray/RaySensor.hh (revision 7168)
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-12-09 22:19:32 UTC (rev 7834)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-12-09 22:21:04 UTC (rev 7835)
@@ -19,6 +19,7 @@
rospack_add_library(F3D src/F3D.cc)
rospack_add_library(gazebo_mechanism_control src/gazebo_mechanism_control.cpp)
rospack_add_library(gazebo_battery src/gazebo_battery.cpp)
+rospack_add_library(Ros_Bumper src/Ros_Bumper.cc)
# This target requires adding player to the manifest.xml.
#rospack_add_executable(player_pr2 src/player/Pr2_Player.cc)
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Bumper.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Bumper.hh 2008-12-09 22:19:32 UTC (rev 7834)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_Bumper.hh 2008-12-09 22:21:04 UTC (rev 7835)
@@ -28,9 +28,14 @@
#include <sys/time.h>
-#include "Controller.hh"
-#include "Entity.hh"
+#include <gazebo/Controller.hh>
+#include <gazebo/Entity.hh>
+#include <gazebo/Param.hh>
+// ros messages
+#include <ros/node.h>
+#include <std_msgs/String.h>
+
namespace gazebo
{
class ContactSensor;
@@ -86,7 +91,20 @@
/// The parent Model
private: ContactSensor *myParent;
-
+
+
+ /// \brief pointer to ros node
+ private: ros::node *rosnode;
+
+ /// \brief set topic name of broadcast
+ private: ParamT<std::string> *bumperTopicNameP;
+ private: std::string bumperTopicName;
+
+ /// \brief A mutex to lock access to fields that are used in message callbacks
+ private: ros::thread::mutex lock;
+
+ /// \brief broadcast some string for now.
+ private: std_msgs::String bumperMsg;
};
/** \} */
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Bumper.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Bumper.cc 2008-12-09 22:19:32 UTC (rev 7834)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Bumper.cc 2008-12-09 22:21:04 UTC (rev 7835)
@@ -24,14 +24,14 @@
* Date: 09 Setp. 2008
*/
-#include "Global.hh"
-#include "XMLConfig.hh"
+#include "gazebo/Global.hh"
+#include "gazebo/XMLConfig.hh"
#include "ContactSensor.hh"
-#include "World.hh"
-#include "gazebo.h"
-#include "GazeboError.hh"
-#include "ControllerFactory.hh"
-#include "Simulator.hh"
+#include "gazebo/World.hh"
+#include "gazebo/gazebo.h"
+#include "gazebo/GazeboError.hh"
+#include "gazebo/ControllerFactory.hh"
+#include "gazebo/Simulator.hh"
#include "gazebo_plugin/Ros_Bumper.hh"
using namespace gazebo;
@@ -47,18 +47,40 @@
if (!this->myParent)
gzthrow("Bumper controller requires a Contact Sensor as its parent");
+
+ Param::Begin(&this->parameters);
+ this->bumperTopicNameP = new ParamT<std::string>("bumperTopicName", "bumper", 0);
+ Param::End();
+
+ rosnode = ros::g_node; // comes from where?
+ int argc = 0;
+ char** argv = NULL;
+ if (rosnode == NULL)
+ {
+ // this only works for a single camera.
+ ros::init(argc,argv);
+ rosnode = new ros::node("ros_gazebo",ros::node::DONT_HANDLE_SIGINT);
+ printf("-------------------- starting node in bumper \n");
+ }
+
}
////////////////////////////////////////////////////////////////////////////////
// Destructor
Ros_Bumper::~Ros_Bumper()
{
+ delete this->bumperTopicNameP;
}
////////////////////////////////////////////////////////////////////////////////
// Load the controller
void Ros_Bumper::LoadChild(XMLConfigNode *node)
{
+ this->bumperTopicNameP->Load(node);
+ this->bumperTopicName = this->bumperTopicNameP->GetValue();
+ std::cout << " publishing contact/collisions to topic name: " << this->bumperTopicName << std::endl;
+
+ rosnode->advertise<std_msgs::String>(this->bumperTopicName,100);
}
////////////////////////////////////////////////////////////////////////////////
@@ -71,6 +93,39 @@
// Update the controller
void Ros_Bumper::UpdateChild()
{
+ this->lock.lock();
+
+ unsigned int num_contacts = this->myParent->GetContactCount();
+
+ double current_time = Simulator::Instance()->GetRealTime();
+
+ std::string my_geom_name;
+ int i_hit_geom;
+ double when_i_hit;
+ std::string geom_i_hit;;
+
+ for (unsigned int i=0; i < num_contacts; i++)
+ {
+ my_geom_name = this->myParent->GetGeomName(i);
+ i_hit_geom = this->myParent->GetContactState(i);
+ when_i_hit= this->myParent->GetContactTime(i);
+ geom_i_hit = this->myParent->GetContactGeomName(i);
+ if (i_hit_geom == 1)
+ {
+ std::ostringstream stream;
+ stream << "touched! i:" << i
+ << " my geom:" << my_geom_name
+ << " other geom:" << geom_i_hit
+ << " time:" << when_i_hit << std::endl;
+ std::cout << stream;
+ this->bumperMsg.data = stream.str();
+ rosnode->publish(this->bumperTopicName,this->bumperMsg);
+ }
+ }
+
+ this->myParent->ResetContactStates();
+
+ this->lock.unlock();
}
////////////////////////////////////////////////////////////////////////////////
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.py
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.py 2008-12-09 22:19:32 UTC (rev 7834)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.py 2008-12-09 22:21:04 UTC (rev 7835)
@@ -120,8 +120,8 @@
#compare thumbnails only
for i in range(len(i0d)):
- (r0,g0,b0) = i0d[i-1]
- (r1,g1,b1) = i1d[i-1]
+ (r0,g0,b0) = i0d[i]
+ (r1,g1,b1) = i1d[i]
#if abs(r0-r1) > 0 or abs(g0-g1) > 0 or abs(b0-b1) > 0:
# print "debug errors ",i,abs(r0-r1),abs(g0-g1),abs(b0-b1)
if abs(r0-r1) > pixel_tol or abs(g0-g1) > pixel_tol or abs(b0-b1) > pixel_tol:
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml 2008-12-09 22:19:32 UTC (rev 7834)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml 2008-12-09 22:21:04 UTC (rev 7835)
@@ -152,6 +152,20 @@
<box size="${base_size_x} ${base_size_y} ${base_size_z}" />
</geometry>
</collision>
+ <map name="bumper_sensor" flag="gazebo">
+ <verbatim key="sensor_base_bumper">
+ <sensor:contact name="${name}_contact_sensor">
+ <geom>${name}_collision</geom>
+ <updateRate>100.0</updateRate>
+ <controller:ros_bumper name="${name}_ros_bumper_controller" plugin="libRos_Bumper.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bumperTopicName>${name}_bumper</bumperTopicName>
+ <interface:bumper name="${name}_bumper_iface" />
+ </controller:ros_bumper>
+ </sensor:contact>
+ </verbatim>
+ </map>
</link>
@@ -212,7 +226,6 @@
<interface:laser name="ros_base_laser_iface" />
</controller:ros_laser>
</sensor:ray>
-
</verbatim>
</map>
</sensor>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-12-09 22:22:20
|
Revision: 7830
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7830&view=rev
Author: hsujohnhsu
Date: 2008-12-09 21:39:42 +0000 (Tue, 09 Dec 2008)
Log Message:
-----------
* update base laser scan range form +/-135 degrees to +/-100 degrees so it doesn't pick up base of arm_pan joint.
* update tilting laser scan range so it doesn't pick up top of arm_pan joint.
* @todo: joints not calibrated correctly in current launch script. should add calibration controllers.
Modified Paths:
--------------
pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch
pkg/trunk/demos/pr2_gazebo/setarms.py
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml
Modified: pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch
===================================================================
--- pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch 2008-12-09 21:36:43 UTC (rev 7829)
+++ pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch 2008-12-09 21:39:42 UTC (rev 7830)
@@ -15,6 +15,7 @@
<!-- send laser tilt motor a command -->
<!--node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 20 0.872 0.3475" respawn="false" output="screen" /-->
- <node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 1 .45 .40" />
+ <!--node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 1 .45 .40" /--> <!-- this one will pick up shoulders at lowest position -->
+ <node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 1 .35 .3" />
</launch>
Modified: pkg/trunk/demos/pr2_gazebo/setarms.py
===================================================================
--- pkg/trunk/demos/pr2_gazebo/setarms.py 2008-12-09 21:36:43 UTC (rev 7829)
+++ pkg/trunk/demos/pr2_gazebo/setarms.py 2008-12-09 21:39:42 UTC (rev 7830)
@@ -55,11 +55,11 @@
CMD_POS_1 = 0.0
-CMD_POS_2 = 2.0
+CMD_POS_2 = 3.142
CMD_POS_3 = 0.0
-CMD_POS_4 = 2.0
+CMD_POS_4 = 3.142
CMD_POS_5 = 3.142
-CMD_POS_6 = 2.0
+CMD_POS_6 = 3.142
CMD_POS_7 = 0.0
CMD_POS_8 = 0.8
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml 2008-12-09 21:36:43 UTC (rev 7829)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml 2008-12-09 21:39:42 UTC (rev 7830)
@@ -24,7 +24,7 @@
<joint name="${parent}_${suffix}_wheel_joint" />
<origin xyz="0 ${reflect*caster_wheel_offset_y} 0" rpy="0 0 0" />
<inertial>
- <mass value="0.44036" />
+ <mass value="0.44036" /> <!-- check jmh 20081205 -->
<com xyz=" 0 0 0 " />
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943" />
@@ -163,7 +163,7 @@
<sensor name="base_laser" type="laser">
<calibration filename="calib_filename" />
<parent name="${name}_link" />
- <origin xyz="0.275 0 0.182" rpy="0 0 0" />
+ <origin xyz="0.275 0 0.132" rpy="0 0 0" />
<joint name="base_laser_joint" />
<inertial>
<mass value="1.0" />
@@ -197,8 +197,8 @@
<origin>0.0 0.0 0.17</origin> <!-- FIXME: for verbatim, adjust this number according to base_laser_center_box_center_offset_z -->
<displayRays>false</displayRays>
- <minAngle>-135</minAngle>
- <maxAngle>135</maxAngle>
+ <minAngle>-100</minAngle> <!-- scans own arms if -135~+135 -->
+ <maxAngle>100</maxAngle>
<minRange>0.05</minRange>
<maxRange>10.0</maxRange>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2008-12-10 02:03:06
|
Revision: 7870
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7870&view=rev
Author: tfoote
Date: 2008-12-10 02:02:56 +0000 (Wed, 10 Dec 2008)
Log Message:
-----------
updating review stati
Modified Paths:
--------------
pkg/trunk/demos/2dnav_erratic/manifest.xml
pkg/trunk/demos/2dnav_gazebo/manifest.xml
pkg/trunk/demos/2dnav_pr2/manifest.xml
pkg/trunk/demos/2dnav_stage/manifest.xml
pkg/trunk/demos/arm_gazebo/manifest.xml
pkg/trunk/demos/pr2_gazebo/manifest.xml
pkg/trunk/demos/pr2_prototype1_gazebo/manifest.xml
pkg/trunk/demos/stair1-demos/manifest.xml
pkg/trunk/deprecated/display_ode_spaces/manifest.xml
pkg/trunk/deprecated/drawstuff/manifest.xml
pkg/trunk/deprecated/libTF/manifest.xml
pkg/trunk/deprecated/test_collision_space/manifest.xml
Modified: pkg/trunk/demos/2dnav_erratic/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav_erratic/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/demos/2dnav_erratic/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -2,7 +2,7 @@
<description>A demo of 2-D navigation.</description>
<author>Brian Gerkey</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="na" notes=""/>
<url>http://pr.willowgarage.com/wiki/FIXME</url>
<depend package="nav_view"/>
<depend package="roslaunch"/>
Modified: pkg/trunk/demos/2dnav_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/demos/2dnav_gazebo/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -2,7 +2,7 @@
<description>A clone of 2-D navigation stack \b rosstage using a 3D simulation environment.</description>
<author>John Hsu</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="NA" notes=""/>
<url>http://pr.willowgarage.com/wiki/Simulator</url>
<depend package="nav_view"/>
<depend package="roslaunch"/>
Modified: pkg/trunk/demos/2dnav_pr2/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/demos/2dnav_pr2/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -2,7 +2,7 @@
<description>A demo of 2-D navigation.</description>
<author>Brian Gerkey</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="na" notes=""/>
<url>http://pr.willowgarage.com/wiki/FIXME</url>
<depend package="roslaunch"/>
<depend package="amcl_player"/>
Modified: pkg/trunk/demos/2dnav_stage/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav_stage/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/demos/2dnav_stage/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -2,7 +2,7 @@
<description>A demo of 2-D navigation.</description>
<author>Brian Gerkey</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="NA" notes=""/>
<url>http://pr.willowgarage.com/wiki/FIXME</url>
<depend package="nav_view"/>
<depend package="nav_view_sdl"/>
Modified: pkg/trunk/demos/arm_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/arm_gazebo/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/demos/arm_gazebo/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -2,7 +2,7 @@
<description>Start a PR2 arm in 3D simulation environment.</description>
<author>John Hsu</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="na" notes=""/>
<url>http://pr.willowgarage.com/wiki/Simulator</url>
<depend package="roslaunch"/>
<depend package="gazebo_plugin"/>
Modified: pkg/trunk/demos/pr2_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/pr2_gazebo/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/demos/pr2_gazebo/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -2,7 +2,7 @@
<description>Gazebo 3D simulation examples.</description>
<author>John Hsu</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="na" notes=""/>
<url>http://pr.willowgarage.com/wiki/Simulator</url>
<depend package="roslaunch"/>
<depend package="gazebo_plugin"/>
Modified: pkg/trunk/demos/pr2_prototype1_gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/pr2_prototype1_gazebo/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/demos/pr2_prototype1_gazebo/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -2,7 +2,7 @@
<description>Start a PR2 in 3D simulation environment.</description>
<author>John Hsu</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="na" notes="demo scripts"/>
<url>http://pr.willowgarage.com/wiki/Simulator</url>
<depend package="roslaunch"/>
<depend package="gazebo_plugin"/>
Modified: pkg/trunk/demos/stair1-demos/manifest.xml
===================================================================
--- pkg/trunk/demos/stair1-demos/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/demos/stair1-demos/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -2,7 +2,7 @@
<description>Some demos that are specific to the STAIR1 robot. Most of these could easily be ported to other robots if the desire/hardware was there.</description>
<author>Morgan Quigley</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="na" notes=""/>
<depend package="nav_view"/>
<depend package="roslaunch"/>
<depend package="amcl_player"/>
Modified: pkg/trunk/deprecated/display_ode_spaces/manifest.xml
===================================================================
--- pkg/trunk/deprecated/display_ode_spaces/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/deprecated/display_ode_spaces/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -5,7 +5,7 @@
<author>Ioan Sucan/is...@wi...</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="deprecated" notes=""/>
<depend package="drawstuff"/>
Modified: pkg/trunk/deprecated/drawstuff/manifest.xml
===================================================================
--- pkg/trunk/deprecated/drawstuff/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/deprecated/drawstuff/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -7,7 +7,7 @@
</description>
<author>Russel Smith</author>
<license>LGPL</license>
-<review status="unreviewed" notes=""/>
+<review status="deprecated" notes=""/>
<url>http://opende.sf.net</url>
<depend package="opende" />
<sysdepend os="ubuntu" version="8.04-hardy" package="freeglut3-dev"/>
Modified: pkg/trunk/deprecated/libTF/manifest.xml
===================================================================
--- pkg/trunk/deprecated/libTF/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/deprecated/libTF/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -6,7 +6,7 @@
</description>
<author>Tully Foote</author>
<license>BSD</license>
-<review status="unreviewed" notes=""/>
+<review status="deprecated" notes=""/>
<url>http://pr.willowgarage.com</url>
<depend package="newmat10"/>
<depend package="ros_exception"/>
Modified: pkg/trunk/deprecated/test_collision_space/manifest.xml
===================================================================
--- pkg/trunk/deprecated/test_collision_space/manifest.xml 2008-12-10 01:43:37 UTC (rev 7869)
+++ pkg/trunk/deprecated/test_collision_space/manifest.xml 2008-12-10 02:02:56 UTC (rev 7870)
@@ -5,7 +5,7 @@
<author>Ioan Sucan/is...@wi...</author>
<license>BSD</license>
- <review status="unreviewed" notes=""/>
+ <review status="deprecated" notes=""/>
<depend package="collision_space"/>
<depend package="display_ode_spaces"/>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2008-12-10 07:09:37
|
Revision: 7901
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7901&view=rev
Author: tfoote
Date: 2008-12-10 07:09:28 +0000 (Wed, 10 Dec 2008)
Log Message:
-----------
moving high performance laser scan projection into laser_scan package
Modified Paths:
--------------
pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h
pkg/trunk/util/laser_scan/manifest.xml
pkg/trunk/util/laser_scan/src/laser_scan.cc
pkg/trunk/util/tf/include/tf/transform_listener.h
pkg/trunk/util/tf/manifest.xml
pkg/trunk/util/tf/src/transform_listener.cpp
pkg/trunk/visualization/ogre_visualizer/manifest.xml
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.h
Modified: pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/drivers/robot/pr2/point_cloud_assembler/src/point_cloud_assembler.cpp 2008-12-10 07:09:28 UTC (rev 7901)
@@ -180,7 +180,7 @@
}
else // Do it the slower (more accurate) way
{
- tf_.transformLaserScanToPointCloud(req.target_frame_id, target_frame_cloud, cur_scan) ;
+ projector_.transformLaserScanToPointCloud(req.target_frame_id, target_frame_cloud, cur_scan, tf_) ;
}
for(unsigned int j = 0; j < target_frame_cloud.get_pts_size(); j++) // Populate full_cloud from the cloud
Modified: pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h
===================================================================
--- pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/util/laser_scan/include/laser_scan/laser_scan.h 2008-12-10 07:09:28 UTC (rev 7901)
@@ -38,6 +38,8 @@
#include <newmat10/newmatio.h>
#include <newmat10/newmatap.h>
+#include "tf/tf.h"
+
#include "std_msgs/LaserScan.h"
#include "std_msgs/PointCloud.h"
#include "std_msgs/PointCloud.h"
@@ -69,6 +71,10 @@
*/
void projectLaser(const std_msgs::LaserScan& scan_in, std_msgs::PointCloud & cloud_out, double range_cutoff=-1.0, bool preservative = false);
+
+ /** \brief Transform a std_msgs::LaserScan into a PointCloud in target frame */
+ void transformLaserScanToPointCloud(const std::string& target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::LaserScan & scanIn, tf::Transformer & tf);
+
private:
/** \brief Return the unit vectors for this configuration
Modified: pkg/trunk/util/laser_scan/manifest.xml
===================================================================
--- pkg/trunk/util/laser_scan/manifest.xml 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/util/laser_scan/manifest.xml 2008-12-10 07:09:28 UTC (rev 7901)
@@ -11,6 +11,7 @@
<depend package="newmat10"/>
<depend package="std_msgs"/>
<depend package="roscpp"/>
+<depend package="tf"/>
<depend package="rosthread"/>
<export>
<cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -llaser_scan"/>
Modified: pkg/trunk/util/laser_scan/src/laser_scan.cc
===================================================================
--- pkg/trunk/util/laser_scan/src/laser_scan.cc 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/util/laser_scan/src/laser_scan.cc 2008-12-10 07:09:28 UTC (rev 7901)
@@ -149,4 +149,100 @@
}
};
+void LaserProjection::transformLaserScanToPointCloud(const std::string & target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::LaserScan & scanIn,
+ tf::Transformer& tf)
+{
+ cloudOut.header = scanIn.header;
+ cloudOut.header.frame_id = target_frame;
+ cloudOut.set_pts_size(scanIn.get_ranges_size());
+ if (scanIn.get_intensities_size() > 0)
+ {
+ cloudOut.set_chan_size(2);
+ cloudOut.chan[0].name ="intensities";
+ cloudOut.chan[0].set_vals_size(scanIn.get_intensities_size());
+
+ cloudOut.chan[1].name ="index";
+ cloudOut.chan[1].set_vals_size(scanIn.get_ranges_size());
+ }
+
+ tf::Stamped<tf::Point> pointIn;
+ tf::Stamped<tf::Point> pointOut;
+
+ pointIn.frame_id_ = scanIn.header.frame_id;
+
+ ///\todo this can be optimized
+ std_msgs::PointCloud intermediate; //optimize out
+
+ projectLaser(scanIn, intermediate, -1.0, true);
+
+ // Extract transforms for the beginning and end of the laser scan
+ ros::Time start_time = scanIn.header.stamp ;
+ ros::Time end_time = scanIn.header.stamp + ros::Duration().fromSec(scanIn.get_ranges_size()*scanIn.time_increment) ;
+
+ tf::Stamped<tf::Transform> start_transform ;
+ tf::Stamped<tf::Transform> end_transform ;
+ tf::Stamped<tf::Transform> cur_transform ;
+
+ tf.lookupTransform(target_frame, scanIn.header.frame_id, start_time, start_transform) ;
+ tf.lookupTransform(target_frame, scanIn.header.frame_id, end_time, end_transform) ;
+
+
+ unsigned int count = 0;
+ for (unsigned int i = 0; i < scanIn.get_ranges_size(); i++)
+ {
+ if (scanIn.ranges[i] < scanIn.range_max
+ && scanIn.ranges[i] > scanIn.range_min) //only when valid
+ {
+ // Looking up transforms in tree is too expensive. Need more optimized way
+ /*
+ pointIn = tf::Stamped<tf::Point>(btVector3(intermediate.pts[i].x, intermediate.pts[i].y, intermediate.pts[i].z),
+ ros::Time(scanIn.header.stamp.to_ull() + (uint64_t) (scanIn.time_increment * 1000000000)),
+ pointIn.frame_id_ = scanIn.header.frame_id);///\todo optimize to no copy
+ transformPoint(target_frame, pointIn, pointOut);
+ */
+
+ // Instead, assume constant motion during the laser-scan, and use slerp to compute intermediate transforms
+ btScalar ratio = i / ( (double) scanIn.get_ranges_size() - 1.0) ;
+
+ //! \todo Make a function that performs both the slerp and linear interpolation needed to interpolate a Full Transform (Quaternion + Vector)
+
+ //Interpolate translation
+ btVector3 v ;
+ v.setInterpolate3(start_transform.getOrigin(), end_transform.getOrigin(), ratio) ;
+ cur_transform.setOrigin(v) ;
+
+ //Interpolate rotation
+ btQuaternion q1, q2 ;
+ start_transform.getBasis().getRotation(q1) ;
+ end_transform.getBasis().getRotation(q2) ;
+
+ // Compute the slerp-ed rotation
+ cur_transform.setRotation( slerp( q1, q2 , ratio) ) ;
+
+ // Apply the transform to the current point
+ btVector3 pointIn(intermediate.pts[i].x, intermediate.pts[i].y, intermediate.pts[i].z) ;
+ btVector3 pointOut = cur_transform * pointIn ;
+
+ // Copy transformed point into cloud
+ cloudOut.pts[count].x = pointOut.x();
+ cloudOut.pts[count].y = pointOut.y();
+ cloudOut.pts[count].z = pointOut.z();
+
+ //Copy index over from projected point cloud
+ cloudOut.chan[1].vals[count] = intermediate.chan[1].vals[i];
+
+
+ if (scanIn.get_intensities_size() >= i) /// \todo optimize and catch length difference better
+ cloudOut.chan[0].vals[count] = scanIn.intensities[i];
+ count++;
+ }
+
+ }
+ //downsize if necessary
+ cloudOut.set_pts_size(count);
+ cloudOut.chan[0].set_vals_size(count);
+ cloudOut.chan[1].set_vals_size(count);
+}
+
+
} //laser_scan
Modified: pkg/trunk/util/tf/include/tf/transform_listener.h
===================================================================
--- pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/util/tf/include/tf/transform_listener.h 2008-12-10 07:09:28 UTC (rev 7901)
@@ -33,7 +33,6 @@
#define TF_TRANSFORMLISTENER_H
#include "std_msgs/PointCloud.h"
-#include "laser_scan/laser_scan.h"
#include "tf/tfMessage.h"
#include "tf/tf.h"
#include "ros/node.h"
@@ -127,8 +126,6 @@
const std_msgs::PointCloud& pcin,
const std::string& fixed_frame, std_msgs::PointCloud& pcout);
- /** \brief Transform a std_msgs::LaserScan into a PointCloud in target frame */
- void transformLaserScanToPointCloud(const std::string& target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::LaserScan & scanIn);
///\todo move to high precision laser projector class void projectAndTransformLaserScan(const std_msgs::LaserScan& scan_in, std_msgs::PointCloud& pcout);
@@ -150,10 +147,6 @@
void transformPointCloud(const std::string & target_frame, const Transform& transform, const ros::Time& target_time, const std_msgs::PointCloud& pcin, std_msgs::PointCloud& pcout);
- /** @brief A helper class for projecting laser scans */
- laser_scan::LaserProjection projector_;
-
-
///\todo Remove : for backwards compatability only
void receiveArray()
{
Modified: pkg/trunk/util/tf/manifest.xml
===================================================================
--- pkg/trunk/util/tf/manifest.xml 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/util/tf/manifest.xml 2008-12-10 07:09:28 UTC (rev 7901)
@@ -15,7 +15,6 @@
<depend package="std_msgs"/>
<depend package="roscpp"/>
<depend package="bullet"/>
-<depend package="laser_scan"/>
<depend package="boost"/>
<depend package="rospy"/>
<export>
Modified: pkg/trunk/util/tf/src/transform_listener.cpp
===================================================================
--- pkg/trunk/util/tf/src/transform_listener.cpp 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/util/tf/src/transform_listener.cpp 2008-12-10 07:09:28 UTC (rev 7901)
@@ -179,100 +179,8 @@
}
-void TransformListener::transformLaserScanToPointCloud(const std::string & target_frame, std_msgs::PointCloud & cloudOut, const std_msgs::LaserScan & scanIn)
-{
- cloudOut.header = scanIn.header;
- cloudOut.header.frame_id = target_frame;
- cloudOut.set_pts_size(scanIn.get_ranges_size());
- if (scanIn.get_intensities_size() > 0)
- {
- cloudOut.set_chan_size(2);
- cloudOut.chan[0].name ="intensities";
- cloudOut.chan[0].set_vals_size(scanIn.get_intensities_size());
- cloudOut.chan[1].name ="index";
- cloudOut.chan[1].set_vals_size(scanIn.get_ranges_size());
- }
- tf::Stamped<tf::Point> pointIn;
- tf::Stamped<tf::Point> pointOut;
-
- pointIn.frame_id_ = scanIn.header.frame_id;
-
- ///\todo this can be optimized
- std_msgs::PointCloud intermediate; //optimize out
- projector_.projectLaser(scanIn, intermediate, -1.0, true);
-
- // Extract transforms for the beginning and end of the laser scan
- ros::Time start_time = scanIn.header.stamp ;
- ros::Time end_time = scanIn.header.stamp + ros::Duration().fromSec(scanIn.get_ranges_size()*scanIn.time_increment) ;
-
- tf::Stamped<tf::Transform> start_transform ;
- tf::Stamped<tf::Transform> end_transform ;
- tf::Stamped<tf::Transform> cur_transform ;
-
- lookupTransform(target_frame, scanIn.header.frame_id, start_time, start_transform) ;
- lookupTransform(target_frame, scanIn.header.frame_id, end_time, end_transform) ;
-
-
- unsigned int count = 0;
- for (unsigned int i = 0; i < scanIn.get_ranges_size(); i++)
- {
- if (scanIn.ranges[i] < scanIn.range_max
- && scanIn.ranges[i] > scanIn.range_min) //only when valid
- {
- // Looking up transforms in tree is too expensive. Need more optimized way
- /*
- pointIn = tf::Stamped<tf::Point>(btVector3(intermediate.pts[i].x, intermediate.pts[i].y, intermediate.pts[i].z),
- ros::Time(scanIn.header.stamp.to_ull() + (uint64_t) (scanIn.time_increment * 1000000000)),
- pointIn.frame_id_ = scanIn.header.frame_id);///\todo optimize to no copy
- transformPoint(target_frame, pointIn, pointOut);
- */
-
- // Instead, assume constant motion during the laser-scan, and use slerp to compute intermediate transforms
- btScalar ratio = i / ( (double) scanIn.get_ranges_size() - 1.0) ;
-
- //! \todo Make a function that performs both the slerp and linear interpolation needed to interpolate a Full Transform (Quaternion + Vector)
-
- //Interpolate translation
- btVector3 v ;
- v.setInterpolate3(start_transform.getOrigin(), end_transform.getOrigin(), ratio) ;
- cur_transform.setOrigin(v) ;
-
- //Interpolate rotation
- btQuaternion q1, q2 ;
- start_transform.getBasis().getRotation(q1) ;
- end_transform.getBasis().getRotation(q2) ;
-
- // Compute the slerp-ed rotation
- cur_transform.setRotation( slerp( q1, q2 , ratio) ) ;
-
- // Apply the transform to the current point
- btVector3 pointIn(intermediate.pts[i].x, intermediate.pts[i].y, intermediate.pts[i].z) ;
- btVector3 pointOut = cur_transform * pointIn ;
-
- // Copy transformed point into cloud
- cloudOut.pts[count].x = pointOut.x();
- cloudOut.pts[count].y = pointOut.y();
- cloudOut.pts[count].z = pointOut.z();
-
- //Copy index over from projected point cloud
- cloudOut.chan[1].vals[count] = intermediate.chan[1].vals[i];
-
-
- if (scanIn.get_intensities_size() >= i) /// \todo optimize and catch length difference better
- cloudOut.chan[0].vals[count] = scanIn.intensities[i];
- count++;
- }
-
- }
- //downsize if necessary
- cloudOut.set_pts_size(count);
- cloudOut.chan[0].set_vals_size(count);
- cloudOut.chan[1].set_vals_size(count);
-}
-
-
void TransformListener::subscription_callback()
{
for (uint i = 0; i < msg_in_.transforms.size(); i++)
Modified: pkg/trunk/visualization/ogre_visualizer/manifest.xml
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/manifest.xml 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/visualization/ogre_visualizer/manifest.xml 2008-12-10 07:09:28 UTC (rev 7901)
@@ -15,6 +15,7 @@
<depend package="std_msgs"/>
<depend package="rosthread"/>
<depend package="tf"/>
+ <depend package="laser_scan"/>
<depend package="wg_robot_description"/>
<depend package="gazebo_robot_description"/>
<depend package="wg_robot_description_parser"/>
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.cpp 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.cpp 2008-12-10 07:09:28 UTC (rev 7901)
@@ -65,7 +65,8 @@
setStyle( style_ );
setBillboardSize( billboard_size_ );
-
+
+ projector_ = new laser_scan::LaserProjection();
scan_notifier_ = new tf::MessageNotifier<std_msgs::LaserScan>(tf_, ros_node_, boost::bind(&LaserScanDisplay::incomingScanCallback, this, _1), "", "", 10);
cloud_notifier_ = new tf::MessageNotifier<std_msgs::PointCloud>(tf_, ros_node_, boost::bind(&LaserScanDisplay::incomingCloudCallback, this, _1), "", "", 10);
}
@@ -368,7 +369,7 @@
frame_id = fixed_frame_;
}
- tf_->transformLaserScanToPointCloud( scan->header.frame_id, cloud, *scan );
+ projector_->transformLaserScanToPointCloud( scan->header.frame_id, cloud, *scan , *tf_);
transformCloud( cloud );
}
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.h
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.h 2008-12-10 06:52:35 UTC (rev 7900)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/laser_scan_display.h 2008-12-10 07:09:28 UTC (rev 7901)
@@ -34,6 +34,8 @@
#include "ogre_tools/point_cloud.h"
#include "helpers/color.h"
+#include "laser_scan/laser_scan.h"
+
#include "std_msgs/LaserScan.h"
#include "std_msgs/PointCloud.h"
#include "std_msgs/Empty.h"
@@ -204,6 +206,8 @@
ColorProperty* color_property_;
EnumProperty* style_property_;
+ laser_scan::LaserProjection* projector_; ///< A Helper class to project laser scans
+
tf::MessageNotifier<std_msgs::PointCloud>* cloud_notifier_;
tf::MessageNotifier<std_msgs::LaserScan>* scan_notifier_;
};
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2008-12-11 02:05:54
|
Revision: 7948
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7948&view=rev
Author: jleibs
Date: 2008-12-11 02:05:50 +0000 (Thu, 11 Dec 2008)
Log Message:
-----------
Unblacklisting assorted packages that now build.
Modified Paths:
--------------
pkg/trunk/util/point_cloud_utils/include/point_cloud_utils/scan_assembler.h
pkg/trunk/util/point_cloud_utils/manifest.xml
pkg/trunk/util/point_cloud_utils/src/scan_assembler.cpp
pkg/trunk/vision/calonder_descriptor/CMakeLists.txt
pkg/trunk/vision/people/CMakeLists.txt
pkg/trunk/vision/people/manifest.xml
pkg/trunk/vision/visual_odometry/src/VOSparseBundleAdj.cpp
Removed Paths:
-------------
pkg/trunk/util/point_cloud_utils/ROS_BUILD_BLACKLIST
pkg/trunk/vision/calonder_descriptor/ROS_BUILD_BLACKLIST
pkg/trunk/vision/people/ROS_BUILD_BLACKLIST
pkg/trunk/vision/stereo_calib/ROS_BUILD_BLACKLIST
pkg/trunk/vision/videre_face_detection/ROS_BUILD_BLACKLIST
pkg/trunk/vision/visual_odometry/ROS_BUILD_BLACKLIST
Deleted: pkg/trunk/util/point_cloud_utils/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/util/point_cloud_utils/ROS_BUILD_BLACKLIST 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/util/point_cloud_utils/ROS_BUILD_BLACKLIST 2008-12-11 02:05:50 UTC (rev 7948)
@@ -1 +0,0 @@
-Depends on calonder_descriptor, which is blacklisted
Modified: pkg/trunk/util/point_cloud_utils/include/point_cloud_utils/scan_assembler.h
===================================================================
--- pkg/trunk/util/point_cloud_utils/include/point_cloud_utils/scan_assembler.h 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/util/point_cloud_utils/include/point_cloud_utils/scan_assembler.h 2008-12-11 02:05:50 UTC (rev 7948)
@@ -35,7 +35,7 @@
#include "ros/node.h"
#include "tf/transform_listener.h"
-#include "laser_scan_utils/laser_scan.h"
+#include "laser_scan/laser_scan.h"
// Messages
#include "std_msgs/LaserScan.h"
Modified: pkg/trunk/util/point_cloud_utils/manifest.xml
===================================================================
--- pkg/trunk/util/point_cloud_utils/manifest.xml 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/util/point_cloud_utils/manifest.xml 2008-12-11 02:05:50 UTC (rev 7948)
@@ -14,6 +14,7 @@
<depend package="tf"/>
<depend package="bullet"/>
<depend package="visual_odometry" />
+<depend package="laser_scan" />
<export>
<cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lpoint_cloud_utils"/>
Modified: pkg/trunk/util/point_cloud_utils/src/scan_assembler.cpp
===================================================================
--- pkg/trunk/util/point_cloud_utils/src/scan_assembler.cpp 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/util/point_cloud_utils/src/scan_assembler.cpp 2008-12-11 02:05:50 UTC (rev 7948)
@@ -58,7 +58,8 @@
{
PointCloud target_frame_cloud ; // Stores the current scan in the target frame
- tf_.transformLaserScanToPointCloud(cloud_.header.frame_id, target_frame_cloud, scan) ; //! \todo Add a try/catch block around this TF calls
+
+ projector_.transformLaserScanToPointCloud(cloud_.header.frame_id, target_frame_cloud, scan, tf_) ; //! \todo Add a try/catch block around this TF calls
cloud_.header.stamp = scan.header.stamp ; // Give the cloud the stamp of the latest scan received
Modified: pkg/trunk/vision/calonder_descriptor/CMakeLists.txt
===================================================================
--- pkg/trunk/vision/calonder_descriptor/CMakeLists.txt 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/vision/calonder_descriptor/CMakeLists.txt 2008-12-11 02:05:50 UTC (rev 7948)
@@ -9,10 +9,13 @@
include_directories(${PYTHON_INCLUDE_PATH})
target_link_libraries(calonder cblas)
-rospack_add_library(pycalonder src/py.cpp src/randomized_tree.cpp src/rtree_classifier.cpp src/patch_generator.cpp)
-set_target_properties(pycalonder PROPERTIES OUTPUT_NAME calonder PREFIX "")
-rospack_add_compile_flags(pycalonder -Wno-missing-field-initializers -save-temps -march=pentium3 -msse3)
+# Commenting out to make build:
+#rospack_add_library(pycalonder src/py.cpp src/randomized_tree.cpp src/rtree_classifier.cpp src/patch_generator.cpp)
+#set_target_properties(pycalonder PROPERTIES OUTPUT_NAME calonder PREFIX "")
+#rospack_add_compile_flags(pycalonder -Wno-missing-field-initializers -save-temps -march=pentium3 -msse3)
+#target_link_libraries(pycalonder cblas)
+
#rospack_add_compile_flags(pycalonder -Wno-missing-field-initializers)
-target_link_libraries(pycalonder cblas)
+
rospack_add_pyunit(test/directed.py)
Deleted: pkg/trunk/vision/calonder_descriptor/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/vision/calonder_descriptor/ROS_BUILD_BLACKLIST 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/vision/calonder_descriptor/ROS_BUILD_BLACKLIST 2008-12-11 02:05:50 UTC (rev 7948)
@@ -1,92 +0,0 @@
-[ 57%] Building CXX object CMakeFiles/pycalonder.dir/src/py.cpp.o
-In file included from
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:18:
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:4:
-error: \u2018SparseSignature\u2019 was not declared in this scope
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:4:
-error: wrong number of template arguments (2, should be 1)
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/include/calonder_descriptor/matcher.h:14:
-error: provided for \u2018template<class Data> class
-features::BruteForceMatcher\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:
-In function \u2018PyObject* make_wrapped_BruteForceMatcher(PyObject*,
-PyObject*)\u2019:
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:77:
-error: \u2018SparseSignature\u2019 was not declared in this scope
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:77:
-error: wrong number of template arguments (2, should be 1)
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/include/calonder_descriptor/matcher.h:14:
-error: provided for \u2018template<class Data> class
-features::BruteForceMatcher\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:
-At global scope:
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:85:
-error: \u2018SparseSignature\u2019 does not name a type
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:
-In function \u2018void wrapped_SparseSignature_dealloc(PyObject*)\u2019:
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:99:
-error: \u2018struct wrapped_SparseSignature_t\u2019 has no member named
-\u2018c\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/generated.i:99:
-error: expected class-name before \u2018(\u2019 token
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:
-In function \u2018PyObject* getSparseSignature(PyObject*, PyObject*)\u2019:
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:103:
-error: \u2018struct wrapped_SparseSignature_t\u2019 has no member named
-\u2018c\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:103:
-error: expected type-specifier before \u2018SparseSignature\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:103:
-error: expected `;' before \u2018SparseSignature\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:100:
-warning: unused variable \u2018pc\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:
-In function \u2018PyObject*
-wrapped_BruteForceMatcher_addSignature(PyObject*, PyObject*)\u2019:
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:137:
-error: request for member \u2018addSignature\u2019 in \u2018*
-pm->wrapped_BruteForceMatcher_t::c\u2019, which is of non-class type
-\u2018int\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:137:
-error: \u2018struct wrapped_SparseSignature_t\u2019 has no member named
-\u2018c\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:
-In function \u2018PyObject* wrapped_BruteForceMatcher_findMatch(PyObject*,
-PyObject*)\u2019:
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:156:
-error: request for member \u2018findMatch\u2019 in \u2018*
-pm->wrapped_BruteForceMatcher_t::c\u2019, which is of non-class type
-\u2018int\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:156:
-error: \u2018struct wrapped_SparseSignature_t\u2019 has no member named
-\u2018c\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:158:
-error: request for member \u2018findMatchPredicated\u2019 in \u2018*
-pm->wrapped_BruteForceMatcher_t::c\u2019, which is of non-class type
-\u2018int\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:158:
-error: \u2018struct wrapped_SparseSignature_t\u2019 has no member named
-\u2018c\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:
-In function \u2018PyObject* wrapped_SparseSignature_dump(PyObject*,
-PyObject*)\u2019:
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:170:
-error: \u2018struct wrapped_SparseSignature_t\u2019 has no member named
-\u2018c\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:171:
-error: \u2018struct wrapped_SparseSignature_t\u2019 has no member named
-\u2018c\u2019
-/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/src/py.cpp:172:
-error: \u2018struct wrapped_SparseSignature_t\u2019 has no member named
-\u2018c\u2019
-make[3]: *** [CMakeFiles/pycalonder.dir/src/py.cpp.o] Error 1
-make[3]: Leaving directory
-`/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/build'
-make[2]: Leaving directory
-`/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/build'
-make[1]: Leaving directory
-`/home/rosbuild/.hudson/jobs/personalrobots-update/workspace/personalrobots/vision/calonder_descriptor/build'
-make[2]: *** [CMakeFiles/pycalonder.dir/all] Error 2
-make[1]: *** [all] Error 2
-make: *** [all] Error 2
-[rosmakeall-buildfail] Build of calonder_descriptor failed
Modified: pkg/trunk/vision/people/CMakeLists.txt
===================================================================
--- pkg/trunk/vision/people/CMakeLists.txt 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/vision/people/CMakeLists.txt 2008-12-11 02:05:50 UTC (rev 7948)
@@ -16,4 +16,6 @@
rospack_add_library(pyface_detection src/py.cpp src/face_detection.cpp src/people.cpp)
set_target_properties(pyface_detection PROPERTIES OUTPUT_NAME face_detection PREFIX "")
+rospack_add_executable(leg_detector src/leg_detector.cpp src/calc_leg_features.cpp)
+
#rospack_add_pyunit(test/directed.py)
Deleted: pkg/trunk/vision/people/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/vision/people/ROS_BUILD_BLACKLIST 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/vision/people/ROS_BUILD_BLACKLIST 2008-12-11 02:05:50 UTC (rev 7948)
@@ -1 +0,0 @@
-Depends on calonder_descriptor, which is blacklisted
Modified: pkg/trunk/vision/people/manifest.xml
===================================================================
--- pkg/trunk/vision/people/manifest.xml 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/vision/people/manifest.xml 2008-12-11 02:05:50 UTC (rev 7948)
@@ -21,6 +21,7 @@
<depend package="rospy"/>
<depend package="image_msgs"/>
<depend package="topic_synchronizer"/>
+<depend package="laser_processor"/>
<sysdepend os="ubuntu" version="7.04-feisty" package="python-numpy"/>
<sysdepend os="ubuntu" version="8.04-hardy" package="python-numpy"/>
</package>
Deleted: pkg/trunk/vision/stereo_calib/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/vision/stereo_calib/ROS_BUILD_BLACKLIST 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/vision/stereo_calib/ROS_BUILD_BLACKLIST 2008-12-11 02:05:50 UTC (rev 7948)
@@ -1 +0,0 @@
-Depends on calonder_descriptor, which is blacklisted
Deleted: pkg/trunk/vision/videre_face_detection/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/vision/videre_face_detection/ROS_BUILD_BLACKLIST 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/vision/videre_face_detection/ROS_BUILD_BLACKLIST 2008-12-11 02:05:50 UTC (rev 7948)
@@ -1 +0,0 @@
-Depends on calonder_descriptor, which is blacklisted
Deleted: pkg/trunk/vision/visual_odometry/ROS_BUILD_BLACKLIST
===================================================================
--- pkg/trunk/vision/visual_odometry/ROS_BUILD_BLACKLIST 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/vision/visual_odometry/ROS_BUILD_BLACKLIST 2008-12-11 02:05:50 UTC (rev 7948)
@@ -1 +0,0 @@
-Depends on calonder_descriptor, which is blacklisted
Modified: pkg/trunk/vision/visual_odometry/src/VOSparseBundleAdj.cpp
===================================================================
--- pkg/trunk/vision/visual_odometry/src/VOSparseBundleAdj.cpp 2008-12-11 02:02:33 UTC (rev 7947)
+++ pkg/trunk/vision/visual_odometry/src/VOSparseBundleAdj.cpp 2008-12-11 02:05:50 UTC (rev 7948)
@@ -436,7 +436,10 @@
}
void VOSparseBundleAdj::Stat2::print() {
+ printf("VOSpareBundleAdj::Stat2::print() was responsible for too many warnings and has been commented out.\n");
+
// The accumulator set which will calculate the properties for us:
+ /*
accumulator_set< int, stats<tag::min, tag::mean, tag::max> > acc;
accumulator_set< int, stats<tag::min, tag::mean, tag::max> > acc2;
accumulator_set< int, stats<tag::min, tag::mean, tag::max> > acc3;
@@ -458,6 +461,7 @@
printf("max maxtracklen = %d, ", extract::max( acc3 ));
printf("avg maxtracklen = %f, ", extract::mean( acc3 ));
printf("\n");
+
accumulator_set< double, stats<tag::min, tag::mean, tag::max> > acc1;
acc1 = std::for_each( avgTrackLens.begin(), avgTrackLens.end(), acc1 );
printf("min avgTracklen = %f, ", extract::min( acc1 ));
@@ -472,6 +476,7 @@
printf("%2d %5d, %7.2f\n", len, count, (double)count/(double)numKeyFrames);
len++;
}
+*/
}
void VOSparseBundleAdj::updateStat2() {
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-12-11 04:16:55
|
Revision: 7958
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7958&view=rev
Author: hsujohnhsu
Date: 2008-12-11 04:16:49 +0000 (Thu, 11 Dec 2008)
Log Message:
-----------
bug fix in launch scripts $LD_LIBRARY_PATH -> $(env LD_LIBRARY_PATH)
Modified Paths:
--------------
pkg/trunk/3rdparty/gazebo/empty_world.launch
pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox
pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.xml
pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml
pkg/trunk/drivers/simulator/gazebo_plugin/test/testslide.xml
Modified: pkg/trunk/3rdparty/gazebo/empty_world.launch
===================================================================
--- pkg/trunk/3rdparty/gazebo/empty_world.launch 2008-12-11 03:37:55 UTC (rev 7957)
+++ pkg/trunk/3rdparty/gazebo/empty_world.launch 2008-12-11 04:16:49 UTC (rev 7958)
@@ -3,7 +3,7 @@
<group name="wg">
<!-- start gazebo -->
<node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/gazebo_worlds/empty.world" respawn="false" output="screen">
- <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(find boost)/boost/lib:$LD_LIBRARY_PATH" />
+ <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(find boost)/boost/lib:$(env LD_LIBRARY_PATH)" />
<env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
<env name="OGRE_RESOURCE_PATH" value="$(find ogre)/ogre/lib/OGRE" />
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox 2008-12-11 03:37:55 UTC (rev 7957)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/doc.dox 2008-12-11 04:16:49 UTC (rev 7958)
@@ -30,7 +30,7 @@
<group name="wg">
<!-- assign environment variables for gazebo and startup gazebo with argument containing the world file. -->
<node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/world/robot.world" respawn="false" output="screen">
- <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$LD_LIBRARY_PATH" />
+ <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(env LD_LIBRARY_PATH)" />
<env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
<env name="OGRE_RESOURCE_PATH" value="$(find ogre)/ogre/lib/OGRE" />
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
@@ -257,7 +257,7 @@
<group name="wg">
<param name="robotdesc/pr2" command="$(find wg_robot_description_parser)/merge "$(find wg_robot_description)/single_link_test/pr2_single_link.xml"" />
<node pkg="gazebo" type="gazebo" args="$(find gazebo_robot_description)/world/robot_single_link.world" respawn="false" output="screen">
- <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$LD_LIBRARY_PATH" />
+ <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(env LD_LIBRARY_PATH)" />
<env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
<env name="OGRE_RESOURCE_PATH" value="$(find ogre)/ogre/lib/OGRE" />
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.xml 2008-12-11 03:37:55 UTC (rev 7957)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.xml 2008-12-11 04:16:49 UTC (rev 7958)
@@ -2,7 +2,7 @@
<master auto="start" />
<node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/gazebo_worlds/test/testcameras.world" respawn="false" output="screen">
- <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(find boost)/boost/lib:$LD_LIBRARY_PATH" />
+ <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(find boost)/boost/lib:$(env LD_LIBRARY_PATH)" />
<env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
<env name="OGRE_RESOURCE_PATH" value="$(find ogre)/ogre/lib/OGRE" />
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml 2008-12-11 03:37:55 UTC (rev 7957)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml 2008-12-11 04:16:49 UTC (rev 7958)
@@ -2,7 +2,7 @@
<master auto="start" />
<node pkg="gazebo" type="gazebo" args="-r $(find gazebo_robot_description)/gazebo_worlds/test/testscan.world" respawn="false" output="screen">
- <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(find boost)/boost/lib:$LD_LIBRARY_PATH" />
+ <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(find boost)/boost/lib:$(env LD_LIBRARY_PATH)" />
<env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
<env name="OGRE_RESOURCE_PATH" value="$(find ogre)/ogre/lib/OGRE" />
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testslide.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testslide.xml 2008-12-11 03:37:55 UTC (rev 7957)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testslide.xml 2008-12-11 04:16:49 UTC (rev 7958)
@@ -2,7 +2,7 @@
<master auto="start" />
<node pkg="gazebo" type="gazebo" args="-r $(find gazebo_robot_description)/gazebo_worlds/test/testslide.world" respawn="false" output="screen">
- <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(find boost)/boost/lib:$LD_LIBRARY_PATH" />
+ <env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$(find boost)/boost/lib:$(env LD_LIBRARY_PATH)" />
<env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
<env name="OGRE_RESOURCE_PATH" value="$(find ogre)/ogre/lib/OGRE" />
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mc...@us...> - 2008-12-11 20:17:53
|
Revision: 7986
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7986&view=rev
Author: mcgann
Date: 2008-12-11 20:17:46 +0000 (Thu, 11 Dec 2008)
Log Message:
-----------
Added ObservationBuffer specific watchdogs to make sure the robot does not go forward without all expected sensor updates. Solves trac #739
Modified Paths:
--------------
pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
pkg/trunk/highlevel/test_highlevel_controllers/test/launch_move_base.xml
pkg/trunk/world_models/costmap_2d/include/costmap_2d/basic_observation_buffer.h
pkg/trunk/world_models/costmap_2d/include/costmap_2d/observation_buffer.h
pkg/trunk/world_models/costmap_2d/src/basic_observation_buffer.cc
pkg/trunk/world_models/costmap_2d/src/observation_buffer.cc
pkg/trunk/world_models/costmap_2d/src/test/module-tests.cc
Modified: pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2008-12-11 20:16:45 UTC (rev 7985)
+++ pkg/trunk/highlevel/highlevel_controllers/include/MoveBase.hh 2008-12-11 20:17:46 UTC (rev 7986)
@@ -195,16 +195,10 @@
bool withinDistance(double x1, double y1, double th1, double x2, double y2, double th2) const ;
/**
- * @brief Watchdog Handling
+ * @brief Tests if all the buffers are appropriately up to date
*/
- void petTheWatchDog(const ros::Time& t);
-
bool checkWatchDog() const;
- // Time stamp for laser data. Should go away when ros::Time::now() works in simulation
- struct timeval last_updated_;
- ros::Time last_time_stamp_;
-
// Callback messages
std_msgs::LaserScan baseScanMsg_; /**< Filled by subscriber with new base laser scans */
std_msgs::LaserScan tiltScanMsg_; /**< Filled by subscriber with new tilte laser scans */
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-12-11 20:16:45 UTC (rev 7985)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveBase.cpp 2008-12-11 20:17:46 UTC (rev 7986)
@@ -88,7 +88,6 @@
param("/costmap_2d/tilt_laser_max_range", tiltLaserMaxRange_, tiltLaserMaxRange_);
// Unsigned chars cannot be stored in parameter server
-
int tmpLethalObstacleThreshold;
param("/costmap_2d/lethal_obstacle_threshold", tmpLethalObstacleThreshold, int(lethalObstacleThreshold));
if (tmpLethalObstacleThreshold > 255)
@@ -116,10 +115,23 @@
robotWidth_ = inscribedRadius * 2;
- // Allocate observation buffers
- baseScanBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("base_laser"), tf_, ros::Duration(0, 0), inscribedRadius, minZ_, maxZ_);
- tiltScanBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("laser_tilt_link"), tf_, ros::Duration(1, 0), inscribedRadius, minZ_, maxZ_);
- stereoCloudBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("stereo"), tf_, ros::Duration(0, 0), inscribedRadius, minZ_, maxZ_);
+ // Obtain parameters for sensors and allocate observation buffers accordingly. Rates are in Hz.
+ double base_laser_update_rate(2.0);
+ double tilt_laser_update_rate(2.0);
+ double stereo_update_rate(2.0);
+ param("/costmap_2d/base_laser_update_rate", base_laser_update_rate , base_laser_update_rate);
+ param("/costmap_2d/tilt_laser_update_rate", tilt_laser_update_rate , tilt_laser_update_rate);
+ param("/costmap_2d/stereo_update_rate", stereo_update_rate , stereo_update_rate);
+ // Then allocate observation buffers
+ baseScanBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("base_laser"), tf_, ros::Duration(0, 0),
+ costmap_2d::BasicObservationBuffer::computeRefreshInterval(base_laser_update_rate),
+ inscribedRadius, minZ_, maxZ_);
+ tiltScanBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("laser_tilt_link"), tf_, ros::Duration(1, 0),
+ costmap_2d::BasicObservationBuffer::computeRefreshInterval(tilt_laser_update_rate),
+ inscribedRadius, minZ_, maxZ_);
+ stereoCloudBuffer_ = new costmap_2d::BasicObservationBuffer(std::string("stereo"), tf_, ros::Duration(0, 0),
+ costmap_2d::BasicObservationBuffer::computeRefreshInterval(stereo_update_rate),
+ inscribedRadius, minZ_, maxZ_);
// get map via RPC
std_srvs::StaticMap::request req;
@@ -348,7 +360,6 @@
std_msgs::PointCloud local_cloud;
local_cloud.header = baseScanMsg_.header;
projector_.projectLaser(baseScanMsg_, local_cloud, baseLaserMaxRange_);
- petTheWatchDog(local_cloud.header.stamp);
lock();
baseScanBuffer_->buffer_cloud(local_cloud);
unlock();
@@ -545,25 +556,14 @@
return false;
}
- void MoveBase::petTheWatchDog(const ros::Time& t){
- last_time_stamp_ = t;
- gettimeofday(&last_updated_, NULL);
- }
-
/**
- * At most one second between updates
+ * The conjunction of all observation buffers must be current
*/
bool MoveBase::checkWatchDog() const {
- struct timeval curr;
- gettimeofday(&curr,NULL);
- double curr_t, last_t, t_diff;
- last_t = last_updated_.tv_sec + last_updated_.tv_usec / 1e6;
- curr_t = curr.tv_sec + curr.tv_usec / 1e6;
- t_diff = curr_t - last_t;
- bool ok = t_diff < 1.0;
+ bool ok = baseScanBuffer_->isCurrent() && tiltScanBuffer_->isCurrent() && stereoCloudBuffer_->isCurrent();
if(!ok)
- ROS_DEBUG("Missed required cost map update. Should not allow commanding now. Check cost map data source.\n");
+ ROS_INFO("Missed required cost map update. Should not allow commanding now. Check cost map data source.\n");
return ok;
}
Modified: pkg/trunk/highlevel/test_highlevel_controllers/test/launch_move_base.xml
===================================================================
--- pkg/trunk/highlevel/test_highlevel_controllers/test/launch_move_base.xml 2008-12-11 20:16:45 UTC (rev 7985)
+++ pkg/trunk/highlevel/test_highlevel_controllers/test/launch_move_base.xml 2008-12-11 20:17:46 UTC (rev 7986)
@@ -19,6 +19,15 @@
<param name="/costmap_2d/circumscribed_radius" value="0.46"/>
<param name="/costmap_2d/inscribed_radius" value="0.325"/>
<param name="/costmap_2d/weight" value="0.1"/>
- <node pkg="highlevel_controllers" type="move_base_sbpl" respawn="false" />
+
+ <!-- Forces a check that we are receiving base scans that are correctly up to date at a rate of at least 5 Hz -->
+ <param name="/costmap_2d/base_laser_update_rate" value="5.0"/>
+
+ <!-- Setting these parameters to 0.0 disables the watchdo on them. For stage this is required since we
+ are not getting any data -->
+ <param name="/costmap_2d/tilt_laser_update_rate" value="0.0"/>
+ <param name="/costmap_2d/stereo_update_rate" value="0.0"/>
+
+ <node pkg="highlevel_controllers" type="move_base_sbpl" respawn="true"/>
</group>
</launch>
Modified: pkg/trunk/world_models/costmap_2d/include/costmap_2d/basic_observation_buffer.h
===================================================================
--- pkg/trunk/world_models/costmap_2d/include/costmap_2d/basic_observation_buffer.h 2008-12-11 20:16:45 UTC (rev 7985)
+++ pkg/trunk/world_models/costmap_2d/include/costmap_2d/basic_observation_buffer.h 2008-12-11 20:17:46 UTC (rev 7986)
@@ -42,7 +42,7 @@
*/
class BasicObservationBuffer: public ObservationBuffer {
public:
- BasicObservationBuffer(const std::string& frame_id, tf::TransformListener& tf, ros::Duration keepAlive, double robotRadius, double minZ, double maxZ);
+ BasicObservationBuffer(const std::string& frame_id, tf::TransformListener& tf, ros::Duration keepAlive, ros::Duration refresh_interval,double robotRadius, double minZ, double maxZ);
virtual void buffer_cloud(const std_msgs::PointCloud& local_cloud);
@@ -60,8 +60,6 @@
* filter based on the min and max z values
*/
std_msgs::PointCloud * extractFootprintAndGround(const std_msgs::PointCloud& baseFrameCloud) const;
-
- const std::string frame_id_;
tf::TransformListener& tf_;
std::deque<std_msgs::PointCloud> point_clouds_; /**< Buffer point clouds until a transform is available */
ros::thread::mutex buffer_mutex_;
Modified: pkg/trunk/world_models/costmap_2d/include/costmap_2d/observation_buffer.h
===================================================================
--- pkg/trunk/world_models/costmap_2d/include/costmap_2d/observation_buffer.h 2008-12-11 20:16:45 UTC (rev 7985)
+++ pkg/trunk/world_models/costmap_2d/include/costmap_2d/observation_buffer.h 2008-12-11 20:17:46 UTC (rev 7986)
@@ -47,7 +47,7 @@
*/
class ObservationBuffer {
public:
- ObservationBuffer(ros::Duration keep_alive):keep_alive_(keep_alive){}
+ ObservationBuffer(const std::string& frame_id, ros::Duration keep_alive, ros::Duration refresh_interval);
virtual ~ObservationBuffer();
@@ -63,9 +63,27 @@
*/
virtual void get_observations(std::vector<Observation>& observations);
+ /**
+ * @brief Checks if the buffered observations are up to date.
+ *
+ * In order to avoid working with stale data, we wish to check if the buffer has been updated
+ * within its refresh interval
+ */
+ bool isCurrent() const;
+
+
+ /**
+ * @brief Translates a rate to an interval in ros duration
+ */
+ static ros::Duration computeRefreshInterval(double rate);
+
+ protected:
+ const std::string frame_id_;
+
private:
std::list<Observation> buffer_;
const ros::Duration keep_alive_;
+ const ros::Duration refresh_interval_;
ros::Time last_updated_;
};
Modified: pkg/trunk/world_models/costmap_2d/src/basic_observation_buffer.cc
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/basic_observation_buffer.cc 2008-12-11 20:16:45 UTC (rev 7985)
+++ pkg/trunk/world_models/costmap_2d/src/basic_observation_buffer.cc 2008-12-11 20:17:46 UTC (rev 7986)
@@ -2,9 +2,9 @@
namespace costmap_2d {
- BasicObservationBuffer::BasicObservationBuffer(const std::string& frame_id, tf::TransformListener& tf, ros::Duration keepAlive,
+ BasicObservationBuffer::BasicObservationBuffer(const std::string& frame_id, tf::TransformListener& tf, ros::Duration keepAlive, ros::Duration refresh_interval,
double robotRadius, double minZ, double maxZ)
- : ObservationBuffer(keepAlive), frame_id_(frame_id), tf_(tf), robotRadius_(robotRadius), minZ_(minZ), maxZ_(maxZ){}
+ : ObservationBuffer(frame_id, keepAlive, refresh_interval), tf_(tf), robotRadius_(robotRadius), minZ_(minZ), maxZ_(maxZ){}
void BasicObservationBuffer::buffer_cloud(const std_msgs::PointCloud& local_cloud)
{
Modified: pkg/trunk/world_models/costmap_2d/src/observation_buffer.cc
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/observation_buffer.cc 2008-12-11 20:16:45 UTC (rev 7985)
+++ pkg/trunk/world_models/costmap_2d/src/observation_buffer.cc 2008-12-11 20:17:46 UTC (rev 7986)
@@ -33,6 +33,20 @@
namespace costmap_2d {
+ ros::Duration ObservationBuffer::computeRefreshInterval(double rate){
+ if(rate <= 0)
+ return ros::Duration(0, 0);
+
+ double period = 1 / rate;
+ return ros::Duration((int) rint(period), (int) rint((period - rint(period)) * pow(10.0, 9.0)));
+ }
+
+ ObservationBuffer::ObservationBuffer(const std::string& frame_id, ros::Duration keep_alive, ros::Duration refresh_interval)
+ :frame_id_(frame_id), keep_alive_(keep_alive), refresh_interval_(refresh_interval){
+ ROS_INFO("Initializing observation buffer for %s with keepAlive = %f and refresh_interval = %f\n",
+ frame_id_.c_str(), keep_alive.toSec(), refresh_interval_.toSec());
+ }
+
// Just clean up outstanding observations
ObservationBuffer::~ObservationBuffer(){
while(!buffer_.empty()){
@@ -46,7 +60,8 @@
// Only works if the observation is in the map frame - test for it. It should be transformed before
// we enque it
bool ObservationBuffer::buffer_observation(const Observation& observation){
- last_updated_ = observation.cloud_->header.stamp;
+ // Basically petting the watchdog here
+ last_updated_ = ros::Time::now();
if(observation.cloud_->header.frame_id != "map")
return false;
@@ -75,4 +90,15 @@
observations.push_back(*it);
}
}
+
+ bool ObservationBuffer::isCurrent() const {
+ static const ros::Duration FOREVER(0, 0);
+ bool ok = refresh_interval_ == FOREVER || (ros::Time::now() - last_updated_ <= refresh_interval_);
+
+ if(!ok){
+ ROS_INFO("Observation Buffer %s is not up to date. It has not been updated for %f seconds.", frame_id_.c_str(), (ros::Time::now() - last_updated_).toSec());
+ }
+
+ return ok;
+ }
}
Modified: pkg/trunk/world_models/costmap_2d/src/test/module-tests.cc
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/test/module-tests.cc 2008-12-11 20:16:45 UTC (rev 7985)
+++ pkg/trunk/world_models/costmap_2d/src/test/module-tests.cc 2008-12-11 20:17:46 UTC (rev 7986)
@@ -132,7 +132,7 @@
// Update the cost map for this observation
map.updateDynamicObstacles(wx, wy, obsBuf);
- // Verify that we know have only 8 * 4 + 4 cells with lethal cost, thus provong that we have correctly cleared
+ // Verify that we now have only 8 * 4 + 4 cells with lethal cost, thus provong that we have correctly cleared
// free space
unsigned int hitCount = 0;
for(unsigned int i=0; i <100; i++){
@@ -165,8 +165,55 @@
* Basic testing for observation buffer
*/
TEST(costmap, test15){
+ // Rate calculations
+ ASSERT_EQ(ObservationBuffer::computeRefreshInterval(-100), ros::Duration(0, 0));
+ ASSERT_EQ(ObservationBuffer::computeRefreshInterval(100), ros::Duration(0, 10000000));
+ ASSERT_EQ(ObservationBuffer::computeRefreshInterval(0), ros::Duration(0, 0));
+ ASSERT_EQ(ObservationBuffer::computeRefreshInterval(5), ros::Duration(0, (int)(0.2 * pow(10.0, 9.0))));
+ ASSERT_EQ(ObservationBuffer::computeRefreshInterval(0.3), ros::Duration(3, (int)((1.0/3.0) * pow(10.0, 9.0))));
+
ros::Duration keep_alive(10, 0);
- ObservationBuffer buffer(keep_alive);
+ ros::Duration refresh_interval(0, 200000000); // 200 ms
+ ObservationBuffer buffer("Foo", keep_alive, refresh_interval);
+
+ // Initially it should be false
+ ASSERT_EQ(buffer.isCurrent(), false);
+
+ std_msgs::Point origin; // Map origin
+ origin.x = 0;
+ origin.y = 0;
+ origin.z = 0;
+
+ ros::Time epoch; // Beginning of time
+
+ // Buffer a point cloud with a time stamp that is very old. It should still not be current
+ std_msgs::PointCloud* p0 = new std_msgs::PointCloud();
+ p0->set_pts_size(1);
+ p0->pts[0].x = 50;
+ p0->pts[0].y = 50;
+ p0->pts[0].z = MAX_Z;
+ p0->header.stamp = epoch;
+ Observation o0(origin, p0);
+ buffer.buffer_observation(o0);
+ // Up to date - ignores the time stamp.
+ ASSERT_EQ(buffer.isCurrent(), true);
+
+ // Now buffer another which has a current time stamp
+ std_msgs::PointCloud* p1 = new std_msgs::PointCloud();
+ p1->set_pts_size(1);
+ p1->pts[0].x = 50;
+ p1->pts[0].y = 50;
+ p1->pts[0].z = MAX_Z;
+ p1->header.stamp = ros::Time::now();
+ Observation o1(origin, p1);
+ buffer.buffer_observation(o1);
+ ASSERT_EQ(buffer.isCurrent(), true);
+
+ // Now go again after sleeping for a bit too long - 300 ms
+ ros::Time oldValue = ros::Time::now();
+ ros::Duration excessiveSleep(0, 300000000);
+ excessiveSleep.sleep();
+ ASSERT_EQ(buffer.isCurrent(), false);
}
/**
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-12-11 22:22:35
|
Revision: 7987
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7987&view=rev
Author: hsujohnhsu
Date: 2008-12-11 21:37:32 +0000 (Thu, 11 Dec 2008)
Log Message:
-----------
* update image test in gazebo_plugins tests according to xvfb-run produced image on desktop.
* move tuck arm command out of default controlers.
Modified Paths:
--------------
pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-simple-amcl.xml
pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-simple-fake_localization.xml
pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-amcl-no_x.xml
pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-amcl.xml
pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-fake_localization-no_x.xml
pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-fake_localization.xml
pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch
pkg/trunk/drivers/simulator/gazebo_plugin/test/test_camera.py
pkg/trunk/drivers/simulator/gazebo_plugin/test/test_camera.valid.ppm
Added Paths:
-----------
pkg/trunk/demos/pr2_gazebo/tuck_arms.py
Removed Paths:
-------------
pkg/trunk/demos/pr2_gazebo/setarms.py
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-simple-amcl.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-simple-amcl.xml 2008-12-11 20:17:46 UTC (rev 7986)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-simple-amcl.xml 2008-12-11 21:37:32 UTC (rev 7987)
@@ -7,6 +7,9 @@
<!-- load map -->
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/map3.png 0.1" respawn="false" output="screen" />
+ <!-- Tug Arms For Navigation -->
+ <node pkg="pr2_gazebo" type="tuck_arms.py" output="screen"/>
+
<!-- nav-stack -->
<include file="$(find 2dnav_gazebo)/2dnav-stack-amcl.xml"/>
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-simple-fake_localization.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-simple-fake_localization.xml 2008-12-11 20:17:46 UTC (rev 7986)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-simple-fake_localization.xml 2008-12-11 21:37:32 UTC (rev 7987)
@@ -7,6 +7,9 @@
<!-- load map -->
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/map3.png 0.1" respawn="false" output="screen" />
+ <!-- Tug Arms For Navigation -->
+ <node pkg="pr2_gazebo" type="tuck_arms.py" output="screen"/>
+
<!-- nav-stack -->
<include file="$(find 2dnav_gazebo)/2dnav-stack-fake_localization.xml"/>
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-amcl-no_x.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-amcl-no_x.xml 2008-12-11 20:17:46 UTC (rev 7986)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-amcl-no_x.xml 2008-12-11 21:37:32 UTC (rev 7987)
@@ -7,6 +7,9 @@
<!-- load map -->
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/willowMap.png 0.1" respawn="false" output="screen" />
+ <!-- Tug Arms For Navigation -->
+ <node pkg="pr2_gazebo" type="tuck_arms.py" output="screen"/>
+
<!-- nav-stack -->
<include file="$(find 2dnav_gazebo)/2dnav-stack-amcl.xml"/>
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-amcl.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-amcl.xml 2008-12-11 20:17:46 UTC (rev 7986)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-amcl.xml 2008-12-11 21:37:32 UTC (rev 7987)
@@ -7,6 +7,9 @@
<!-- load map -->
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/willowMap.png 0.1" respawn="false" output="screen" />
+ <!-- Tug Arms For Navigation -->
+ <node pkg="pr2_gazebo" type="tuck_arms.py" output="screen"/>
+
<!-- nav-stack -->
<include file="$(find 2dnav_gazebo)/2dnav-stack-amcl.xml"/>
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-fake_localization-no_x.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-fake_localization-no_x.xml 2008-12-11 20:17:46 UTC (rev 7986)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-fake_localization-no_x.xml 2008-12-11 21:37:32 UTC (rev 7987)
@@ -7,6 +7,9 @@
<!-- load map -->
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/willowMap.png 0.1" respawn="false" output="screen" />
+ <!-- Tug Arms For Navigation -->
+ <node pkg="pr2_gazebo" type="tuck_arms.py" output="screen"/>
+
<!-- nav-stack -->
<include file="$(find 2dnav_gazebo)/2dnav-stack-fake_localization.xml"/>
Modified: pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-fake_localization.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-fake_localization.xml 2008-12-11 20:17:46 UTC (rev 7986)
+++ pkg/trunk/demos/2dnav_gazebo/2dnav-gazebo-wg-fake_localization.xml 2008-12-11 21:37:32 UTC (rev 7987)
@@ -7,6 +7,9 @@
<!-- load map -->
<node pkg="map_server" type="map_server" args="$(find gazebo_robot_description)/world/Media/materials/textures/willowMap.png 0.1" respawn="false" output="screen" />
+ <!-- Tug Arms For Navigation -->
+ <node pkg="pr2_gazebo" type="tuck_arms.py" output="screen"/>
+
<!-- nav-stack -->
<include file="$(find 2dnav_gazebo)/2dnav-stack-fake_localization.xml"/>
Modified: pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch
===================================================================
--- pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch 2008-12-11 20:17:46 UTC (rev 7986)
+++ pkg/trunk/demos/pr2_gazebo/pr2_default_controllers.launch 2008-12-11 21:37:32 UTC (rev 7987)
@@ -9,7 +9,7 @@
<node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2_prototype1/controllers_head_laser_tilt_torso_gazebo.xml" output="screen"/>
<!-- Tug Arms For Navigation -->
- <node pkg="pr2_gazebo" type="setarms.py" output="screen"/>
+ <!--node pkg="pr2_gazebo" type="tuck_arms.py" output="screen"/-->
<!-- PR2 Calibration -->
<!--include file="$(find wg_robot_description)/pr2_prototype1/calibrate.launch" /-->
Deleted: pkg/trunk/demos/pr2_gazebo/setarms.py
===================================================================
--- pkg/trunk/demos/pr2_gazebo/setarms.py 2008-12-11 20:17:46 UTC (rev 7986)
+++ pkg/trunk/demos/pr2_gazebo/setarms.py 2008-12-11 21:37:32 UTC (rev 7987)
@@ -1,79 +0,0 @@
-#!/usr/bin/env python
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2008, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# * Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# * Redistributions in binary form must reproduce the above
-# copyright notice, this list of conditions and the following
-# disclaimer in the documentation and/or other materials provided
-# with the distribution.
-# * Neither the name of the Willow Garage nor the names of its
-# contributors may be used to endorse or promote products derived
-# from this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-
-## Gazebo tug arms for navigation
-
-PKG = 'pr2_gazebo'
-NAME = 'setarms'
-
-import math
-import rostools
-rostools.update_path(PKG)
-rostools.update_path('rostest')
-rostools.update_path('std_msgs')
-rostools.update_path('pr2_mechanism_controllers')
-rostools.update_path('robot_msgs')
-rostools.update_path('rospy')
-
-
-import sys, unittest
-import os, os.path, threading, time
-import rospy, rostest
-from std_msgs.msg import *
-from pr2_mechanism_controllers.msg import *
-
-
-CMD_POS_1 = 0.0
-CMD_POS_2 = 3.142
-CMD_POS_3 = 0.0
-CMD_POS_4 = 3.142
-CMD_POS_5 = 3.142
-CMD_POS_6 = 3.142
-CMD_POS_7 = 0.0
-CMD_POS_8 = 0.8
-
-if __name__ == '__main__':
- pub_l_arm = rospy.Publisher("left_arm_commands", JointPosCmd)
- pub_l_gripper = rospy.Publisher("l_gripper_controller/set_command", Float64)
- pub_r_arm = rospy.Publisher("right_arm_commands", JointPosCmd)
- pub_r_gripper = rospy.Publisher("r_gripper_controller/set_command", Float64)
- rospy.init_node(NAME, anonymous=True)
- timeout_t = time.time() + 10.0 #publish for 10 seconds then stop
- while time.time() < timeout_t:
- pub_l_arm.publish(JointPosCmd(['l_shoulder_pan_joint','l_shoulder_lift_joint','l_upper_arm_roll_joint','l_elbow_flex_joint','l_forearm_roll_joint','l_wrist_flex_joint','l_wrist_roll_joint'],[CMD_POS_1,CMD_POS_2,CMD_POS_3,CMD_POS_4,CMD_POS_5,CMD_POS_6,CMD_POS_7],[0,0,0,0,0,0,0],0))
- pub_l_gripper.publish(Float64(CMD_POS_8))
- pub_r_arm.publish(JointPosCmd(['r_shoulder_pan_joint','r_shoulder_lift_joint','r_upper_arm_rolr_joint','r_elbow_flex_joint','r_forearm_roll_joint','r_wrist_flex_joint','r_wrist_roll_joint'],[CMD_POS_1,CMD_POS_2,CMD_POS_3,CMD_POS_4,CMD_POS_5,CMD_POS_6,CMD_POS_7],[0,0,0,0,0,0,0],0))
- pub_r_gripper.publish(Float64(CMD_POS_8))
- time.sleep(0.2)
-
Copied: pkg/trunk/demos/pr2_gazebo/tuck_arms.py (from rev 7982, pkg/trunk/demos/pr2_gazebo/setarms.py)
===================================================================
--- pkg/trunk/demos/pr2_gazebo/tuck_arms.py (rev 0)
+++ pkg/trunk/demos/pr2_gazebo/tuck_arms.py 2008-12-11 21:37:32 UTC (rev 7987)
@@ -0,0 +1,79 @@
+#!/usr/bin/env python
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above
+# copyright notice, this list of conditions and the following
+# disclaimer in the documentation and/or other materials provided
+# with the distribution.
+# * Neither the name of the Willow Garage nor the names of its
+# contributors may be used to endorse or promote products derived
+# from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+
+## Gazebo tug arms for navigation
+
+PKG = 'pr2_gazebo'
+NAME = 'tuck_arms'
+
+import math
+import rostools
+rostools.update_path(PKG)
+rostools.update_path('rostest')
+rostools.update_path('std_msgs')
+rostools.update_path('pr2_mechanism_controllers')
+rostools.update_path('robot_msgs')
+rostools.update_path('rospy')
+
+
+import sys, unittest
+import os, os.path, threading, time
+import rospy, rostest
+from std_msgs.msg import *
+from pr2_mechanism_controllers.msg import *
+
+
+CMD_POS_1 = 0.0
+CMD_POS_2 = 3.142
+CMD_POS_3 = 0.0
+CMD_POS_4 = 3.142
+CMD_POS_5 = 3.142
+CMD_POS_6 = 3.142
+CMD_POS_7 = 0.0
+CMD_POS_8 = 0.8
+
+if __name__ == '__main__':
+ pub_l_arm = rospy.Publisher("left_arm_commands", JointPosCmd)
+ pub_l_gripper = rospy.Publisher("l_gripper_controller/set_command", Float64)
+ pub_r_arm = rospy.Publisher("right_arm_commands", JointPosCmd)
+ pub_r_gripper = rospy.Publisher("r_gripper_controller/set_command", Float64)
+ rospy.init_node(NAME, anonymous=True)
+ timeout_t = time.time() + 10.0 #publish for 10 seconds then stop
+ while time.time() < timeout_t:
+ pub_l_arm.publish(JointPosCmd(['l_shoulder_pan_joint','l_shoulder_lift_joint','l_upper_arm_roll_joint','l_elbow_flex_joint','l_forearm_roll_joint','l_wrist_flex_joint','l_wrist_roll_joint'],[CMD_POS_1,CMD_POS_2,CMD_POS_3,CMD_POS_4,CMD_POS_5,CMD_POS_6,CMD_POS_7],[0,0,0,0,0,0,0],0))
+ pub_l_gripper.publish(Float64(CMD_POS_8))
+ pub_r_arm.publish(JointPosCmd(['r_shoulder_pan_joint','r_shoulder_lift_joint','r_upper_arm_rolr_joint','r_elbow_flex_joint','r_forearm_roll_joint','r_wrist_flex_joint','r_wrist_roll_joint'],[CMD_POS_1,CMD_POS_2,CMD_POS_3,CMD_POS_4,CMD_POS_5,CMD_POS_6,CMD_POS_7],[0,0,0,0,0,0,0],0))
+ pub_r_gripper.publish(Float64(CMD_POS_8))
+ time.sleep(0.2)
+
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/test_camera.py
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/test_camera.py 2008-12-11 20:17:46 UTC (rev 7986)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/test_camera.py 2008-12-11 21:37:32 UTC (rev 7987)
@@ -56,8 +56,8 @@
FRAME_TARGET = "cam_sen-0050.ppm"
FRAME_DIR = "test_camera_frames"
TOTAL_ERROR_TOL = 5
-TEST_DURATION = 30
-TEST_INIT_WAIT = 10
+TEST_DURATION = 10
+TEST_INIT_WAIT = 40
class PollCameraThread(threading.Thread):
def __init__(self, target, dir):
@@ -160,9 +160,9 @@
print " - comparing images "
- im1.save("testsave.ppm") # uncomment this line to capture a new valid frame when things change
+ im1.save("test_1.ppm") # uncomment this line to capture a new valid frame when things change
im0.save("test_0.ppm")
- imc.save("test_diff.ppm")
+ imc.save("test_d.ppm")
#im1.show()
#im0.show()
#imc.show()
@@ -178,7 +178,7 @@
self.success = False
def test_camera(self):
- print " wait TEST_INIT_WAIT sec for objects to settle "
+ print " wait TEST_INIT_WAIT sec for objects to settle and arms to tuck "
time.sleep(TEST_INIT_WAIT)
print " subscribe stereo left image from ROS "
#rospy.TopicSub("test_camera/image", Image, self.imageInput) # this is a test camera, simply looking at the cups
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/test_camera.valid.ppm
===================================================================
(Binary files differ)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2008-12-12 17:10:01
|
Revision: 8009
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=8009&view=rev
Author: isucan
Date: 2008-12-12 17:09:54 +0000 (Fri, 12 Dec 2008)
Log Message:
-----------
deprecating planning_models (renamed to planning_models_with_libTF). A new planning_models will be added soon (old one ported to use bullet linear math)
Modified Paths:
--------------
pkg/trunk/deprecated/planning_models_with_libTF/CMakeLists.txt
pkg/trunk/deprecated/planning_models_with_libTF/manifest.xml
pkg/trunk/motion_planning/collision_space/manifest.xml
pkg/trunk/motion_planning/ompl/Makefile
pkg/trunk/motion_planning/plan_kinematic_path/manifest.xml
pkg/trunk/motion_planning/planning_node_util/manifest.xml
pkg/trunk/visualization/ogre_visualizer/manifest.xml
pkg/trunk/world_models/world_3d_map/manifest.xml
Added Paths:
-----------
pkg/trunk/deprecated/planning_models_with_libTF/
Removed Paths:
-------------
pkg/trunk/motion_planning/planning_models/
Property changes on: pkg/trunk/deprecated/planning_models_with_libTF
___________________________________________________________________
Added: svn:mergeinfo
+
Modified: pkg/trunk/deprecated/planning_models_with_libTF/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/planning_models/CMakeLists.txt 2008-12-11 23:34:08 UTC (rev 7992)
+++ pkg/trunk/deprecated/planning_models_with_libTF/CMakeLists.txt 2008-12-12 17:09:54 UTC (rev 8009)
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 2.6)
include(rosbuild)
-rospack(planning_models)
-rospack_add_library(planning_models src/planning_models/kinematic.cpp
+rospack(planning_models_with_libTF)
+rospack_add_library(planning_models_with_libtf src/planning_models/kinematic.cpp
# src/planning_models/kinodynamic.cpp
)
Modified: pkg/trunk/deprecated/planning_models_with_libTF/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_models/manifest.xml 2008-12-11 23:34:08 UTC (rev 7992)
+++ pkg/trunk/deprecated/planning_models_with_libTF/manifest.xml 2008-12-12 17:09:54 UTC (rev 8009)
@@ -12,7 +12,7 @@
<depend package="libTF"/>
<export>
- <cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lplanning_models"/>
+ <cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lplanning_models_with_libtf"/>
</export>
</package>
Modified: pkg/trunk/motion_planning/collision_space/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/collision_space/manifest.xml 2008-12-12 06:33:40 UTC (rev 8008)
+++ pkg/trunk/motion_planning/collision_space/manifest.xml 2008-12-12 17:09:54 UTC (rev 8009)
@@ -8,7 +8,7 @@
<review status="unreviewed" notes=""/>
<depend package="rosthread"/>
- <depend package="planning_models"/>
+ <depend package="planning_models_with_libTF"/>
<!--
We currently disable Octree collision checking since dependency on
Modified: pkg/trunk/motion_planning/ompl/Makefile
===================================================================
--- pkg/trunk/motion_planning/ompl/Makefile 2008-12-12 06:33:40 UTC (rev 8008)
+++ pkg/trunk/motion_planning/ompl/Makefile 2008-12-12 17:09:54 UTC (rev 8009)
@@ -1 +1,589 @@
-include $(shell rospack find mk)/cmake.mk
+# CMAKE generated file: DO NOT EDIT!
+# Generated by "Unix Makefiles" Generator, CMake Version 2.6
+
+# Default target executed when no arguments are given to make.
+default_target: all
+.PHONY : default_target
+
+#=============================================================================
+# Special targets provided by cmake.
+
+# Disable implicit rules so canoncical targets will work.
+.SUFFIXES:
+
+# Remove some rules from gmake that .SUFFIXES does not remove.
+SUFFIXES =
+
+.SUFFIXES: .hpux_make_needs_suffix_list
+
+# Suppress display of executed commands.
+$(VERBOSE).SILENT:
+
+# A target that is always out of date.
+cmake_force:
+.PHONY : cmake_force
+
+#=============================================================================
+# Set environment variables for the build.
+
+# The shell in which to execute make rules.
+SHELL = /bin/sh
+
+# The CMake executable.
+CMAKE_COMMAND = /home/isucan/repos/ros/3rdparty/cmake/cmake/bin/cmake
+
+# The command to remove a file.
+RM = /home/isucan/repos/ros/3rdparty/cmake/cmake/bin/cmake -E remove -f
+
+# The program to use to edit the cache.
+CMAKE_EDIT_COMMAND = /home/isucan/repos/ros/3rdparty/cmake/cmake/bin/ccmake
+
+# The top-level source directory on which CMake was run.
+CMAKE_SOURCE_DIR = /home/isucan/repos/ros-pkg/motion_planning/ompl
+
+# The top-level build directory on which CMake was run.
+CMAKE_BINARY_DIR = /home/isucan/repos/ros-pkg/motion_planning/ompl
+
+#=============================================================================
+# Targets provided globally by CMake.
+
+# Special rule for the target edit_cache
+edit_cache:
+ @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake cache editor..."
+ /home/isucan/repos/ros/3rdparty/cmake/cmake/bin/ccmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
+.PHONY : edit_cache
+
+# Special rule for the target edit_cache
+edit_cache/fast: edit_cache
+.PHONY : edit_cache/fast
+
+# Special rule for the target rebuild_cache
+rebuild_cache:
+ @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..."
+ /home/isucan/repos/ros/3rdparty/cmake/cmake/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
+.PHONY : rebuild_cache
+
+# Special rule for the target rebuild_cache
+rebuild_cache/fast: rebuild_cache
+.PHONY : rebuild_cache/fast
+
+# The main all target
+all: cmake_check_build_system
+ $(CMAKE_COMMAND) -E cmake_progress_start /home/isucan/repos/ros-pkg/motion_planning/ompl/CMakeFiles /home/isucan/repos/ros-pkg/motion_planning/ompl/CMakeFiles/progress.make
+ $(MAKE) -f CMakeFiles/Makefile2 all
+ $(CMAKE_COMMAND) -E cmake_progress_start /home/isucan/repos/ros-pkg/motion_planning/ompl/CMakeFiles 0
+.PHONY : all
+
+# The main clean target
+clean:
+ $(MAKE) -f CMakeFiles/Makefile2 clean
+.PHONY : clean
+
+# The main clean target
+clean/fast: clean
+.PHONY : clean/fast
+
+# Prepare targets for installation.
+preinstall: all
+ $(MAKE) -f CMakeFiles/Makefile2 preinstall
+.PHONY : preinstall
+
+# Prepare targets for installation.
+preinstall/fast:
+ $(MAKE) -f CMakeFiles/Makefile2 preinstall
+.PHONY : preinstall/fast
+
+# clear depends
+depend:
+ $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1
+.PHONY : depend
+
+#=============================================================================
+# Target rules for targets named gcoverage
+
+# Build rule for target.
+gcoverage: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 gcoverage
+.PHONY : gcoverage
+
+# fast build rule for target.
+gcoverage/fast:
+ $(MAKE) -f CMakeFiles/gcoverage.dir/build.make CMakeFiles/gcoverage.dir/build
+.PHONY : gcoverage/fast
+
+#=============================================================================
+# Target rules for targets named gcoverage-run
+
+# Build rule for target.
+gcoverage-run: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 gcoverage-run
+.PHONY : gcoverage-run
+
+# fast build rule for target.
+gcoverage-run/fast:
+ $(MAKE) -f CMakeFiles/gcoverage-run.dir/build.make CMakeFiles/gcoverage-run.dir/build
+.PHONY : gcoverage-run/fast
+
+#=============================================================================
+# Target rules for targets named ompl
+
+# Build rule for target.
+ompl: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 ompl
+.PHONY : ompl
+
+# fast build rule for target.
+ompl/fast:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/build
+.PHONY : ompl/fast
+
+#=============================================================================
+# Target rules for targets named ompl_code_ompl_base_util_src_output.cpp.gcov
+
+# Build rule for target.
+ompl_code_ompl_base_util_src_output.cpp.gcov: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 ompl_code_ompl_base_util_src_output.cpp.gcov
+.PHONY : ompl_code_ompl_base_util_src_output.cpp.gcov
+
+# fast build rule for target.
+ompl_code_ompl_base_util_src_output.cpp.gcov/fast:
+ $(MAKE) -f CMakeFiles/ompl_code_ompl_base_util_src_output.cpp.gcov.dir/build.make CMakeFiles/ompl_code_ompl_base_util_src_output.cpp.gcov.dir/build
+.PHONY : ompl_code_ompl_base_util_src_output.cpp.gcov/fast
+
+#=============================================================================
+# Target rules for targets named ompl_code_ompl_base_util_src_time.cpp.gcov
+
+# Build rule for target.
+ompl_code_ompl_base_util_src_time.cpp.gcov: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 ompl_code_ompl_base_util_src_time.cpp.gcov
+.PHONY : ompl_code_ompl_base_util_src_time.cpp.gcov
+
+# fast build rule for target.
+ompl_code_ompl_base_util_src_time.cpp.gcov/fast:
+ $(MAKE) -f CMakeFiles/ompl_code_ompl_base_util_src_time.cpp.gcov.dir/build.make CMakeFiles/ompl_code_ompl_base_util_src_time.cpp.gcov.dir/build
+.PHONY : ompl_code_ompl_base_util_src_time.cpp.gcov/fast
+
+#=============================================================================
+# Target rules for targets named ompl_code_ompl_extension_samplingbased_kinematic_extension_est_src_EST.cpp.gcov
+
+# Build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_extension_est_src_EST.cpp.gcov: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 ompl_code_ompl_extension_samplingbased_kinematic_extension_est_src_EST.cpp.gcov
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_extension_est_src_EST.cpp.gcov
+
+# fast build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_extension_est_src_EST.cpp.gcov/fast:
+ $(MAKE) -f CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_extension_est_src_EST.cpp.gcov.dir/build.make CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_extension_est_src_EST.cpp.gcov.dir/build
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_extension_est_src_EST.cpp.gcov/fast
+
+#=============================================================================
+# Target rules for targets named ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_LazyRRT.cpp.gcov
+
+# Build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_LazyRRT.cpp.gcov: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_LazyRRT.cpp.gcov
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_LazyRRT.cpp.gcov
+
+# fast build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_LazyRRT.cpp.gcov/fast:
+ $(MAKE) -f CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_LazyRRT.cpp.gcov.dir/build.make CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_LazyRRT.cpp.gcov.dir/build
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_LazyRRT.cpp.gcov/fast
+
+#=============================================================================
+# Target rules for targets named ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_RRT.cpp.gcov
+
+# Build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_RRT.cpp.gcov: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_RRT.cpp.gcov
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_RRT.cpp.gcov
+
+# fast build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_RRT.cpp.gcov/fast:
+ $(MAKE) -f CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_RRT.cpp.gcov.dir/build.make CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_RRT.cpp.gcov.dir/build
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_extension_rrt_src_RRT.cpp.gcov/fast
+
+#=============================================================================
+# Target rules for targets named ompl_code_ompl_extension_samplingbased_kinematic_extension_sbl_src_SBL.cpp.gcov
+
+# Build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_extension_sbl_src_SBL.cpp.gcov: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 ompl_code_ompl_extension_samplingbased_kinematic_extension_sbl_src_SBL.cpp.gcov
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_extension_sbl_src_SBL.cpp.gcov
+
+# fast build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_extension_sbl_src_SBL.cpp.gcov/fast:
+ $(MAKE) -f CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_extension_sbl_src_SBL.cpp.gcov.dir/build.make CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_extension_sbl_src_SBL.cpp.gcov.dir/build
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_extension_sbl_src_SBL.cpp.gcov/fast
+
+#=============================================================================
+# Target rules for targets named ompl_code_ompl_extension_samplingbased_kinematic_src_PathSmootherKinematic.cpp.gcov
+
+# Build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_src_PathSmootherKinematic.cpp.gcov: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 ompl_code_ompl_extension_samplingbased_kinematic_src_PathSmootherKinematic.cpp.gcov
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_src_PathSmootherKinematic.cpp.gcov
+
+# fast build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_src_PathSmootherKinematic.cpp.gcov/fast:
+ $(MAKE) -f CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_src_PathSmootherKinematic.cpp.gcov.dir/build.make CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_src_PathSmootherKinematic.cpp.gcov.dir/build
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_src_PathSmootherKinematic.cpp.gcov/fast
+
+#=============================================================================
+# Target rules for targets named ompl_code_ompl_extension_samplingbased_kinematic_src_SpaceInformationKinematic.cpp.gcov
+
+# Build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_src_SpaceInformationKinematic.cpp.gcov: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 ompl_code_ompl_extension_samplingbased_kinematic_src_SpaceInformationKinematic.cpp.gcov
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_src_SpaceInformationKinematic.cpp.gcov
+
+# fast build rule for target.
+ompl_code_ompl_extension_samplingbased_kinematic_src_SpaceInformationKinematic.cpp.gcov/fast:
+ $(MAKE) -f CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_src_SpaceInformationKinematic.cpp.gcov.dir/build.make CMakeFiles/ompl_code_ompl_extension_samplingbased_kinematic_src_SpaceInformationKinematic.cpp.gcov.dir/build
+.PHONY : ompl_code_ompl_extension_samplingbased_kinematic_src_SpaceInformationKinematic.cpp.gcov/fast
+
+#=============================================================================
+# Target rules for targets named test
+
+# Build rule for target.
+test: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 test
+.PHONY : test
+
+# fast build rule for target.
+test/fast:
+ $(MAKE) -f CMakeFiles/test.dir/build.make CMakeFiles/test.dir/build
+.PHONY : test/fast
+
+#=============================================================================
+# Target rules for targets named test-future
+
+# Build rule for target.
+test-future: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 test-future
+.PHONY : test-future
+
+# fast build rule for target.
+test-future/fast:
+ $(MAKE) -f CMakeFiles/test-future.dir/build.make CMakeFiles/test-future.dir/build
+.PHONY : test-future/fast
+
+#=============================================================================
+# Target rules for targets named test_grid
+
+# Build rule for target.
+test_grid: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 test_grid
+.PHONY : test_grid
+
+# fast build rule for target.
+test_grid/fast:
+ $(MAKE) -f CMakeFiles/test_grid.dir/build.make CMakeFiles/test_grid.dir/build
+.PHONY : test_grid/fast
+
+#=============================================================================
+# Target rules for targets named test_test_grid
+
+# Build rule for target.
+test_test_grid: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 test_test_grid
+.PHONY : test_test_grid
+
+# fast build rule for target.
+test_test_grid/fast:
+ $(MAKE) -f CMakeFiles/test_test_grid.dir/build.make CMakeFiles/test_test_grid.dir/build
+.PHONY : test_test_grid/fast
+
+#=============================================================================
+# Target rules for targets named tests
+
+# Build rule for target.
+tests: cmake_check_build_system
+ $(MAKE) -f CMakeFiles/Makefile2 tests
+.PHONY : tests
+
+# fast build rule for target.
+tests/fast:
+ $(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/build
+.PHONY : tests/fast
+
+code/examples/samplingbased/kinematic/grid/grid.o: code/examples/samplingbased/kinematic/grid/grid.cpp.o
+.PHONY : code/examples/samplingbased/kinematic/grid/grid.o
+
+# target to build an object file
+code/examples/samplingbased/kinematic/grid/grid.cpp.o:
+ $(MAKE) -f CMakeFiles/test_grid.dir/build.make CMakeFiles/test_grid.dir/code/examples/samplingbased/kinematic/grid/grid.cpp.o
+.PHONY : code/examples/samplingbased/kinematic/grid/grid.cpp.o
+
+code/examples/samplingbased/kinematic/grid/grid.i: code/examples/samplingbased/kinematic/grid/grid.cpp.i
+.PHONY : code/examples/samplingbased/kinematic/grid/grid.i
+
+# target to preprocess a source file
+code/examples/samplingbased/kinematic/grid/grid.cpp.i:
+ $(MAKE) -f CMakeFiles/test_grid.dir/build.make CMakeFiles/test_grid.dir/code/examples/samplingbased/kinematic/grid/grid.cpp.i
+.PHONY : code/examples/samplingbased/kinematic/grid/grid.cpp.i
+
+code/examples/samplingbased/kinematic/grid/grid.s: code/examples/samplingbased/kinematic/grid/grid.cpp.s
+.PHONY : code/examples/samplingbased/kinematic/grid/grid.s
+
+# target to generate assembly for a file
+code/examples/samplingbased/kinematic/grid/grid.cpp.s:
+ $(MAKE) -f CMakeFiles/test_grid.dir/build.make CMakeFiles/test_grid.dir/code/examples/samplingbased/kinematic/grid/grid.cpp.s
+.PHONY : code/examples/samplingbased/kinematic/grid/grid.cpp.s
+
+code/ompl/base/util/src/output.o: code/ompl/base/util/src/output.cpp.o
+.PHONY : code/ompl/base/util/src/output.o
+
+# target to build an object file
+code/ompl/base/util/src/output.cpp.o:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/base/util/src/output.cpp.o
+.PHONY : code/ompl/base/util/src/output.cpp.o
+
+code/ompl/base/util/src/output.i: code/ompl/base/util/src/output.cpp.i
+.PHONY : code/ompl/base/util/src/output.i
+
+# target to preprocess a source file
+code/ompl/base/util/src/output.cpp.i:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/base/util/src/output.cpp.i
+.PHONY : code/ompl/base/util/src/output.cpp.i
+
+code/ompl/base/util/src/output.s: code/ompl/base/util/src/output.cpp.s
+.PHONY : code/ompl/base/util/src/output.s
+
+# target to generate assembly for a file
+code/ompl/base/util/src/output.cpp.s:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/base/util/src/output.cpp.s
+.PHONY : code/ompl/base/util/src/output.cpp.s
+
+code/ompl/base/util/src/time.o: code/ompl/base/util/src/time.cpp.o
+.PHONY : code/ompl/base/util/src/time.o
+
+# target to build an object file
+code/ompl/base/util/src/time.cpp.o:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/base/util/src/time.cpp.o
+.PHONY : code/ompl/base/util/src/time.cpp.o
+
+code/ompl/base/util/src/time.i: code/ompl/base/util/src/time.cpp.i
+.PHONY : code/ompl/base/util/src/time.i
+
+# target to preprocess a source file
+code/ompl/base/util/src/time.cpp.i:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/base/util/src/time.cpp.i
+.PHONY : code/ompl/base/util/src/time.cpp.i
+
+code/ompl/base/util/src/time.s: code/ompl/base/util/src/time.cpp.s
+.PHONY : code/ompl/base/util/src/time.s
+
+# target to generate assembly for a file
+code/ompl/base/util/src/time.cpp.s:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/base/util/src/time.cpp.s
+.PHONY : code/ompl/base/util/src/time.cpp.s
+
+code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.o: code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.o
+
+# target to build an object file
+code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.o:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.o
+
+code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.i: code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.i
+
+# target to preprocess a source file
+code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.i:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.i
+
+code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.s: code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.s
+
+# target to generate assembly for a file
+code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.s:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/est/src/EST.cpp.s
+
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.o: code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.o
+
+# target to build an object file
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.o:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.o
+
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.i: code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.i
+
+# target to preprocess a source file
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.i:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.i
+
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.s: code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.s
+
+# target to generate assembly for a file
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.s:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp.s
+
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.o: code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.o
+
+# target to build an object file
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.o:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.o
+
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.i: code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.i
+
+# target to preprocess a source file
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.i:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.i
+
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.s: code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.s
+
+# target to generate assembly for a file
+code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.s:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp.s
+
+code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.o: code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.o
+
+# target to build an object file
+code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.o:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.o
+
+code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.i: code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.i
+
+# target to preprocess a source file
+code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.i:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.i
+
+code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.s: code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.s
+
+# target to generate assembly for a file
+code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.s:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/extension/sbl/src/SBL.cpp.s
+
+code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.o: code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.o
+
+# target to build an object file
+code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.o:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.o
+
+code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.i: code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.i
+
+# target to preprocess a source file
+code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.i:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.i
+
+code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.s: code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.s
+
+# target to generate assembly for a file
+code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.s:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.s
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/PathSmootherKinematic.cpp.s
+
+code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.o: code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.o
+
+# target to build an object file
+code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp.o:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp.o
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp.o
+
+code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.i: code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.i
+
+# target to preprocess a source file
+code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp.i:
+ $(MAKE) -f CMakeFiles/ompl.dir/build.make CMakeFiles/ompl.dir/code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp.i
+.PHONY : code/ompl/extension/samplingbased/kinematic/src/SpaceInformationKinematic.cpp.i
+
+code/ompl/ex...
[truncated message content] |