|
From: <tpr...@us...> - 2009-06-25 16:41:32
|
Revision: 17677
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17677&view=rev
Author: tpratkanis
Date: 2009-06-25 16:41:27 +0000 (Thu, 25 Jun 2009)
Log Message:
-----------
Renaming executive_trex_pr2 to trex_ros.
Modified Paths:
--------------
pkg/trunk/demos/2dnav_gazebo/trex/run_milestone_1_gazebo.xml
pkg/trunk/demos/2dnav_gazebo/trex/run_milestone_1_gazebo_empty.xml
pkg/trunk/highlevel/executive_python/milestone1/m1.launch
pkg/trunk/stacks/trex/trex_pr2/manifest.xml
pkg/trunk/stacks/trex/trex_ros/CMakeLists.txt
pkg/trunk/stacks/trex/trex_ros/include/executive_trex_pr2/ros_reactor.h
pkg/trunk/stacks/trex/trex_ros/src/monitor.cpp
Added Paths:
-----------
pkg/trunk/stacks/trex/trex_ros/
Removed Paths:
-------------
pkg/trunk/stacks/trex/executive_trex_pr2/
Modified: pkg/trunk/demos/2dnav_gazebo/trex/run_milestone_1_gazebo.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/trex/run_milestone_1_gazebo.xml 2009-06-25 16:21:40 UTC (rev 17676)
+++ pkg/trunk/demos/2dnav_gazebo/trex/run_milestone_1_gazebo.xml 2009-06-25 16:41:27 UTC (rev 17677)
@@ -4,7 +4,7 @@
<!-- start up trex -->
<param name="/trex/input_file" value="pr2.cfg"/>
- <param name="/trex/path" value="$(find 2dnav_gazebo)/trex:$(find executive_trex_pr2)/miles_gazebo.3:$(find 2dnav_gazebo)/trex/logs:$(find executive_trex_pr2)"/>
+ <param name="/trex/path" value="$(find 2dnav_gazebo)/trex:$(find trex_ros)/miles_gazebo.3:$(find 2dnav_gazebo)/trex/logs:$(find trex_ros)"/>
<param name="/trex/log_dir" value="$(find 2dnav_gazebo)/trex/logs"/>
<node pkg="trex_pr2" type="trexfast" output="screen" />
</launch>
Modified: pkg/trunk/demos/2dnav_gazebo/trex/run_milestone_1_gazebo_empty.xml
===================================================================
--- pkg/trunk/demos/2dnav_gazebo/trex/run_milestone_1_gazebo_empty.xml 2009-06-25 16:21:40 UTC (rev 17676)
+++ pkg/trunk/demos/2dnav_gazebo/trex/run_milestone_1_gazebo_empty.xml 2009-06-25 16:41:27 UTC (rev 17677)
@@ -4,7 +4,7 @@
<!-- start up trex -->
<param name="/trex/input_file" value="pr2.cfg"/>
- <param name="/trex/path" value="$(find 2dnav_gazebo)/trex:$(find executive_trex_pr2)/miles_gazebo.3:$(find 2dnav_gazebo)/trex/logs:$(find executive_trex_pr2)"/>
+ <param name="/trex/path" value="$(find 2dnav_gazebo)/trex:$(find trex_ros)/miles_gazebo.3:$(find 2dnav_gazebo)/trex/logs:$(find trex_ros)"/>
<param name="/trex/log_dir" value="$(find 2dnav_gazebo)/trex/logs"/>
<node pkg="trex_pr2" type="trexfast" output="screen" />
</launch>
Modified: pkg/trunk/highlevel/executive_python/milestone1/m1.launch
===================================================================
--- pkg/trunk/highlevel/executive_python/milestone1/m1.launch 2009-06-25 16:21:40 UTC (rev 17676)
+++ pkg/trunk/highlevel/executive_python/milestone1/m1.launch 2009-06-25 16:41:27 UTC (rev 17677)
@@ -6,7 +6,7 @@
<launch>
- <node pkg="executive_trex_pr2" type="fake_battery_controller.py">
+ <node pkg="trex_ros" type="fake_battery_controller.py">
<remap from="battery_state" to="bogus_battery_state"/>
</node>
<node pkg="highlevel_controllers" type="recharge_controller">
Modified: pkg/trunk/stacks/trex/trex_pr2/manifest.xml
===================================================================
--- pkg/trunk/stacks/trex/trex_pr2/manifest.xml 2009-06-25 16:21:40 UTC (rev 17676)
+++ pkg/trunk/stacks/trex/trex_pr2/manifest.xml 2009-06-25 16:41:27 UTC (rev 17677)
@@ -20,7 +20,7 @@
<depend package="door_msgs" />
<depend package="deprecated_msgs" />
<depend package="gtest" />
- <depend package="executive_trex_pr2" />
+ <depend package="trex_ros" />
<export>
<nddl iflags="-I${prefix}/nddl -I${prefix}/deprecated -I${prefix} "/>
Modified: pkg/trunk/stacks/trex/trex_ros/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/trex/executive_trex_pr2/CMakeLists.txt 2009-06-25 00:50:05 UTC (rev 17643)
+++ pkg/trunk/stacks/trex/trex_ros/CMakeLists.txt 2009-06-25 16:41:27 UTC (rev 17677)
@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 2.4.6)
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
#set(ROS_BUILD_TYPE Release)
-rospack(executive_trex_pr2)
+rospack(trex_ros)
genmsg()
gensrv()
Modified: pkg/trunk/stacks/trex/trex_ros/include/executive_trex_pr2/ros_reactor.h
===================================================================
--- pkg/trunk/stacks/trex/executive_trex_pr2/include/executive_trex_pr2/ros_reactor.h 2009-06-25 00:50:05 UTC (rev 17643)
+++ pkg/trunk/stacks/trex/trex_ros/include/executive_trex_pr2/ros_reactor.h 2009-06-25 16:41:27 UTC (rev 17677)
@@ -4,12 +4,13 @@
#include "ros/ros.h"
#include "ros/node.h"
#include "executive_trex_pr2/executive.h"
-#include "executive_trex_pr2/ExecuteGoals.h"
+#include "trex_ros/ExecuteGoals.h"
#include "DbCore.hh"
using namespace TREX;
using namespace EUROPA;
+using namespace trex_ros;
namespace executive_trex_pr2 {
/**
Modified: pkg/trunk/stacks/trex/trex_ros/src/monitor.cpp
===================================================================
--- pkg/trunk/stacks/trex/executive_trex_pr2/src/monitor.cpp 2009-06-25 00:50:05 UTC (rev 17643)
+++ pkg/trunk/stacks/trex/trex_ros/src/monitor.cpp 2009-06-25 16:41:27 UTC (rev 17677)
@@ -5,7 +5,7 @@
#include "Domains.hh"
#include "executive_trex_pr2/executive.h"
#include <vector>
-#include <executive_trex_pr2/TrexMonitor.h>
+#include <trex_ros/TrexMonitor.h>
namespace TREX {
@@ -32,7 +32,7 @@
ROS_ERROR("No topic for monitor, setting default: %s.", m_topic_name.c_str());
}
ros::NodeHandle node_handle;
- ros::Publisher m_pub = node_handle.advertise<executive_trex_pr2::TrexMonitor>(m_topic_name, 10);
+ ros::Publisher m_pub = node_handle.advertise<trex_ros::TrexMonitor>(m_topic_name, 10);
}
~Monitor() {
@@ -40,7 +40,7 @@
}
void notify(Observation const &obs) {
- executive_trex_pr2::TrexMonitor msg;
+ trex_ros::TrexMonitor msg;
msg.timeline = obs.getObjectName().c_str();
msg.set_variable_names_size(obs.countParameters());
msg.set_variable_values_size(obs.countParameters());
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-25 18:12:35
|
Revision: 17682
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17682&view=rev
Author: isucan
Date: 2009-06-25 18:11:51 +0000 (Thu, 25 Jun 2009)
Log Message:
-----------
some documentation
Modified Paths:
--------------
pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp
pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_mask.h
pkg/trunk/util/robot_self_filter/mainpage.dox
pkg/trunk/util/robot_self_filter/src/self_filter.cpp
pkg/trunk/util/robot_self_filter/src/test_filter.cpp
Modified: pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp 2009-06-25 18:11:51 UTC (rev 17682)
@@ -109,7 +109,6 @@
// configure the self mask and the message notifier
- sf_.configure();
std::vector<std::string> frames;
sf_.getLinkFrames(frames);
if (std::find(frames.begin(), frames.end(), robotFrame_) == frames.end())
Modified: pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_mask.h
===================================================================
--- pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_mask.h 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/util/robot_self_filter/include/robot_self_filter/self_mask.h 2009-06-25 18:11:51 UTC (rev 17682)
@@ -68,6 +68,7 @@
/** \brief Construct the filter */
SelfMask(tf::TransformListener &tf) : rm_("robot_description"), tf_(tf)
{
+ configure();
}
/** \brief Destructor to clean up
@@ -79,8 +80,6 @@
delete bodies_[i].body;
}
- bool configure(void);
-
/** \brief Compute the mask for a given pointcloud. If a mask element is true, the point
is outside the robot
*/
@@ -93,13 +92,18 @@
setup is performed, assumeFrame() should be called before use */
bool getMask(double x, double y, double z) const;
- /** Get the set of frames that correspond to the links */
+ /** \brief Get the set of frames that correspond to the links */
void getLinkFrames(std::vector<std::string> &frames) const;
private:
+ /** \brief Configure the filter. */
+ bool configure(void);
+
+ /** \brief Compute bounding spheres for the checked robot links. */
void computeBoundingSpheres(void);
+ /** \brief Perform the actual mask computation. */
void maskSimple(const robot_msgs::PointCloud& data_in, std::vector<bool> &mask);
planning_environment::RobotModels rm_;
Modified: pkg/trunk/util/robot_self_filter/mainpage.dox
===================================================================
--- pkg/trunk/util/robot_self_filter/mainpage.dox 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/util/robot_self_filter/mainpage.dox 2009-06-25 18:11:51 UTC (rev 17682)
@@ -2,8 +2,14 @@
\mainpage
\htmlinclude manifest.html
-\b new_robot_self_filter is ...
+\b robot_self_filter can either remove points from a pointcloud that
+are on the robot (parts the robot can see of itself) or it can
+annotate the points by adding a channel with a name of choice that
+will have values of 1.0 (point is outside the robot) or -1.0 (point is
+on the robot)
+
+
<!--
In addition to providing an overview of your package,
this is the section where the specification and design/architecture
@@ -13,7 +19,8 @@
-->
-\section codeapi Code API
+<!-- \section codeapi Code API
+-->
<!--
Provide links to specific auto-generated API documentation within your
@@ -34,86 +41,80 @@
APPEAR IN THE CODE. You should list names of every topic, service and
parameter used in your code. There is a template below that you can
use to document each node separately.
+-->
List of nodes:
-- \b node_name1
-- \b node_name2
--->
+- \b self_filter
+- \b test_filter
<!-- START: copy from here to 'END' for each node
<hr>
-\subsection node_name node_name
+\subsection self_filter self_filter
-node_name does (provide a basic description of your node)
+self_filter listents to a pointcloud on the 'cloud_in' topic and
+broadcasts a pointcloud on 'cloud_out' topic. There are two modes of
+using this node: it can either remove points that are on the robot
+from the input cloud and only broadcast the rest, or it can annotate
+the points with another channel with a name of choice.
+
\subsubsection Usage
\verbatim
-$ node_type1 [standard ROS args]
+$ self_filter [standard ROS params]
\endverbatim
\par Example
\verbatim
-$ node_type1
+$ self_filter robot_description:=robotdesc/pr2 cloud_in:=tilt_cloud cloud_out:=tilt_cloud_filtered
\endverbatim
\subsubsection topics ROS topics
Subscribes to:
-- \b "in": [std_msgs/FooType] description of in
+- \b "cloud_in": [robot_msgs/PointCloud]
Publishes to:
-- \b "out": [std_msgs/FooType] description of out
+- \b "cloud_out": [robot_msgs/PointCloud]
\subsubsection parameters ROS parameters
Reads the following parameters from the parameter server
-- \b "~param_name" : \b [type] description of param_name
-- \b "~my_param" : \b [string] description of my_param
+- \b "~annotate" : \b [string] if specified, this channel name will be added to the input pointcloud
+and no points will be removed. The values of this channel will be only -1.0 (point on robot) and 1.0
+(point outside)
-Sets the following parameters on the parameter server
+- \b "~robot_description" : \b [string] the URDF description of the robot
-- \b "~param_name" : \b [type] description of param_name
-\subsubsection services ROS services
-- \b "foo_service": [std_srvs/FooType] description of foo_service
+\subsection test_filter test_filter
+test_filter randomly generates points around & inside the robot and
+uses the filter to only keep the ones inside or the ones outside. The
+kept set is then sent as a visualization messages to rviz. This
+provides a simpl means to test the filter.
-END: copy for each node -->
-
-
-<!-- START: Uncomment if you have any command-line tools
-
-\section commandline Command-line tools
-
-This section is a catch-all for any additional tools that your package
-provides or uses that may be of use to the reader. For example:
-
-- tools/scripts (e.g. rospack, roscd)
-- roslaunch .launch files
-- xmlparam files
-
-\subsection script_name script_name
-
-Description of what this script/file does.
-
\subsubsection Usage
\verbatim
-$ ./script_name [args]
+$ test_filter [standard ROS params]
\endverbatim
\par Example
\verbatim
-$ ./script_name foo bar
+$ test_filter robot_description:=robotdesc/pr2
\endverbatim
-END: Command-Line Tools Section -->
+\subsubsection parameters ROS parameters
-*/
\ No newline at end of file
+Reads the following parameters from the parameter server
+
+- \b "~robot_description" : \b [string] the URDF description of the robot
+
+*/
Modified: pkg/trunk/util/robot_self_filter/src/self_filter.cpp
===================================================================
--- pkg/trunk/util/robot_self_filter/src/self_filter.cpp 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/util/robot_self_filter/src/self_filter.cpp 2009-06-25 18:11:51 UTC (rev 17682)
@@ -44,7 +44,6 @@
SelfFilter(void) : sf_(tf_), mn_(tf_, boost::bind(&SelfFilter::cloudCallback, this, _1), "cloud_in", "", 1)
{
- sf_.configure();
std::vector<std::string> frames;
sf_.getLinkFrames(frames);
mn_.setTargetFrame(frames);
Modified: pkg/trunk/util/robot_self_filter/src/test_filter.cpp
===================================================================
--- pkg/trunk/util/robot_self_filter/src/test_filter.cpp 2009-06-25 18:10:04 UTC (rev 17681)
+++ pkg/trunk/util/robot_self_filter/src/test_filter.cpp 2009-06-25 18:11:51 UTC (rev 17682)
@@ -45,7 +45,6 @@
TestSelfFilter(void) : sf_(tf_)
{
id_ = 1;
- sf_.configure();
vmPub_ = nodeHandle_.advertise<visualization_msgs::Marker>("visualization_marker", 10240);
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-25 18:28:25
|
Revision: 17683
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17683&view=rev
Author: isucan
Date: 2009-06-25 18:28:22 +0000 (Thu, 25 Jun 2009)
Log Message:
-----------
using annotated pointclouds
Modified Paths:
--------------
pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch
pkg/trunk/mapping/collision_map/collision_map_occ.launch
pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp
pkg/trunk/util/robot_self_filter/src/self_filter.cpp
Modified: pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch 2009-06-25 18:11:51 UTC (rev 17682)
+++ pkg/trunk/demos/tabletop_manipulation/launch/laser-perception.launch 2009-06-25 18:28:22 UTC (rev 17683)
@@ -13,11 +13,12 @@
<node pkg="robot_self_filter" type="self_filter" respawn="true" output="screen">
<remap from="robot_description" to="robotdesc/pr2" />
<remap from="cloud_in" to="tilt_scan_cloud" />
- <remap from="cloud_out" to="tilt_scan_cloud_filtered" />
+ <remap from="cloud_out" to="tilt_scan_cloud_annotated" />
+ <param name="annotate" type="string" value="on_self" />
</node>
<node pkg="point_cloud_assembler" type="point_cloud_assembler_srv" output="screen" name="point_cloud_assembler">
- <remap from="scan_in" to="tilt_scan_cloud_filtered"/>
+ <remap from="scan_in" to="tilt_scan_cloud_annotated"/>
<param name="tf_cache_time_secs" type="double" value="10.0" />
<param name="tf_tolerance_secs" type="double" value="0.0" />
<param name="max_scans" type="int" value="400" />
@@ -29,9 +30,9 @@
<node pkg="point_cloud_assembler" type="point_cloud_snapshotter" output="screen" name="snapshotter">
<remap from="laser_scanner_signal" to="laser_tilt_controller/laser_scanner_signal"/>
<remap from="build_cloud" to="point_cloud_assembler/build_cloud" />
- <remap from="full_cloud" to="full_cloud_filtered" />
+ <remap from="full_cloud" to="full_cloud_annotated" />
</node>
- <include file="$(find collision_map)/collision_map.launch" /> <!-- USE collision_map not collision_map_occ -->
+ <include file="$(find collision_map)/collision_map_occ.launch" />
</launch>
Modified: pkg/trunk/mapping/collision_map/collision_map_occ.launch
===================================================================
--- pkg/trunk/mapping/collision_map/collision_map_occ.launch 2009-06-25 18:11:51 UTC (rev 17682)
+++ pkg/trunk/mapping/collision_map/collision_map_occ.launch 2009-06-25 18:28:22 UTC (rev 17683)
@@ -1,8 +1,11 @@
<launch>
<node pkg="collision_map" type="collision_map_occ_node" name="collision_map_occ" respawn="true" output="screen">
- <remap from="cloud_in" to="full_cloud_filtered" />
+ <remap from="cloud_in" to="full_cloud_annotated" />
<remap from="robot_description" to="robotdesc/pr2" />
+ <!-- tell the collision map there may be an annotation channel telling which points are on the robot -->
+ <param name="cloud_annotation" type="string" value="on_self" />
+
<!-- a frame that does not change as the robot moves -->
<param name="fixed_frame" type="string" value="base_link" />
Modified: pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp 2009-06-25 18:11:51 UTC (rev 17682)
+++ pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp 2009-06-25 18:28:22 UTC (rev 17683)
@@ -54,6 +54,62 @@
CollisionMapperOcc(void) : sf_(tf_),
mn_(tf_, boost::bind(&CollisionMapperOcc::cloudCallback, this, _1), "cloud_in", "", 1)
{
+ loadParams();
+
+ // configure the self mask and the message notifier
+ std::vector<std::string> frames;
+ sf_.getLinkFrames(frames);
+ if (std::find(frames.begin(), frames.end(), robotFrame_) == frames.end())
+ frames.push_back(robotFrame_);
+ mn_.setTargetFrame(frames);
+
+ // advertise our topic
+ cmapPublisher_ = nh_.advertise<robot_msgs::CollisionMap>("collision_map_occ", 1);
+ }
+
+private:
+
+ struct CollisionPoint
+ {
+ int x, y, z;
+ };
+
+ struct CollisionPointOrder
+ {
+ bool operator()(const CollisionPoint &a, const CollisionPoint &b)
+ {
+ if (a.x < b.x)
+ return true;
+ if (a.x > b.x)
+ return false;
+ if (a.y < b.y)
+ return true;
+ if (a.y > b.y)
+ return false;
+ return a.z < b.z;
+ }
+ };
+
+ // parameters & precomputed values for the box that represents the collision map
+ // around the robot
+ struct BoxInfo
+ {
+ double dimensionX, dimensionY, dimensionZ;
+ double originX, originY, originZ;
+ double sensorX, sensorY, sensorZ;
+ double resolution;
+ int radius;
+ int sx, sy, sz;
+ int minX, minY, minZ;
+ int maxX, maxY, maxZ;
+ double real_minX, real_minY, real_minZ;
+ double real_maxX, real_maxY, real_maxZ;
+ };
+
+ typedef std::set<CollisionPoint, CollisionPointOrder> CMap;
+
+ void loadParams(void)
+ {
// a frame that does not move with the robot
nh_.param<std::string>("~fixed_frame", fixedFrame_, "odom");
@@ -85,7 +141,9 @@
"sensor is at (%f, %f, %f), fixed fame is '%s', radius for raytraced occlusions is %d.",
robotFrame_.c_str(), bi_.dimensionX, bi_.dimensionY, bi_.dimensionZ, bi_.originX, bi_.originY, bi_.originZ, bi_.resolution,
bi_.sensorX, bi_.sensorY, bi_.sensorZ, fixedFrame_.c_str(), bi_.radius);
-
+
+ nh_.param<std::string>("~cloud_annotation", cloud_annotation_, std::string());
+
// compute some useful values
bi_.sx = (int)(0.5 + (bi_.sensorX - bi_.originX) / bi_.resolution);
bi_.sy = (int)(0.5 + (bi_.sensorY - bi_.originY) / bi_.resolution);
@@ -105,61 +163,37 @@
bi_.real_minY = -bi_.dimensionY + bi_.originY;
bi_.real_maxY = bi_.dimensionY + bi_.originY;
bi_.real_minZ = -bi_.dimensionZ + bi_.originZ;
- bi_.real_maxZ = bi_.dimensionZ + bi_.originZ;
-
-
- // configure the self mask and the message notifier
- std::vector<std::string> frames;
- sf_.getLinkFrames(frames);
- if (std::find(frames.begin(), frames.end(), robotFrame_) == frames.end())
- frames.push_back(robotFrame_);
- mn_.setTargetFrame(frames);
-
- // advertise our topic
- cmapPublisher_ = nh_.advertise<robot_msgs::CollisionMap>("collision_map_occ", 1);
+ bi_.real_maxZ = bi_.dimensionZ + bi_.originZ;
}
-private:
-
- struct CollisionPoint
+ void computeCloudMask(const robot_msgs::PointCloud &cloud, std::vector<bool> &mask)
{
- int x, y, z;
- };
-
- struct CollisionPointOrder
- {
- bool operator()(const CollisionPoint &a, const CollisionPoint &b)
+ if (cloud_annotation_.empty())
+ sf_.mask(cloud, mask);
+ else
{
- if (a.x < b.x)
- return true;
- if (a.x > b.x)
- return false;
- if (a.y < b.y)
- return true;
- if (a.y > b.y)
- return false;
- return a.z < b.z;
+ int c = -1;
+ for (unsigned int i = 0 ; i < cloud.chan.size() ; ++i)
+ if (cloud.chan[i].name == cloud_annotation_)
+ {
+ c = i;
+ break;
+ }
+ if (c < 0)
+ {
+ ROS_WARN("Cloud annotation channel '%s' is missing", cloud_annotation_.c_str());
+ sf_.mask(cloud, mask);
+ }
+ else
+ {
+ ROS_ASSERT(cloud.chan[c].vals.size() == cloud.pts.size());
+ mask.resize(cloud.pts.size());
+ for (unsigned int i = 0 ; i < mask.size() ; ++i)
+ mask[i] = cloud.chan[c].vals[i] > 0.0;
+ }
}
- };
-
- // parameters & precomputed values for the box that represents the collision map
- // around the robot
- struct BoxInfo
- {
- double dimensionX, dimensionY, dimensionZ;
- double originX, originY, originZ;
- double sensorX, sensorY, sensorZ;
- double resolution;
- int radius;
- int sx, sy, sz;
- int minX, minY, minZ;
- int maxX, maxY, maxZ;
- double real_minX, real_minY, real_minZ;
- double real_maxX, real_maxY, real_maxZ;
- };
+ }
- typedef std::set<CollisionPoint, CollisionPointOrder> CMap;
-
void cloudCallback(const robot_msgs::PointCloudConstPtr &cloud)
{
std::vector<bool> mask;
@@ -181,7 +215,7 @@
{
// separate the received points into ones on the robot and ones that are obstacles
// the frame of the cloud does not matter here
- sf_.mask(*cloud, mask);
+ computeCloudMask(*cloud, mask);
}
}
@@ -616,7 +650,8 @@
ros::NodeHandle nh_;
ros::Publisher cmapPublisher_;
roslib::Header header_;
-
+ std::string cloud_annotation_;
+
CMap currentMap_;
BoxInfo bi_;
std::string fixedFrame_;
Modified: pkg/trunk/util/robot_self_filter/src/self_filter.cpp
===================================================================
--- pkg/trunk/util/robot_self_filter/src/self_filter.cpp 2009-06-25 18:11:51 UTC (rev 17682)
+++ pkg/trunk/util/robot_self_filter/src/self_filter.cpp 2009-06-25 18:28:22 UTC (rev 17683)
@@ -47,7 +47,7 @@
std::vector<std::string> frames;
sf_.getLinkFrames(frames);
mn_.setTargetFrame(frames);
- nh_.param<std::string>("/self_filter/annotate", annotate_, std::string());
+ nh_.param<std::string>("~annotate", annotate_, std::string());
pointCloudPublisher_ = nh_.advertise<robot_msgs::PointCloud>("cloud_out", 1);
if (!annotate_.empty())
ROS_INFO("Self filter is adding annotation channel '%s'", annotate_.c_str());
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <stu...@us...> - 2009-06-26 01:22:26
|
Revision: 17735
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17735&view=rev
Author: stuglaser
Date: 2009-06-26 00:55:23 +0000 (Fri, 26 Jun 2009)
Log Message:
-----------
The JointVelocityController has the new-style init function, and can also communicate with ROS on its own.
Modified Paths:
--------------
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp
pkg/trunk/stacks/mechanism/mechanism_model/include/mechanism_model/controller.h
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h 2009-06-26 00:55:08 UTC (rev 17734)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h 2009-06-26 00:55:23 UTC (rev 17735)
@@ -48,10 +48,19 @@
<pid p="1.0" i="2.0" d="3.0" iClamp="4.0" /><br>
</joint><br>
</controller><br>
+
+ Configuration:
+ <controller name>:
+ type: "JointVelocityController"
+ joint: "<joint_name>"
+ pid: { p: <p_gain>, i: <i_gain>, d: <d_gain>, i_clamp: <i_clamp> }
+
+
*/
/***************************************************/
#include <ros/node.h>
+#include <ros/node_handle.h>
#include "mechanism_model/controller.h"
#include "control_toolbox/pid.h"
@@ -86,6 +95,7 @@
*/
bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
bool init(mechanism::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid);
+ bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
@@ -113,11 +123,20 @@
double dt_;
private:
+ ros::NodeHandle node_;
mechanism::RobotState *robot_; /**< Pointer to robot structure. */
control_toolbox::Pid pid_controller_; /**< Internal PID controller. */
double last_time_; /**< Last time stamp of update. */
+ int loop_count_;
double command_; /**< Last commanded position. */
friend class JointVelocityControllerNode;
+
+ boost::scoped_ptr<
+ realtime_tools::RealtimePublisher<
+ robot_mechanism_controllers::JointControllerState> > controller_state_publisher_ ;
+
+ ros::Subscriber sub_command_;
+ void setCommandCB(const std_msgs::Float64ConstPtr& msg);
};
/***************************************************/
@@ -161,6 +180,7 @@
JointVelocityController *c_; /**< The controller. */
control_toolbox::PidGainsSetter pid_tuner_;
+ int count;
};
}
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp 2009-06-26 00:55:08 UTC (rev 17734)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp 2009-06-26 00:55:23 UTC (rev 17735)
@@ -35,17 +35,19 @@
#include <robot_mechanism_controllers/joint_velocity_controller.h>
using namespace std;
-using namespace controller;
+namespace controller {
+
ROS_REGISTER_CONTROLLER(JointVelocityController)
JointVelocityController::JointVelocityController()
-: joint_state_(NULL), robot_(NULL), last_time_(0), command_(0)
+: joint_state_(NULL), robot_(NULL), last_time_(0), loop_count_(0), command_(0)
{
}
JointVelocityController::~JointVelocityController()
{
+ sub_command_.shutdown();
}
bool JointVelocityController::init(mechanism::RobotState *robot, const std::string &joint_name,
@@ -94,6 +96,31 @@
return init(robot, joint_name, pid);
}
+bool JointVelocityController::init(mechanism::RobotState *robot, const ros::NodeHandle &n)
+{
+ assert(robot);
+ node_ = n;
+
+ std::string joint_name;
+ if (!node_.getParam("joint", joint_name)) {
+ ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
+ return false;
+ }
+
+ control_toolbox::Pid pid;
+ if (!pid.init(ros::NodeHandle(node_, "pid")))
+ return false;
+
+ controller_state_publisher_.reset(
+ new realtime_tools::RealtimePublisher<robot_mechanism_controllers::JointControllerState>
+ (node_, "state", 1));
+
+ sub_command_ = node_.subscribe<std_msgs::Float64>("set_command", 1, &JointVelocityController::setCommandCB, this);
+
+ return init(robot, joint_name, pid);
+}
+
+
void JointVelocityController::setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
{
pid_controller_.setGains(p,i,d,i_max,i_min);
@@ -125,20 +152,45 @@
void JointVelocityController::update()
{
assert(robot_ != NULL);
- double error(0);
double time = robot_->hw_->current_time_;
- error =joint_state_->velocity_ - command_;
- dt_= time - last_time_;
+ double error = joint_state_->velocity_ - command_;
+ dt_ = time - last_time_;
joint_state_->commanded_effort_ += pid_controller_.updatePid(error, dt_);
+ if(loop_count_ % 10 == 0)
+ {
+ if(controller_state_publisher_ && controller_state_publisher_->trylock())
+ {
+ controller_state_publisher_->msg_.set_point = command_;
+ controller_state_publisher_->msg_.process_value = joint_state_->velocity_;
+ controller_state_publisher_->msg_.error = error;
+ controller_state_publisher_->msg_.time_step = dt_;
+
+ double dummy;
+ getGains(controller_state_publisher_->msg_.p,
+ controller_state_publisher_->msg_.i,
+ controller_state_publisher_->msg_.d,
+ controller_state_publisher_->msg_.i_clamp,
+ dummy);
+ controller_state_publisher_->unlockAndPublish();
+ }
+ }
+ loop_count_++;
+
last_time_ = time;
}
+void JointVelocityController::setCommandCB(const std_msgs::Float64ConstPtr& msg)
+{
+ command_ = msg->data;
+}
+
+
//------ Joint Velocity controller node --------
ROS_REGISTER_CONTROLLER(JointVelocityControllerNode)
-JointVelocityControllerNode::JointVelocityControllerNode(): node_(ros::Node::instance())
+JointVelocityControllerNode::JointVelocityControllerNode(): node_(ros::Node::instance()), count(0)
{
c_ = new JointVelocityController();
controller_state_publisher_ = NULL;
@@ -153,7 +205,6 @@
void JointVelocityControllerNode::update()
{
- static int count = 0;
c_->update();
if(count % 10 == 0)
@@ -217,3 +268,5 @@
resp.v = cmd;
return true;
}
+
+} // namespace
Modified: pkg/trunk/stacks/mechanism/mechanism_model/include/mechanism_model/controller.h
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_model/include/mechanism_model/controller.h 2009-06-26 00:55:08 UTC (rev 17734)
+++ pkg/trunk/stacks/mechanism/mechanism_model/include/mechanism_model/controller.h 2009-06-26 00:55:23 UTC (rev 17735)
@@ -48,6 +48,7 @@
#include <tinyxml/tinyxml.h>
#include <std_srvs/Empty.h>
#include <ros/node.h>
+#include <ros/node_handle.h>
namespace controller
{
@@ -76,16 +77,17 @@
static RosController##c ROS_CONTROLLER_##c;
-
class Controller
{
public:
enum {CONSTRUCTED, INITIALIZED, RUNNING};
int state_;
+ bool autostart_;
Controller()
{
state_ = CONSTRUCTED;
+ autostart_ = true;
}
virtual ~Controller()
{
@@ -97,6 +99,7 @@
virtual void update(void) = 0;
virtual bool stopping() {return true;}
virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config) = 0;
+ virtual bool init(mechanism::RobotState *robot, const ros::NodeHandle &n) { return false; };
bool isRunning()
{
@@ -137,6 +140,27 @@
return ret;
}
+ bool initRequest(mechanism::RobotState *robot, const ros::NodeHandle &n)
+ {
+ if (state_ != CONSTRUCTED)
+ return false;
+ else
+ {
+ // initialize
+ if (!init(robot, n))
+ return false;
+ state_ = INITIALIZED;
+
+ // autostart if needed
+ ros::NodeHandle nn;
+ nn.param("~autostart", autostart_, true);
+ if (autostart_ && !startRequest())
+ return false;
+
+ return true;
+ }
+ }
+
bool initXmlRequest(mechanism::RobotState *robot, TiXmlElement *config, std::string controller_name)
{
if (state_ != CONSTRUCTED)
@@ -148,6 +172,11 @@
return false;
state_ = INITIALIZED;
+ // autostart if needed
+ ros::Node::instance()->param(controller_name+"/autostart", autostart_, true);
+ if (autostart_ && !startRequest())
+ return false;
+
return true;
}
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <wa...@us...> - 2009-06-26 04:11:54
|
Revision: 17753
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17753&view=rev
Author: wattsk
Date: 2009-06-26 04:11:49 +0000 (Fri, 26 Jun 2009)
Log Message:
-----------
Moved disk_usage.py to pr2_computer_monitor
Modified Paths:
--------------
pkg/trunk/pr2/life_test/manifest.xml
pkg/trunk/pr2/life_test/simple_test/fake_test.py
pkg/trunk/pr2/life_test/simple_test/test.launch
pkg/trunk/pr2/life_test/src/life_test/life_test.py
pkg/trunk/pr2/life_test/src/life_test/ui.py
pkg/trunk/pr2/life_test/tests.xml
pkg/trunk/pr2/life_test/xrc/gui.fbp
pkg/trunk/pr2/life_test/xrc/gui.xrc
pkg/trunk/pr2/motorconf_gui/src/motorconf_gui/ui.py
pkg/trunk/pr2/pr2_computer_monitor/manifest.xml
pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py
pkg/trunk/pr2/qualification/manifest.xml
pkg/trunk/pr2/qualification/scripts/hysteresis_sinesweep_plot.py
pkg/trunk/pr2/qualification/src/qualification/result.py
pkg/trunk/pr2/qualification/src/qualification/ui.py
pkg/trunk/pr2/qualification/tests/simple_example/startup.launch
Added Paths:
-----------
pkg/trunk/pr2/life_test/msg/
pkg/trunk/pr2/life_test/msg/DeviceReading.msg
pkg/trunk/pr2/life_test/msg/TestStatus.msg
pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py
pkg/trunk/pr2/life_test/simple_test/fake_trans.csv
pkg/trunk/pr2/life_test/src/life_test/test_param.py
pkg/trunk/pr2/life_test/src/life_test/test_record.py
pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/disk_usage.py
pkg/trunk/pr2/wg_hardware_roslaunch/
pkg/trunk/pr2/wg_hardware_roslaunch/manifest.xml
pkg/trunk/pr2/wg_hardware_roslaunch/src/
pkg/trunk/pr2/wg_hardware_roslaunch/src/wg_hardware_roslaunch/
pkg/trunk/pr2/wg_hardware_roslaunch/src/wg_hardware_roslaunch/__init__.py
pkg/trunk/pr2/wg_hardware_roslaunch/src/wg_hardware_roslaunch/roslaunch_caller.py
Removed Paths:
-------------
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/disk_usage.py
Modified: pkg/trunk/pr2/life_test/manifest.xml
===================================================================
--- pkg/trunk/pr2/life_test/manifest.xml 2009-06-26 03:55:29 UTC (rev 17752)
+++ pkg/trunk/pr2/life_test/manifest.xml 2009-06-26 04:11:49 UTC (rev 17753)
@@ -31,4 +31,6 @@
<depend package="runtime_monitor" />
<depend package="invent_client" />
<depend package="diagnostic_msgs" />
+ <depend package="wg_hardware_roslaunch" />
+ <depend package="mechanism_msgs" />
</package>
Added: pkg/trunk/pr2/life_test/msg/DeviceReading.msg
===================================================================
--- pkg/trunk/pr2/life_test/msg/DeviceReading.msg (rev 0)
+++ pkg/trunk/pr2/life_test/msg/DeviceReading.msg 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1,9 @@
+byte DEVICE_OK = 0
+byte DEVICE_BROKEN = 1
+byte DEVICE_NO_EXIST = 2
+
+string joint_name
+string act_name
+byte cal_reading
+float64 position
+byte status
\ No newline at end of file
Added: pkg/trunk/pr2/life_test/msg/TestStatus.msg
===================================================================
--- pkg/trunk/pr2/life_test/msg/TestStatus.msg (rev 0)
+++ pkg/trunk/pr2/life_test/msg/TestStatus.msg 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1,7 @@
+byte TEST_RUNNING = 0
+byte TEST_WARNING = 1
+byte TEST_ERROR = 2
+byte TEST_STALE = 3
+
+byte test_ok
+string message
\ No newline at end of file
Added: pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py
===================================================================
--- pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py (rev 0)
+++ pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1,207 @@
+#!/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 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: Kevin Watts
+
+import roslib
+roslib.load_manifest('life_test')
+
+from mechanism_msgs.msg import MechanismState
+from diagnostic_msgs.msg import *
+
+from std_srvs.srv import *
+
+from life_test import *
+from life_test.msg import TestStatus
+from life_test.trans_monitor import TransmissionMonitor
+
+import rospy
+
+import sys, os
+
+import threading
+import traceback
+import csv
+
+
+class EtherCATTestMonitorNode():
+ def __init__(self):
+ rospy.init_node('test_monitor', anonymous = True)
+
+ csv_filename = rospy.myargv()[1] # CSV of device data
+ self.create_trans_monitors(csv_filename)
+
+ self._mutex = threading.Lock()
+
+ self._ethercat_ok = True
+ self._transmissions_ok = True
+ self._ethercat_update_time = 0
+ self._mech_update_time = 0
+ self._diags = []
+ self._trans_status = []
+
+ self.test_status_pub = rospy.Publisher('test_status', TestStatus)
+ self.diag_sub = rospy.Subscriber('/diagnostics', DiagnosticMessage, self.diag_callback)
+ self.diag_pub = rospy.Publisher('/diagnostics', DiagnosticMessage)
+
+ self.reset_motors = rospy.ServiceProxy('reset_motors', Empty)
+ self.halt_motors = rospy.ServiceProxy('halt_motors', Empty)
+
+ self.reset_srv = rospy.Service('reset_test', Empty, self.reset_test)
+ self.halt_srv = rospy.Service('halt_test', Empty, self.halt_test)
+
+ self.mech_state_sub = rospy.Subscriber('mechanism_state', MechanismState, self.mech_state_callback)
+
+ # Publish status at 1Hz
+ self._timer = threading.Timer(1.0, self.publish_status)
+ self._timer.start()
+
+ rospy.spin()
+
+ def __del__(self):
+ self.test_status_pub.unregister()
+ self.diag_sub.unregister()
+ self.mech_state_sub.unregister()
+
+ self.reset_srv.unregister()
+ self.halt_srv.unregister()
+
+
+ def create_trans_monitors(self, csv_filename):
+ self._trans_monitors = []
+ trans_csv = csv.reader(open(csv_filename, 'rb'))
+ for row in trans_csv:
+ actuator = row[0].lstrip().rstrip()
+ joint = row[1].lstrip().rstrip()
+ ref = float(row[2])
+ deadband = float(row[3])
+ continuous = (int(row[4]) == 1)
+ positive = (int(row[5]) == 1)
+ self._trans_monitors.append(TransmissionMonitor(
+ actuator, joint, ref,
+ deadband, continuous, positive))
+
+ def publish_status(self):
+ self._mutex.acquire()
+
+ self.check_diags()
+
+ status = TestStatus()
+
+ if rospy.get_time() - self._ethercat_update_time > 3 or rospy.get_time() - self._mech_update_time > 1:
+ status.test_ok = TestStatus.TEST_STALE
+ status.message = 'EtherCAT Master Stale'
+ elif self._ethercat_ok and self._transmissions_ok:
+ status.test_ok = TestStatus.TEST_RUNNING
+ status.message = 'OK'
+ else:
+ status.test_ok = TestStatus.TEST_ERROR
+ if not self._transmissions_ok:
+ status.message = 'Transmission Broken'
+ else:
+ status.message = 'EtherCAT Halted'
+
+ self.test_status_pub.publish(status)
+
+ self.diag_pub.publish(status = self._trans_status)
+
+ # Halt the test if we have a bad transmission
+ if self._ethercat_ok and not self._transmissions_ok:
+ self.halt_motors()
+
+ if not rospy.is_shutdown():
+ timer = threading.Timer(0.5, self.publish_status)
+ timer.start()
+
+ self._mutex.release()
+
+
+ def reset_test(self, srv):
+ self._mutex.acquire() # Need this here?
+
+ for monitor in self._trans_monitors:
+ monitor.reset()
+ self.reset_motors()
+
+ self._mutex.release()
+ return EmptyResponse()
+
+ def halt_test(self, srv = None):
+ self.halt_motors()
+ return EmptyResponse()
+
+ def mech_state_callback(self, mech_state):
+ self._mutex.acquire()
+
+ self._mech_update_time = rospy.get_time()
+
+ self._transmissions_ok = True
+ self._trans_status = []
+ for monitor in self._trans_monitors:
+ diag, state = monitor.update(mech_state)
+ self._trans_status.append(diag)
+ self._transmissions_ok = self._transmissions_ok and state
+
+ self._mutex.release()
+
+ def diag_callback(self, msg):
+ self._mutex.acquire()
+ self._diags.append(msg)
+ self._mutex.release()
+
+ def check_diags(self):
+ # Checks EtherCAT Master diagnostics to see if test running
+ etherCAT_master_name = 'EtherCAT Master'
+ try:
+ for msg in self._diags:
+ for stat in msg.status:
+ if stat.name == 'EtherCAT Master':
+ self._ethercat_ok = (stat.level == 0)
+ self._ethercat_update_time = rospy.get_time()
+
+ self._diags = []
+
+ except Exception, e:
+ rospy.logerr('Caught exception processing diagnostic msg.\nEx: %s' % traceback.format_exc())
+
+
+
+if __name__ == '__main__':
+ try:
+ my_node = EtherCATTestMonitorNode()
+ except:
+ print 'Caught exception in test monitor node'
+ traceback.print_exc()
+ sys.exit(2)
Property changes on: pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py
___________________________________________________________________
Added: svn:executable
+ *
Modified: pkg/trunk/pr2/life_test/simple_test/fake_test.py
===================================================================
--- pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-06-26 03:55:29 UTC (rev 17752)
+++ pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-06-26 04:11:49 UTC (rev 17753)
@@ -32,6 +32,8 @@
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
+# Author: Kevin Watts
+
import roslib
roslib.load_manifest('life_test')
import wx
@@ -39,6 +41,7 @@
from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
from std_srvs.srv import *
+from mechanism_msgs.msg import MechanismState, JointState, ActuatorState
import os
import time
@@ -48,16 +51,24 @@
import threading
from wx import xrc
+import math
+
class FakeTestFrame(wx.Frame):
def __init__(self, parent):
wx.Frame.__init__(self, parent, wx.ID_ANY, 'Fake Test')
- self.diag_pub = rospy.Publisher('diagnostics', DiagnosticMessage)
+ self.diag_pub = rospy.Publisher('/diagnostics', DiagnosticMessage)
+ self.mech_pub = rospy.Publisher('mechanism_state', MechanismState)
+ self._mech_timer = wx.Timer(self, 2)
+ self.Bind(wx.EVT_TIMER, self.on_mech_timer, self._mech_timer)
+ self._last_mech_pub = rospy.get_time()
+ self._mech_timer.Start(50, True)
+
self._diag_timer = wx.Timer(self, 1)
self.Bind(wx.EVT_TIMER, self.on_timer, self._diag_timer)
self._last_publish = rospy.get_time()
- self._diag_timer.Start(250, True)
+ self._diag_timer.Start(500, True)
# Load XRC
xrc_path = os.path.join(roslib.packages.get_pkg_dir('life_test'), 'xrc/gui.xrc')
@@ -65,10 +76,78 @@
self._panel = xrc.XmlResource(xrc_path).LoadPanel(self, 'fake_panel')
self._pub_check_box = xrc.XRCCTRL(self._panel, 'publish_check_box')
self._level_choice = xrc.XRCCTRL(self._panel, 'level_choice')
+
+ self.enum_param_ctrl = xrc.XRCCTRL(self._panel, 'enum_param_ctrl')
+ self.range_param_ctrl = xrc.XRCCTRL(self._panel, 'range_param_ctrl')
+
+ self._cal_box = xrc.XRCCTRL(self._panel, 'calibration_box')
self._reset_srv = rospy.Service('reset_motors', Empty, self.on_reset)
self._halt_srv = rospy.Service('halt_motors', Empty, self.on_halt)
+
+ self._start_time = rospy.get_time()
+ def on_mech_timer(self, event = None):
+ self._mech_timer.Start(10, True)
+
+ # Joint state is a sine, period 1s, Amplitude 2,
+ trig_arg = rospy.get_time() - self._start_time
+
+ sine = math.sin(trig_arg)
+ cosine = math.cos(trig_arg)
+
+ # Stop joint at zero if not running
+ level = self._level_choice.GetSelection()
+ if level != 0:
+ sine = 0
+ cosine = 0
+
+ jnt_st = JointState()
+ jnt_st.name = 'fake_joint'
+ jnt_st.position = float(2 * sine)
+ jnt_st.velocity = float(2 * cosine)
+ jnt_st.applied_effort = float(-2 * sine)
+ jnt_st.commanded_effort = float(-2 * sine)
+ jnt_st.is_calibrated = 1
+
+ # Use same position as above, with 100:1 reduction -> Ampltitude 200
+ act_st = ActuatorState()
+ act_st.name = 'fake_motor'
+ act_st.device_id = 0
+ act_st.encoder_count = 200 * int(sine) + 1134
+ act_st.position = float(200 * sine)
+ act_st.timestamp = float(rospy.get_time())
+ act_st.encoder_velocity = float(200 * sine)
+ act_st.velocity = float(200 * cosine)
+
+ # Only one that makes a difference
+ act_st.calibration_reading = 14
+ if sine > 0.0 and self._cal_box.IsChecked():
+ act_st.calibration_reading = 13
+
+ act_st.calibration_rising_edge_valid = 1
+ act_st.calibration_falling_edge_valid = 1
+ act_st.last_calibration_rising_edge = float(0.0)
+ act_st.last_calibration_falling_edge = float(0.0)
+ act_st.is_enabled = 1
+ act_st.run_stop_hit = 0
+ act_st.last_requested_current = float(0.0)
+ act_st.last_commanded_current = float(0.0)
+ act_st.last_measured_current = float(0.0)
+ act_st.last_requested_effort = float(0.0)
+ act_st.last_commanded_effort = float(0.0)
+ act_st.last_measured_effort = float(0.0)
+ act_st.motor_voltage = float(0.0)
+ act_st.num_encoder_errors = 0
+
+ mech_st = MechanismState()
+ mech_st.time = rospy.get_time()
+ mech_st.actuator_states = [ act_st ]
+ mech_st.joint_states = [ jnt_st ]
+
+ self.mech_pub.publish(mech_st)
+
+
def on_halt(self, srv):
print 'Halting'
wx.CallAfter(self.set_level, 2)
@@ -79,21 +158,29 @@
return EmptyResponse()
def set_level(self, val):
- print 'Setting level'
self._level_choice.SetSelection(val)
+ def set_enum_ctrl(self):
+ enum_param = rospy.get_param('test_choice')
+ self.enum_param_ctrl.SetValue(enum_param)
+
+ def set_range_ctrl(self):
+ range_param = rospy.get_param('cycle_rate')
+ self.range_param_ctrl.SetValue(range_param)
+
def on_timer(self, event = None):
print 'Making message'
- self._diag_timer.Start(500, True)
+ self._diag_timer.Start(1000, True)
level_dict = { "OK": 0, "Warn": 1, "Error": 2 }
level = self._level_choice.GetSelection()
- # level_dict[self._level_choice.GetStringSelection()]
- print 'Level %s' % level
+
choice = self._level_choice.GetStringSelection()
- print 'Choice %s' % choice
+ self.set_enum_ctrl()
+ self.set_range_ctrl()
+
if self._pub_check_box.IsChecked():
self.publish_diag(level, str(choice))
@@ -105,15 +192,15 @@
stat.level = level
stat.name = 'EtherCAT Master' # So ghetto
- stat.message = choice #'OK'
+ stat.message = choice
self.diag_pub.publish(msg)
class FakeTestApp(wx.App):
def OnInit(self):
- rospy.init_node("fake_test")
+ rospy.init_node("fake_test_node")
self._frame = FakeTestFrame(None)
- self._frame.SetSize(wx.Size(200, 100))
+ self._frame.SetSize(wx.Size(224, 230))
self._frame.Layout()
self._frame.Centre()
self._frame.Show(True)
Added: pkg/trunk/pr2/life_test/simple_test/fake_trans.csv
===================================================================
--- pkg/trunk/pr2/life_test/simple_test/fake_trans.csv (rev 0)
+++ pkg/trunk/pr2/life_test/simple_test/fake_trans.csv 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1 @@
+fake_motor,fake_joint,0.0,0.1,0,1
\ No newline at end of file
Modified: pkg/trunk/pr2/life_test/simple_test/test.launch
===================================================================
--- pkg/trunk/pr2/life_test/simple_test/test.launch 2009-06-26 03:55:29 UTC (rev 17752)
+++ pkg/trunk/pr2/life_test/simple_test/test.launch 2009-06-26 04:11:49 UTC (rev 17753)
@@ -1,3 +1,5 @@
<launch>
<node pkg="life_test" type="fake_test.py" />
+
+ <node pkg="life_test" type="ethercat_test_monitor.py" args="$(find life_test)/simple_test/fake_trans.csv" />
</launch>
\ No newline at end of file
Modified: pkg/trunk/pr2/life_test/src/life_test/life_test.py
===================================================================
--- pkg/trunk/pr2/life_test/src/life_test/life_test.py 2009-06-26 03:55:29 UTC (rev 17752)
+++ pkg/trunk/pr2/life_test/src/life_test/life_test.py 2009-06-26 04:11:49 UTC (rev 17753)
@@ -38,20 +38,24 @@
roslib.load_manifest('life_test')
import sys, os, math, string
-from datetime import datetime
import csv
import traceback
-from time import sleep, mktime, strftime, localtime
+from time import sleep, strftime, localtime
import threading
from socket import gethostname
import wx
-import wx.aui
from wx import xrc
-import rospy, roslaunch
+import rospy
from std_srvs.srv import *
from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+
+# Stuff from life_test package
+from msg import TestStatus
+from test_param import TestParam, LifeTest
+from test_record import TestRecord
+
import runtime_monitor
from runtime_monitor.monitor_panel import MonitorPanel
@@ -61,138 +65,9 @@
from email.mime.base import MIMEBase
from email import Encoders
-
-class LifeTest:
- def __init__(self, short_serial, test_name, desc, cycle_rate, test_type, launch_file):
- self._short_serial = short_serial
- self._name = test_name
- self._desc = desc
- self._cycle_rate = cycle_rate
- self._launch_script = launch_file
- self._test_type = test_type
-
-class TestRecord:
- def __init__(self, test, serial):
- self._start_time = rospy.get_time()
- self._cum_seconds = 0
- self._last_update_time = rospy.get_time()
- self._was_running = False
- self._was_launched = False
- self._num_alerts = 0
- self._num_halts = 0
-
- self._rate = test._cycle_rate
- self._serial = serial
- self._test_name = test._name
-
- self._log = {}
- self._last_log_time = self._last_update_time
-
- csv_name = strftime("%m%d%Y_%H%M%S", localtime(self._start_time)) + '_' + str(self._serial) + '_' + self._test_name + '.csv'
- csv_name = csv_name.replace(' ', '_').replace('/', '__')
- self.log_file = os.path.join(roslib.packages.get_pkg_dir('life_test'), 'logs/%s' % csv_name)
-
+import wg_hardware_roslaunch.roslaunch_caller as roslaunch_caller
- log_csv = csv.writer(open(self.log_file, 'wb'))
- log_csv.writerow(['Time', 'Status',
- 'Elapsed (s)', 'Active (s)',
- 'Cycles', 'Cycle Rate', 'Notes'])
- def get_elapsed(self):
- elapsed = rospy.get_time() - self._start_time
- return elapsed
-
- def get_cum_time(self):
- return self._cum_seconds
-
- def get_duration_str(self, duration):
- hrs = max(math.floor(duration / 3600), 0)
- min = max(math.floor(duration / 6), 0) / 10 - hrs * 60
-
- return "%dhr, %.1fm" % (hrs, min)
-
- def get_active_str(self):
- return self.get_duration_str(self._cum_seconds)
-
- def get_elapsed_str(self):
- return self.get_duration_str(self.get_elapsed())
-
- def get_cycles(self):
- cycles = self._rate * self._cum_seconds
- return cycles
-
- def update(self, launched, running, stale, note):
- if running and not launched:
- rospy.logerr('Reported impossible state of running and not launched')
- return 0, ''
-
- if stale and running:
- rospy.logerr('Reported impossible state of running and stale')
- return 0, ''
-
- if self._was_running and running:
- self._cum_seconds = rospy.get_time() - self._last_update_time + self._cum_seconds
-
- alert = 0 # 0 - None, 1 - Notify, 2 - alert
- msg = ''
- state = 'Running'
-
- if launched and (not running) and stale:
- state = 'Halted, stale'
- elif launched and (not running):
- state = 'Halted'
- elif not launched:
- state = 'Stopped'
-
- if (not self._was_launched) and launched:
- alert = 1
- msg = "Test launched."
- elif self._was_launched and (not launched):
- alert = 1
- msg = "Test shut down."
-
- elif self._was_running and (not running):
- alert = 2
- if stale:
- msg = "Test has gone stale!"
- else:
- msg = "Test has stopped running!"
- elif (not self._was_running) and running:
- alert = 1
- msg = "Test has restarted and is running."
-
- self._num_halts += 1
-
- if alert:
- self._num_alerts += 1
-
- self._was_running = running
- self._was_launched = launched
- self._last_update_time = rospy.get_time()
-
- if alert or note != '' or (running and self._last_log_time - rospy.get_time() > 7200):
- self.write_csv_row(self._last_update_time, state, msg, note)
- self._log[rospy.get_time()] = msg + ' ' + note
- self._last_log_time = self._last_update_time
-
- return alert, msg
-
- def write_csv_row(self, update_time, state, msg, note):
- log_msg = msg + ' ' + note
- log_msg = log_msg.replace(',', ';')
-
- time_str = strftime("%m/%d/%Y %H:%M:%S", localtime(update_time))
-
- log_csv = csv.writer(open(self.log_file, 'ab'))
- log_csv.writerow([time_str, state,
- self.get_elapsed(), self.get_cum_time(),
- self.get_cycles(), self._rate,
- log_msg])
-
- def csv_filename(self):
- return self.log_file
-
-
class TestMonitorPanel(wx.Panel):
def __init__(self, parent, manager, test, serial):
wx.Panel.__init__(self, parent)
@@ -201,8 +76,7 @@
self._mutex = threading.Lock()
-
- self._diag_sub = None
+ self._status_sub = None
self._diags = []
# Set up test and loggers
@@ -250,7 +124,6 @@
self._user_submit.Bind(wx.EVT_BUTTON, self.on_user_entry)
self._done_time_ctrl = xrc.XRCCTRL(self._panel, 'done_time_ctrl')
- self._total_cycles_ctrl = xrc.XRCCTRL(self._panel, 'total_cycles_ctrl')
self._elapsed_time_ctrl = xrc.XRCCTRL(self._panel, 'elapsed_time_ctrl')
self._active_time_ctrl = xrc.XRCCTRL(self._panel, 'active_time_ctrl')
@@ -261,8 +134,7 @@
self._send_log_button = xrc.XRCCTRL(self._panel, 'send_test_log_button')
self._send_log_button.Bind(wx.EVT_BUTTON, self.on_send_test_log)
-
- # Add runtime to the pane...
+ # Add runtime to the panel...
self._notebook = xrc.XRCCTRL(self._panel, 'test_data_notebook')
wx.CallAfter(self.create_monitor)
@@ -270,8 +142,6 @@
self._sizer.Add(self._panel, 1, wx.EXPAND)
self.SetSizer(self._sizer)
self.Layout()
-
- self._test_team = [ "wa...@wi...", "sta...@wi..." ]
self._machine = None
self._current_log = {}
@@ -286,6 +156,7 @@
self._test_complete = False
# Timeout for etherCAT diagnostics
+ # Don't start it here, wait until test is launched
self.timer = wx.Timer(self)
self.Bind(wx.EVT_TIMER, self.on_timer, self.timer)
self.last_message_time = rospy.get_time()
@@ -312,18 +183,15 @@
def __del__(self):
# Somehow calling log function in destructor
- print 'Stopping launches'
self.stop_test()
- if self._diag_sub:
- print 'Unregistering from diagnostics'
- self._diag_sub.unregister()
+ if self._status_sub:
+ self._status_sub.unregister()
def is_launched(self):
return self._test_launcher is not None
def on_end_choice(self, event = None):
- #self._mutex.acquire()
choice = self._end_cond_type.GetStringSelection()
# Set test_duration_ctrl units also
@@ -336,8 +204,7 @@
self._test_duration_ctrl.SetValue(0)
active_time = self._record.get_cum_time()
- cycles = self._record.get_cycles()
-
+ # Should probably add cycles back in somehow
if choice == 'Hours':
hrs = math.ceil((active_time / 3600))
self._test_duration_ctrl.SetRange(hrs, 168) # Week
@@ -346,20 +213,14 @@
min = math.ceil((active_time / 60))
self._test_duration_ctrl.SetRange(min, 600) # 10 Hrs
self._test_duration_ctrl.SetValue(min + 10)
- elif choice == 'Cycles':
- cycle_val = cycles + math.ceil(self._test._cycle_rate * 300) # 5 min
- self._test_duration_ctrl.SetRange(cycles, 100000) # Long time
- self._test_duration_ctrl.SetValue(cycle_val)
else:
self._test_duration_ctrl.SetRange(0, 0) # Can't change limits
self._test_duration_ctrl.SetValue(0)
- #self._mutex.release()
-
def on_user_entry(self, event):
entry = self._user_log.GetValue()
msg = 'OPERATOR: ' + entry
- self.log(msg)
+ self.update_test_record(msg)
self._user_log.Clear()
self._user_log.SetFocus()
@@ -371,26 +232,28 @@
if name.find('@') < 0:
name = name + '@willowgarage.com'
- self.notify_operator(3, 'Test log requested by operator.', string.join(names, ','))
+ self.notify_operator(3, 'Log Requested.', string.join(names, ','))
def on_close(self, event):
- #self.stop_test()
- self.log('Closing down test.')
+ self.update_test_record('Closing down test.')
self.update_invent()
self.record_test_log()
- self.notify_operator(1, 'Test closing.')
+ self.notify_operator(1, 'Closing.')
self._manager.close_tab(self._serial)
def update_test_record(self, note = ''):
alert, msg = self._record.update(self.is_launched(), self._is_running, self._is_stale, note)
- if alert > 0:
- #self.log(msg)
- self._current_log[rospy.get_time()] = msg
- self._manager.log_test_entry(self._test._name, self._machine, msg)
-
- #self._log_ctrl.AppendText(
+
+ lst = [msg, note]
+ message = string.join(lst, ' ')
+
+ if alert > 0 or note != '':
+ self._current_log[rospy.get_time()] = message
+ self._manager.log_test_entry(self._test._name, self._machine, message)
self.display_logs()
+
+ if alert > 0:
self.notify_operator(alert, msg)
@@ -405,11 +268,8 @@
return duration * 60
if end_condition == 'Seconds':
return duration
- if end_condition == 'Cycles':
- return duration / self._test._cycle_rate
-
else: #if end_condition == 'Continuous':
- return 10**9 # Roughly 30 years
+ return 10**10 # Roughly 300 years
def calc_remaining(self):
total_sec = self.calc_run_time()
@@ -422,47 +282,36 @@
if rospy.get_time() - self._last_invent_time > self.invent_timeout and self.is_launched():
self.update_invent()
- #self.invent_timer.Start(self.invent_timeout * 500, True)
-
-
def update_invent(self):
- rospy.logerr('Updating invent')
-
- # Reset timer, last time
- #self.invent_timer.Start(self.invent_timeout * 500, True)
self._last_invent_time = rospy.get_time()
# Don't log anything if we haven't l...
[truncated message content] |
|
From: <is...@us...> - 2009-06-27 23:06:05
|
Revision: 17829
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17829&view=rev
Author: isucan
Date: 2009-06-27 23:06:04 +0000 (Sat, 27 Jun 2009)
Log Message:
-----------
more debug messages + bugfix in move_arm
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp
pkg/trunk/highlevel/move_arm/src/move_arm.cpp
pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
Modified: pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp
===================================================================
--- pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp 2009-06-27 22:30:32 UTC (rev 17828)
+++ pkg/trunk/highlevel/move_arm/src/arm_cmd_line.cpp 2009-06-27 23:06:04 UTC (rev 17829)
@@ -303,7 +303,7 @@
else
{
std::cout << "Moving to " << config << "..." << std::endl;
- if (move_arm.execute(goals[config], feedback, ros::Duration(10.0)) != robot_actions::SUCCESS)
+ if (move_arm.execute(goals[config], feedback, ros::Duration(allowed_time)) != robot_actions::SUCCESS)
std::cerr << "Failed achieving goal" << std::endl;
else
std::cout << "Success!" << std::endl;
Modified: pkg/trunk/highlevel/move_arm/src/move_arm.cpp
===================================================================
--- pkg/trunk/highlevel/move_arm/src/move_arm.cpp 2009-06-27 22:30:32 UTC (rev 17828)
+++ pkg/trunk/highlevel/move_arm/src/move_arm.cpp 2009-06-27 23:06:04 UTC (rev 17829)
@@ -183,6 +183,7 @@
int trajectoryId = -1;
bool approx = false;
ros::Duration eps(0.01);
+ ros::Duration epsLong(0.1);
while (true)
{
// if we have to stop, do so
@@ -210,7 +211,10 @@
if (clientPlan.call(req, res))
{
if (res.path.states.empty())
- ROS_WARN("Unable to plan path to desired goal");
+ {
+ ROS_WARN("Unable to plan path to desired goal");
+ epsLong.sleep();
+ }
else
{
if (res.unsafe)
@@ -250,12 +254,15 @@
if (isPreemptRequested() || !node_handle_.ok())
result = robot_actions::PREEMPTED;
+ // if preeemt was requested while we are planning, terminate
+ if (result != robot_actions::SUCCESS && feedback == pr2_robot_actions::MoveArmState::PLANNING)
+ break;
// stop the robot if we need to
if (feedback == pr2_robot_actions::MoveArmState::MOVING)
{
bool safe = planningMonitor_->isEnvironmentSafe();
- bool valid = planningMonitor_->isPathValid(currentPath_);
+ bool valid = planningMonitor_->isPathValid(currentPath_, true);
if (result == robot_actions::PREEMPTED || !safe || !valid)
{
if (result == robot_actions::PREEMPTED)
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-27 22:30:32 UTC (rev 17828)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-27 23:06:04 UTC (rev 17829)
@@ -78,7 +78,7 @@
bool isStateValidAtGoal(const planning_models::StateParams *state) const;
/** \brief Check if the path is valid */
- bool isPathValid(const motion_planning_msgs::KinematicPath &path) const;
+ bool isPathValid(const motion_planning_msgs::KinematicPath &path, bool verbose) const;
/** \brief Set the kinematic constraints the monitor should use when checking a path */
void setPathConstraints(const motion_planning_msgs::KinematicConstraints &kc);
@@ -104,7 +104,7 @@
bool transformJoint(const std::string &name, unsigned int index, std::vector<double> ¶ms, roslib::Header &header, const std::string& target) const;
/** \brief Check the path assuming it is in the frame of the model */
- bool isPathValidAux(const motion_planning_msgs::KinematicPath &path) const;
+ bool isPathValidAux(const motion_planning_msgs::KinematicPath &path, bool verbose) const;
motion_planning_msgs::KinematicConstraints kcPath_;
motion_planning_msgs::KinematicConstraints kcGoal_;
Modified: pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-27 22:30:32 UTC (rev 17828)
+++ pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-27 23:06:04 UTC (rev 17829)
@@ -258,21 +258,21 @@
}
-bool planning_environment::PlanningMonitor::isPathValid(const motion_planning_msgs::KinematicPath &path) const
+bool planning_environment::PlanningMonitor::isPathValid(const motion_planning_msgs::KinematicPath &path, bool verbose) const
{
if (path.header.frame_id != getFrameId())
{
motion_planning_msgs::KinematicPath pathT = path;
if (transformPathToFrame(pathT, getFrameId()))
- return isPathValidAux(pathT);
+ return isPathValidAux(pathT, verbose);
else
return false;
}
else
- return isPathValidAux(path);
+ return isPathValidAux(path, verbose);
}
-bool planning_environment::PlanningMonitor::isPathValidAux(const motion_planning_msgs::KinematicPath &path) const
+bool planning_environment::PlanningMonitor::isPathValidAux(const motion_planning_msgs::KinematicPath &path, bool verbose) const
{
boost::scoped_ptr<planning_models::StateParams> sp(getKinematicModel()->newStateParams());
@@ -339,10 +339,17 @@
// check for collision
valid = !getEnvironmentModel()->isCollision();
-
+
+ if (verbose && !valid)
+ ROS_INFO("isPathValid: State %d is in collision", i);
+
// check for validity
if (valid)
+ {
valid = ks.decide(sp->getParams());
+ if (verbose && !valid)
+ ROS_INFO("isPathValid: State %d does not satisfy constraints", i);
+ }
}
// if we got to the last state, we also check the goal constraints
@@ -351,6 +358,8 @@
ks.add(getKinematicModel(), kcGoal_.joint_constraint);
ks.add(getKinematicModel(), kcGoal_.pose_constraint);
valid = ks.decide(sp->getParams());
+ if (verbose && !valid)
+ ROS_INFO("isPathValid: Goal state does not satisfy constraints");
}
getKinematicModel()->unlock();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-27 23:49:02
|
Revision: 17831
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17831&view=rev
Author: isucan
Date: 2009-06-27 23:49:00 +0000 (Sat, 27 Jun 2009)
Log Message:
-----------
parameter updates for launch files
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/move_larm.launch
pkg/trunk/highlevel/move_arm/move_rarm.launch
pkg/trunk/motion_planning/ompl_planning/motion_planning.launch
pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
Modified: pkg/trunk/highlevel/move_arm/move_larm.launch
===================================================================
--- pkg/trunk/highlevel/move_arm/move_larm.launch 2009-06-27 23:26:53 UTC (rev 17830)
+++ pkg/trunk/highlevel/move_arm/move_larm.launch 2009-06-27 23:49:00 UTC (rev 17831)
@@ -15,5 +15,8 @@
<remap from="motion_plan" to="plan_kinematic_path" />
<param name="arm" type="string" value="left_arm" />
+ <param name="refresh_interval_collision_map" type="double" value="5.0" />
+ <param name="refresh_interval_kinematic_state" type="double" value="1.0" />
+
</node>
</launch>
Modified: pkg/trunk/highlevel/move_arm/move_rarm.launch
===================================================================
--- pkg/trunk/highlevel/move_arm/move_rarm.launch 2009-06-27 23:26:53 UTC (rev 17830)
+++ pkg/trunk/highlevel/move_arm/move_rarm.launch 2009-06-27 23:49:00 UTC (rev 17831)
@@ -15,5 +15,8 @@
<remap from="motion_plan" to="plan_kinematic_path" />
<param name="arm" type="string" value="right_arm" />
+ <param name="refresh_interval_collision_map" type="double" value="5.0" />
+ <param name="refresh_interval_kinematic_state" type="double" value="1.0" />
+
</node>
</launch>
Modified: pkg/trunk/motion_planning/ompl_planning/motion_planning.launch
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/motion_planning.launch 2009-06-27 23:26:53 UTC (rev 17830)
+++ pkg/trunk/motion_planning/ompl_planning/motion_planning.launch 2009-06-27 23:49:00 UTC (rev 17831)
@@ -4,8 +4,8 @@
<remap from="robot_description" to="robotdesc/pr2" />
<remap from="collision_map" to="collision_map_occ" />
<remap from="collision_map_update" to="collision_map_occ_update" />
- <param name="refresh_interval_collision_map" type="double" value="0.0" />
- <param name="refresh_interval_kinematic_state" type="double" value="0.0" />
+ <param name="refresh_interval_collision_map" type="double" value="5.0" />
+ <param name="refresh_interval_kinematic_state" type="double" value="1.0" />
<param name="verbose_collisions" type="bool" value="false" />
</node>
</launch>
Modified: pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-27 23:26:53 UTC (rev 17830)
+++ pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-27 23:49:00 UTC (rev 17831)
@@ -291,7 +291,10 @@
getEnvironmentModel()->lock();
getKinematicModel()->lock();
-
+
+ bool vlevel = getEnvironmentModel()->getVerbose();
+ getEnvironmentModel()->setVerbose(verbose);
+
// figure out the poses of the robot model
getKinematicModel()->computeTransforms(sp->getParams());
// update the collision space
@@ -362,6 +365,7 @@
ROS_INFO("isPathValid: Goal state does not satisfy constraints");
}
+ getEnvironmentModel()->setVerbose(vlevel);
getKinematicModel()->unlock();
getEnvironmentModel()->unlock();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-29 02:15:45
|
Revision: 17849
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17849&view=rev
Author: isucan
Date: 2009-06-29 01:48:17 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
launch files define static plane
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/move_larm.launch
pkg/trunk/highlevel/move_arm/move_rarm.launch
pkg/trunk/motion_planning/ompl_planning/motion_planning.launch
Modified: pkg/trunk/highlevel/move_arm/move_larm.launch
===================================================================
--- pkg/trunk/highlevel/move_arm/move_larm.launch 2009-06-29 01:42:11 UTC (rev 17848)
+++ pkg/trunk/highlevel/move_arm/move_larm.launch 2009-06-29 01:48:17 UTC (rev 17849)
@@ -17,6 +17,6 @@
<param name="arm" type="string" value="left_arm" />
<param name="refresh_interval_collision_map" type="double" value="5.0" />
<param name="refresh_interval_kinematic_state" type="double" value="1.0" />
-
+ <param name="bounding_planes" type="string" value="0 0 1 -0.01" />
</node>
</launch>
Modified: pkg/trunk/highlevel/move_arm/move_rarm.launch
===================================================================
--- pkg/trunk/highlevel/move_arm/move_rarm.launch 2009-06-29 01:42:11 UTC (rev 17848)
+++ pkg/trunk/highlevel/move_arm/move_rarm.launch 2009-06-29 01:48:17 UTC (rev 17849)
@@ -17,6 +17,6 @@
<param name="arm" type="string" value="right_arm" />
<param name="refresh_interval_collision_map" type="double" value="5.0" />
<param name="refresh_interval_kinematic_state" type="double" value="1.0" />
-
+ <param name="bounding_planes" type="string" value="0 0 1 -0.01" />
</node>
</launch>
Modified: pkg/trunk/motion_planning/ompl_planning/motion_planning.launch
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/motion_planning.launch 2009-06-29 01:42:11 UTC (rev 17848)
+++ pkg/trunk/motion_planning/ompl_planning/motion_planning.launch 2009-06-29 01:48:17 UTC (rev 17849)
@@ -6,6 +6,7 @@
<remap from="collision_map_update" to="collision_map_occ_update" />
<param name="refresh_interval_collision_map" type="double" value="5.0" />
<param name="refresh_interval_kinematic_state" type="double" value="1.0" />
+ <param name="bounding_planes" type="string" value="0 0 1 -0.01" />
<param name="verbose_collisions" type="bool" value="false" />
</node>
</launch>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-29 02:30:22
|
Revision: 17852
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17852&view=rev
Author: isucan
Date: 2009-06-29 02:30:18 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
small fix for self watch
Modified Paths:
--------------
pkg/trunk/util/self_watch/self_watch.cpp
pkg/trunk/world_models/collision_space/src/environmentODE.cpp
Modified: pkg/trunk/util/self_watch/self_watch.cpp
===================================================================
--- pkg/trunk/util/self_watch/self_watch.cpp 2009-06-29 02:07:12 UTC (rev 17851)
+++ pkg/trunk/util/self_watch/self_watch.cpp 2009-06-29 02:30:18 UTC (rev 17852)
@@ -68,6 +68,8 @@
m_envModels = boost::shared_ptr<planning_environment::CollisionModels>(new planning_environment::CollisionModels("robot_description", m_scaling, m_padding));
m_kmodel = m_envModels->getKinematicModel();
m_collisionSpace = m_envModels->getODECollisionModel();
+ m_collisionSpace->setSelfCollision(true);
+ m_collisionSpace->setVerbose(true);
// create a state that can be used to monitor the
// changes in the joints of the kinematic model
@@ -129,11 +131,11 @@
if (contacts.size() > 0)
{
- ROS_WARN("Collision found in %g seconds", (ros::WallTime::now() - start_time).toSec());
+ ROS_WARN("Collision found in %g seconds", (ros::WallTime::now() - start_time).toSec());
for (unsigned int i = 0 ; i < contacts.size() ; ++i)
{
- ROS_INFO("Collision between link '%s' and '%s'", contacts[i].link1->name.c_str(), contacts[i].link2 ? contacts[i].link2->name.c_str() : "ENVIRONMENT");
- ROS_INFO("Contact point (in robot frame): (%g, %g, %g)", contacts[i].pos.x(), contacts[i].pos.y(), contacts[i].pos.z());
+ ROS_INFO("Collision between link '%s' and '%s'", contacts[i].link1 ? contacts[i].link1->name.c_str() : "ENVIRONMENT", contacts[i].link2 ? contacts[i].link2->name.c_str() : "ENVIRONMENT");
+ ROS_INFO("Contact point (in frame %s): (%g, %g, %g)", m_stateMonitor->getFrameId().c_str(), contacts[i].pos.x(), contacts[i].pos.y(), contacts[i].pos.z());
ROS_INFO("Contact normal: (%g, %g, %g)", contacts[i].normal.x(), contacts[i].normal.y(), contacts[i].normal.z());
ROS_INFO("Contact depth: %g", contacts[i].depth);
}
Modified: pkg/trunk/world_models/collision_space/src/environmentODE.cpp
===================================================================
--- pkg/trunk/world_models/collision_space/src/environmentODE.cpp 2009-06-29 02:07:12 UTC (rev 17851)
+++ pkg/trunk/world_models/collision_space/src/environmentODE.cpp 2009-06-29 02:30:18 UTC (rev 17852)
@@ -332,8 +332,15 @@
EnvironmentModelODE::kGeom* kg1 = reinterpret_cast<EnvironmentModelODE::kGeom*>(dGeomGetData(o1));
EnvironmentModelODE::kGeom* kg2 = reinterpret_cast<EnvironmentModelODE::kGeom*>(dGeomGetData(o2));
if (kg1 && kg2)
+ {
if (cdata->selfCollisionTest->at(kg1->index)[kg2->index] == false)
return;
+ else
+ {
+ cdata->link1 = kg1->link;
+ cdata->link2 = kg2->link;
+ }
+ }
}
if (cdata->contacts)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-29 16:06:42
|
Revision: 17857
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17857&view=rev
Author: isucan
Date: 2009-06-29 16:06:40 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
added the kinematic:: prefix to known planners (we will be adding dynamic ones as well)
Modified Paths:
--------------
pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPModel.h
pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPModel.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPESTSetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKKPIECESetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKSBLSetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPKPIECESetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLBKPIECESetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLazyRRTSetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPRRTSetup.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPSBLSetup.cpp
pkg/trunk/stacks/pr2/pr2_defs/planning/planning.yaml
Modified: pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPModel.h
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPModel.h 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/include/kinematic_planning/RKPModel.h 2009-06-29 16:06:40 UTC (rev 17857)
@@ -76,14 +76,14 @@
protected:
- void addRRT(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
- void addLazyRRT(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
- void addEST(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
- void addSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
- void addIKSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
- void addKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
- void addLBKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
- void addIKKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ void add_kRRT(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ void add_kLazyRRT(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ void add_kEST(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ void add_kSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ void add_kIKSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ void add_kKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ void add_kLBKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
+ void add_kIKKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options);
};
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPModel.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPModel.cpp 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/RKPModel.cpp 2009-06-29 16:06:40 UTC (rev 17857)
@@ -43,35 +43,35 @@
for (unsigned int i = 0 ; i < cfgs.size() ; ++i)
{
std::string type = cfgs[i]->getParamString("type");
- if (type == "RRT")
- addRRT(cfgs[i]);
+ if (type == "kinematic::RRT")
+ add_kRRT(cfgs[i]);
else
- if (type == "LazyRRT")
- addLazyRRT(cfgs[i]);
+ if (type == "kinematic::LazyRRT")
+ add_kLazyRRT(cfgs[i]);
else
- if (type == "EST")
- addEST(cfgs[i]);
+ if (type == "kinematic::EST")
+ add_kEST(cfgs[i]);
else
- if (type == "SBL")
- addSBL(cfgs[i]);
+ if (type == "kinematic::SBL")
+ add_kSBL(cfgs[i]);
else
- if (type == "KPIECE")
- addKPIECE(cfgs[i]);
+ if (type == "kinematic::KPIECE")
+ add_kKPIECE(cfgs[i]);
else
- if (type == "LBKPIECE")
- addLBKPIECE(cfgs[i]);
+ if (type == "kinematic::LBKPIECE")
+ add_kLBKPIECE(cfgs[i]);
else
- if (type == "IKSBL")
- addIKSBL(cfgs[i]);
+ if (type == "kinematic::IKSBL")
+ add_kIKSBL(cfgs[i]);
else
- if (type == "IKKPIECE")
- addIKKPIECE(cfgs[i]);
+ if (type == "kinematic::IKKPIECE")
+ add_kIKKPIECE(cfgs[i]);
else
ROS_WARN("Unknown planner type: %s", type.c_str());
}
}
-void kinematic_planning::RKPModel::addRRT(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+void kinematic_planning::RKPModel::add_kRRT(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
{
RKPPlannerSetup *rrt = new RKPRRTSetup(dynamic_cast<RKPModelBase*>(this));
if (rrt->setup(options))
@@ -80,7 +80,7 @@
delete rrt;
}
-void kinematic_planning::RKPModel::addLazyRRT(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+void kinematic_planning::RKPModel::add_kLazyRRT(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
{
RKPPlannerSetup *rrt = new RKPLazyRRTSetup(dynamic_cast<RKPModelBase*>(this));
if (rrt->setup(options))
@@ -89,7 +89,7 @@
delete rrt;
}
-void kinematic_planning::RKPModel::addEST(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+void kinematic_planning::RKPModel::add_kEST(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
{
RKPPlannerSetup *est = new RKPESTSetup(dynamic_cast<RKPModelBase*>(this));
if (est->setup(options))
@@ -98,7 +98,7 @@
delete est;
}
-void kinematic_planning::RKPModel::addSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+void kinematic_planning::RKPModel::add_kSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
{
RKPPlannerSetup *sbl = new RKPSBLSetup(dynamic_cast<RKPModelBase*>(this));
if (sbl->setup(options))
@@ -107,7 +107,7 @@
delete sbl;
}
-void kinematic_planning::RKPModel::addIKSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+void kinematic_planning::RKPModel::add_kIKSBL(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
{
RKPPlannerSetup *sbl = new RKPIKSBLSetup(dynamic_cast<RKPModelBase*>(this));
if (sbl->setup(options))
@@ -116,7 +116,7 @@
delete sbl;
}
-void kinematic_planning::RKPModel::addKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+void kinematic_planning::RKPModel::add_kKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
{
RKPPlannerSetup *kpiece = new RKPKPIECESetup(dynamic_cast<RKPModelBase*>(this));
if (kpiece->setup(options))
@@ -125,7 +125,7 @@
delete kpiece;
}
-void kinematic_planning::RKPModel::addLBKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+void kinematic_planning::RKPModel::add_kLBKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
{
RKPPlannerSetup *kpiece = new RKPLBKPIECESetup(dynamic_cast<RKPModelBase*>(this));
if (kpiece->setup(options))
@@ -135,7 +135,7 @@
}
-void kinematic_planning::RKPModel::addIKKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
+void kinematic_planning::RKPModel::add_kIKKPIECE(boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> &options)
{
RKPPlannerSetup *kpiece = new RKPIKKPIECESetup(dynamic_cast<RKPModelBase*>(this));
if (kpiece->setup(options))
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPESTSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPESTSetup.cpp 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPESTSetup.cpp 2009-06-29 16:06:40 UTC (rev 17857)
@@ -39,7 +39,7 @@
kinematic_planning::RKPESTSetup::RKPESTSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "EST";
+ name = "kinematic::EST";
priority = 1;
}
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKKPIECESetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKKPIECESetup.cpp 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKKPIECESetup.cpp 2009-06-29 16:06:40 UTC (rev 17857)
@@ -38,7 +38,7 @@
kinematic_planning::RKPIKKPIECESetup::RKPIKKPIECESetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "IKKPIECE";
+ name = "kinematic::IKKPIECE";
priority = 5;
}
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKSBLSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKSBLSetup.cpp 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPIKSBLSetup.cpp 2009-06-29 16:06:40 UTC (rev 17857)
@@ -38,7 +38,7 @@
kinematic_planning::RKPIKSBLSetup::RKPIKSBLSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "IKSBL";
+ name = "kinematic::IKSBL";
priority = 4;
}
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPKPIECESetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPKPIECESetup.cpp 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPKPIECESetup.cpp 2009-06-29 16:06:40 UTC (rev 17857)
@@ -38,7 +38,7 @@
kinematic_planning::RKPKPIECESetup::RKPKPIECESetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "KPIECE";
+ name = "kinematic::KPIECE";
priority = 3;
}
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLBKPIECESetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLBKPIECESetup.cpp 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLBKPIECESetup.cpp 2009-06-29 16:06:40 UTC (rev 17857)
@@ -38,7 +38,7 @@
kinematic_planning::RKPLBKPIECESetup::RKPLBKPIECESetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "LBKPIECE";
+ name = "kinematic::LBKPIECE";
priority = 11;
}
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLazyRRTSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLazyRRTSetup.cpp 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPLazyRRTSetup.cpp 2009-06-29 16:06:40 UTC (rev 17857)
@@ -38,7 +38,7 @@
kinematic_planning::RKPLazyRRTSetup::RKPLazyRRTSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "LazyRRT";
+ name = "kinematic::LazyRRT";
priority = 2;
}
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPRRTSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPRRTSetup.cpp 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPRRTSetup.cpp 2009-06-29 16:06:40 UTC (rev 17857)
@@ -38,7 +38,7 @@
kinematic_planning::RKPRRTSetup::RKPRRTSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "RRT";
+ name = "kinematic::RRT";
priority = 2;
}
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPSBLSetup.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPSBLSetup.cpp 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/ompl_planner/RKPSBLSetup.cpp 2009-06-29 16:06:40 UTC (rev 17857)
@@ -38,7 +38,7 @@
kinematic_planning::RKPSBLSetup::RKPSBLSetup(RKPModelBase *m) : RKPPlannerSetup(m)
{
- name = "SBL";
+ name = "kinematic::SBL";
priority = 10;
}
Modified: pkg/trunk/stacks/pr2/pr2_defs/planning/planning.yaml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_defs/planning/planning.yaml 2009-06-29 16:00:27 UTC (rev 17856)
+++ pkg/trunk/stacks/pr2/pr2_defs/planning/planning.yaml 2009-06-29 16:06:40 UTC (rev 17857)
@@ -74,55 +74,55 @@
planner_configs:
RRTConfig1:
- type: RRT
+ type: kinematic::RRT
range: 0.75
LazyRRTConfig1:
- type: LazyRRT
+ type: kinematic::LazyRRT
range: 0.75
SBLConfig1:
- type: SBL
+ type: kinematic::SBL
projection: 0 1
celldim: 1 1
range: 0.5
KPIECEConfig1:
- type: KPIECE
+ type: kinematic::KPIECE
projection: 0 1
celldim: 1 1
range: 0.5
RRTConfig2:
- type: RRT
+ type: kinematic::RRT
range: 0.75
SBLConfig2:
- type: SBL
+ type: kinematic::SBL
projection: 5 6
celldim: 0.1 0.1
KPIECEConfig2l:
- type: KPIECE
+ type: kinematic::KPIECE
projection: link l_wrist_roll_link
celldim: 0.1 0.1 0.1
KPIECEConfig2r:
- type: KPIECE
+ type: kinematic::KPIECE
projection: link r_wrist_roll_link
celldim: 0.1 0.1 0.1
LBKPIECEConfig1:
- type: LBKPIECE
+ type: kinematic::LBKPIECE
projection: 5 6
celldim: 0.1 0.1
LBKPIECEConfig2r:
- type: LBKPIECE
+ type: kinematic::LBKPIECE
projection: link r_wrist_roll_link
celldim: 0.1 0.1 0.1
LBKPIECEConfig2l:
- type: LBKPIECE
+ type: kinematic::LBKPIECE
projection: link l_wrist_roll_link
celldim: 0.1 0.1 0.1
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2009-06-29 20:52:37
|
Revision: 17881
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17881&view=rev
Author: hsujohnhsu
Date: 2009-06-29 20:51:09 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
update to latest gazebo trunk - factory is now a default iface.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/xml2factory.cpp
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/balcony.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty_10000hz.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty_100hz.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/floorobj.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/obstacle.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple_erratic.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple_office.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tablegrasp.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tables.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_camera.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_scan.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_slide.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/teststereo.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/wg.world
pkg/trunk/stacks/simulators/gazebo/Makefile
pkg/trunk/stacks/simulators/gazebo/gazebo_new_patch.diff
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp 2009-06-29 20:51:09 UTC (rev 17881)
@@ -123,7 +123,7 @@
/// Open the Factory interface
try
{
- factoryIface->Open(client, "factory_model::factory_iface");
+ factoryIface->Open(client, "default");
}
catch (gazebo::GazeboError e)
{
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/xml2factory.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/xml2factory.cpp 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/xml2factory.cpp 2009-06-29 20:51:09 UTC (rev 17881)
@@ -117,7 +117,7 @@
/// Open the Factory interface
try
{
- factoryIface->Open(client, "factory_model::factory_iface");
+ factoryIface->Open(client, "default");
}
catch (gazebo::GazeboError e)
{
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/balcony.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/balcony.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/balcony.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -342,19 +342,6 @@
</model:physical>
-->
-
-
-
-
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!-- White Directional light -->
<model:renderable name="directional_white">
<light>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -84,15 +84,6 @@
</body:plane>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!--
<model:physical name="walls">
<include embedded="false">
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty_10000hz.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty_10000hz.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty_10000hz.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -78,15 +78,6 @@
</body:plane>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!--
<model:physical name="walls">
<include embedded="false">
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty_100hz.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty_100hz.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/empty_100hz.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -91,15 +91,6 @@
</body:plane>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!-- White Directional light -->
<!--
<model:renderable name="directional_white">
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/floorobj.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/floorobj.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/floorobj.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -299,17 +299,6 @@
</body:box>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
-
-
<!-- White Directional light -->
<!--
<model:renderable name="directional_white">
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/obstacle.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/obstacle.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/obstacle.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -324,18 +324,6 @@
</body:box>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
-
-
-
<!-- White Directional light -->
<!--
<model:renderable name="directional_white">
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -242,15 +242,6 @@
</body:box>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!-- White Directional light -->
<model:renderable name="point_white">
<xyz>0.0 0.0 3</xyz>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple_erratic.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple_erratic.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple_erratic.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -241,15 +241,6 @@
</body:box>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!-- White Directional light -->
<model:renderable name="directional_white">
<light>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple_office.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple_office.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/simple_office.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -185,19 +185,6 @@
</body:box>
</model:physical>
-
-
-
-
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!-- White Directional light -->
<model:renderable name="directional_white">
<light>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tablegrasp.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tablegrasp.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tablegrasp.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -286,15 +286,6 @@
</body:box>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!-- White Directional light -->
<!--
<model:renderable name="directional_white">
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tables.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tables.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tables.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -129,15 +129,6 @@
</include>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!-- White Directional light -->
<!--
<model:renderable name="directional_white">
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_camera.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_camera.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_camera.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -192,13 +192,4 @@
</light>
</model:renderable>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
</gazebo:world>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_scan.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_scan.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_scan.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -190,13 +190,4 @@
</light>
</model:renderable>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
</gazebo:world>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_slide.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_slide.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/test_slide.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -269,12 +269,4 @@
</model:renderable>
-->
- <model:empty name="factory_model">
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
</gazebo:world>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/teststereo.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/teststereo.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/teststereo.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -185,13 +185,4 @@
</light>
</model:renderable>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
</gazebo:world>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/wg.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/wg.world 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/wg.world 2009-06-29 20:51:09 UTC (rev 17881)
@@ -133,15 +133,6 @@
</include>
</model:physical>
- <model:empty name="factory_model">
- <model_thread>false</model_thread>
- <controller:factory name="factory_controller">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:factory name="factory_iface"/>
- </controller:factory>
- </model:empty>
-
<!-- White Directional light -->
<model:renderable name="point_white">
<xyz>0.0 0.0 50</xyz>
Modified: pkg/trunk/stacks/simulators/gazebo/Makefile
===================================================================
--- pkg/trunk/stacks/simulators/gazebo/Makefile 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/stacks/simulators/gazebo/Makefile 2009-06-29 20:51:09 UTC (rev 17881)
@@ -5,7 +5,7 @@
SVN_DIR = gazebo-svn
SVN_URL = https://playerstage.svn.sourceforge.net/svnroot/playerstage/code/gazebo/trunk
-SVN_REVISION = -r 7891
+SVN_REVISION = -r 7929
SVN_PATCH = gazebo_new_patch.diff
include $(shell rospack find mk)/svn_checkout.mk
Modified: pkg/trunk/stacks/simulators/gazebo/gazebo_new_patch.diff
===================================================================
--- pkg/trunk/stacks/simulators/gazebo/gazebo_new_patch.diff 2009-06-29 20:51:03 UTC (rev 17880)
+++ pkg/trunk/stacks/simulators/gazebo/gazebo_new_patch.diff 2009-06-29 20:51:09 UTC (rev 17881)
@@ -1,8 +1,8 @@
Index: server/physics/Body.hh
===================================================================
---- server/physics/Body.hh (revision 7891)
+--- server/physics/Body.hh (revision 7929)
+++ server/physics/Body.hh (working copy)
-@@ -259,6 +259,8 @@
+@@ -268,6 +268,8 @@
protected: ParamT<double> *iyzP;
protected: bool customMassMatrix;
protected: double cx,cy,cz,bodyMass,ixx,iyy,izz,ixy,ixz,iyz;
@@ -13,9 +13,9 @@
/// \}
Index: server/physics/Geom.cc
===================================================================
---- server/physics/Geom.cc (revision 7891)
+--- server/physics/Geom.cc (revision 7929)
+++ server/physics/Geom.cc (working copy)
-@@ -250,7 +250,7 @@
+@@ -249,7 +249,7 @@
if (this->placeable && !this->IsStatic())
{
@@ -26,7 +26,7 @@
dGeomTransformSetGeom( this->transId, this->geomId );
Index: server/physics/Body.cc
===================================================================
---- server/physics/Body.cc (revision 7891)
+--- server/physics/Body.cc (revision 7929)
+++ server/physics/Body.cc (working copy)
@@ -242,6 +242,10 @@
}
@@ -41,7 +41,7 @@
Index: worlds/bandit.world
===================================================================
---- worlds/bandit.world (revision 7891)
+--- worlds/bandit.world (revision 7929)
+++ worlds/bandit.world (working copy)
@@ -16,7 +16,7 @@
<verbosity>5</verbosity>
@@ -61,42 +61,3 @@
<static>false</static>
<attach>
-Index: worlds/test_stacks_with_rays.world
-===================================================================
---- worlds/test_stacks_with_rays.world (revision 7891)
-+++ worlds/test_stacks_with_rays.world (working copy)
-@@ -28,7 +28,7 @@
- <cfm>0.0000000001</cfm>
- <erp>0.2</erp>
- <quickStep>true</quickStep>
-- <quickStepIters>10</quickStepIters>
-+ <quickStepIters>100</quickStepIters>
- <quickStepW>1.3</quickStepW>
- </physics:ode>
-
-Index: worlds/test_stacks.world
-===================================================================
---- worlds/test_stacks.world (revision 7891)
-+++ worlds/test_stacks.world (working copy)
-@@ -28,7 +28,7 @@
- <cfm>0.0000000001</cfm>
- <erp>0.1</erp>
- <quickStep>true</quickStep>
-- <quickStepIters>30</quickStepIters>
-+ <quickStepIters>20</quickStepIters>
- <quickStepW>1.3</quickStepW>
- </physics:ode>
-
-Index: CMakeLists.txt
-===================================================================
---- CMakeLists.txt (revision 7891)
-+++ CMakeLists.txt (working copy)
-@@ -30,7 +30,7 @@
- SET (gazebocontroller_sources_desc "List of controller sources"
- CACHE INTERNAL "Gazebo controller sources list description" FORCE)
-
--SET (OGRE_VERSION 1.6.2 CACHE INTERNAL "Ogre version requirement" FORCE)
-+SET (OGRE_VERSION 1.6.1 CACHE INTERNAL "Ogre version requirement" FORCE)
-
- SET (FREEIMAGE_MAJOR_VERSION 3 CACHE INTERNAL "FreeImage major version requirement" FORCE)
- SET (FREEIMAGE_MINOR_VERSION 10 CACHE INTERNAL "FreeImage minor version requirement" FORCE)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ei...@us...> - 2009-06-29 21:31:24
|
Revision: 17895
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17895&view=rev
Author: eitanme
Date: 2009-06-29 21:30:21 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
Fixing a spelling error with one of the Cosmap2DROS parameters. Also, adding documentation for the costmap_2d_tutorials package.
Modified Paths:
--------------
pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml
pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml
pkg/trunk/demos/door_demos/launch/move_base_door.launch
pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml
pkg/trunk/highlevel/move_base_stage/config/costmap_common_params.yaml
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch
pkg/trunk/nav/base_local_planner/mainpage.dox
pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap_params.yaml
pkg/trunk/nav/nav_apps/costmap_2d_tutorials/mainpage.dox
pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/observation_buffer.h
pkg/trunk/stacks/world_models/costmap_2d/launch_costmap_2d_ros.xml
pkg/trunk/stacks/world_models/costmap_2d/mainpage.dox
pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp
Modified: pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/demos/2dnav_erratic/config/costmap_common_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -17,4 +17,4 @@
lethal_cost_threshold: 100
observation_topics: scan
scan: {sensor_frame: frame_from_message, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
+ observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
Modified: pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml
===================================================================
--- pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/demos/2dnav_pr2/config/costmap_common_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -19,14 +19,14 @@
observation_topics: base_scan_marking base_scan tilt_scan ground_object_cloud
base_scan_marking: {sensor_frame: base_laser, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstacle_height: 2.0}
+ observation_persistence: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstacle_height: 2.0}
base_scan: {sensor_frame: base_laser, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: false, clearing: true, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
+ observation_persistence: 0.0, marking: false, clearing: true, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
tilt_scan: {sensor_frame: laser_tilt_link, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.2, marking: false, clearing: true, min_obstacle_height: -20.00, max_obstacle_height: 40.0}
+ observation_persistence: 0.2, marking: false, clearing: true, min_obstacle_height: -20.00, max_obstacle_height: 40.0}
ground_object_cloud: {sensor_frame: laser_tilt_link, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 3.0, marking: true, clearing: false, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
+ observation_persistence: 3.0, marking: true, clearing: false, min_obstacle_height: -0.10, max_obstacle_height: 2.0}
# END VOXEL STUFF
Modified: pkg/trunk/demos/door_demos/launch/move_base_door.launch
===================================================================
--- pkg/trunk/demos/door_demos/launch/move_base_door.launch 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/demos/door_demos/launch/move_base_door.launch 2009-06-29 21:30:21 UTC (rev 17895)
@@ -35,21 +35,21 @@
<param name="costmap/observation_topics" value="base_scan base_scan_marking" />
<param name="costmap/base_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/base_scan/observation_persistance" value="0.0" />
+ <param name="costmap/base_scan/observation_persistence" value="0.0" />
<param name="costmap/base_scan/expected_update_rate" value="0.2" />
<param name="costmap/base_scan/data_type" value="LaserScan" />
<param name="costmap/base_scan/clearing" value="true" />
<param name="costmap/base_scan/marking" value="false" />
<param name="costmap/base_scan_marking/sensor_frame" value="frame_from_message" />
- <param name="costmap/base_scan_marking/observation_persistance" value="0.0" />
+ <param name="costmap/base_scan_marking/observation_persistence" value="0.0" />
<param name="costmap/base_scan_marking/expected_update_rate" value="0.2" />
<param name="costmap/base_scan_marking/data_type" value="PointCloud" />
<param name="costmap/base_scan_marking/clearing" value="false" />
<param name="costmap/base_scan_marking/marking" value="true" />
<param name="costmap/tilt_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/tilt_scan/observation_persistance" value="0.0" />
+ <param name="costmap/tilt_scan/observation_persistence" value="0.0" />
<param name="costmap/tilt_scan/expected_update_rate" value="0.2" />
<param name="costmap/tilt_scan/data_type" value="LaserScan" />
<param name="costmap/tilt_scan/clearing" value="true" />
Modified: pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml
===================================================================
--- pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/demos/erratic_gazebo/costmap_common_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -12,7 +12,7 @@
observation_topics: base_scan_marking base_scan
base_scan_marking: {sensor_frame: base_laser, data_type: PointCloud, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstalce_height: 2.0}
+ observation_persistence: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstalce_height: 2.0}
base_scan: {sensor_frame: base_laser, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: false, clearing: true, min_obstacle_height: 0.08, max_obstalce_height: 2.0}
+ observation_persistence: 0.0, marking: false, clearing: true, min_obstacle_height: 0.08, max_obstalce_height: 2.0}
Modified: pkg/trunk/highlevel/move_base_stage/config/costmap_common_params.yaml
===================================================================
--- pkg/trunk/highlevel/move_base_stage/config/costmap_common_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/highlevel/move_base_stage/config/costmap_common_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -17,4 +17,4 @@
lethal_cost_threshold: 100
observation_topics: base_scan
base_scan: {sensor_frame: frame_from_message, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
+ observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
Modified: pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/sbpl_door_action_planner.launch 2009-06-29 21:30:21 UTC (rev 17895)
@@ -18,7 +18,7 @@
<param name="costmap/observation_topics" value="base_scan" />
<param name="costmap/base_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/base_scan/observation_persistance" value="0.0" />
+ <param name="costmap/base_scan/observation_persistence" value="0.0" />
<param name="costmap/base_scan/expected_update_rate" value="0.2" />
<param name="costmap/base_scan/data_type" value="LaserScan" />
<param name="costmap/base_scan/clearing" value="true" />
Modified: pkg/trunk/nav/base_local_planner/mainpage.dox
===================================================================
--- pkg/trunk/nav/base_local_planner/mainpage.dox 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/nav/base_local_planner/mainpage.dox 2009-06-29 21:30:21 UTC (rev 17895)
@@ -4,10 +4,25 @@
@htmlinclude manifest.html
@section summary Summary
-Write a summary here
+This package provides an implementation of a local planner for a mobile robot.
+The planner uses either the Trajectory Rollout or Dynamic Window Approach to povide safe local naivagtion
+commands to the base.
-@subsection example Example
-An example of a subsection
+@section usage Usage
+There are two main ways to use this package. The first is to create a TrajectoryPlanner object and manage it
+yourself. The second, and encouraged method, is to use a ROS wrapper (base_local_planner::TrajectoryPlannerROS)
+that manages the underlying TrajectoryPlanner for you and adheres to the ROS nav_robot_actions::BaseLocalPlanner
+interface. See below for an example of base_local_planner::TrajectoryPlannerROS construction.
+@subsection construction TrajectoryPlannerROS Construction
+To construct a base_local_planner::TrajectoryPlannerROS object, pass it a name, a reference to a
+costmap_2D::Costmap2DROS, and a reference to a tf::TransformListener.
+@verbatim
+#include "ros/ros.h"
+#include "tf/transform_listener.h"
+#include "costmap_2d/costmap_2d_ros.h"
+#include "base_local_planner/trajectory_planner_ros.h"
+
+
*/
Modified: pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap_params.yaml
===================================================================
--- pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap_params.yaml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/nav/nav_apps/costmap_2d_tutorials/launch_example/costmap_params.yaml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -1,24 +1,116 @@
+#First, we need to set frame_ids for the costmap. The global_frame refers to the
+#operating frame of the costmap, and the robot_base_frame refers to the frame of
+#the base link of the robot. Here, we'll set them to "map" and "base_link"
+#respectively.
global_frame: /map
robot_base_frame: base_link
+
+#Next, we'll set the some frequency parameters for the costmap. The first is the
+#update_frequency. This controls how often sensor data from the world should bet
+#put into the costmap. The higher this parameter is set, the more current the
+#costmap's world will be. However, keep in mind that with more frequent updates
+#also comes more CPU usage. We'll use a value of 5Hz as our update rate. The
+#second frequency parameter that we can set on the costmap is how often to
+#publish visualization data. We'll set that to 2Hz.
update_frequency: 5.0
publish_frequency: 2.0
+
+#The transform_tolerance parameter is used to define the latency we are willing to accept
+#on transforms from the robot_base_frame to the global_frame of the costmap. We'll set this
+#to 0.3 seconds.
transform_tolerance: 0.3
+
+#The obstacle_range parameter defines at what distance we will start to use sensor data
+#to place obstacles into the costmap. We'll set it to 2.5 meters here which means that we'll
+#put in sensor hits that are up to 2.5 meters away from us.
obstacle_range: 2.5
+
+#The max_obstacle_height parameter defines the maximum height of an obstacle for the costmap.
+#We'll set it to 2.0 meters for our robot.
max_obstacle_height: 2.0
+
+#The raytrace_range parameter sets how far we'll look out from the robot when raytracing freeespace.
+#Here we'll set it to be 3.0 meters. Its suggested to set this parameter to be equal or greater to
+#the obstacle_range parameter above to ensure that freespace is cleared out correctly.
raytrace_range: 3.0
+
+#The following three parameters are used for inflation of obstacles within the costmap. The inscribed
+#radius should be set to the radius of the inner circle of the robot. The circumscribed radius should
+#be set to the radius of the outer circle of the robot. The inflation radius should be set to the maximum
+#distance from obstacles at which cost information is desired.
inscribed_radius: 0.325
circumscribed_radius: 0.46
inflation_radius: 0.55
+#The observation_topics list allows users of a Costmap2DROS object to specify what topics should be used
+#in conjunction with the underlying Costmap2D object. Topics should be listed here, separated by spaces and
+#should be configured in their individual namespaces as shown below. Each topic in this list will be subscribed
+#to and managed by the Costmap2DROS object subject to its configuration settings.
observation_topics: base_scan
-base_scan: {sensor_frame: frame_from_message, data_type: LaserScan, expected_update_rate: 0.2,
- observation_persistance: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}
+#This is an example of topic configuration for the base_scan topic listed in the observation_topics list above.
+#Notice that the base scan receives its own namespace to read its configuration from.
+base_scan:
+#The sensor_frame parameter specifies what frame the origin of the sensor is
+#assumed to be in. The special value "frame_from_message" infers the origin
+#frame from the frame_id sent in each message over the base_scan topic. Any
+#other string will override the frame_id sent in the message.
+ sensor_frame: frame_from_message
+
+#The data_type parameter specifies what message type to expect for the topic. The
+#two supported message types at this point are LaserScan and PointCloud.
+ data_type: LaserScan
+
+#The expected_update_rate parameter specifies the delay between messages that the Costmap2DROS
+#object will tolerate. For example, we expect that the base_scan should come in at 20Hz, which is
+#0.05 seconds between messages. However, we are willing to tolerate some jitter and want
+#to be warned when the time between messages exceeds 0.2 seconds.
+ expected_update_rate: 0.2
+
+#The observation_persistence parameter controls how long a message/observation from the topic persists
+#in its associated observation buffer. In this case, we'll set the persistence to 0.0 seconds meaning
+#we'll only keep the latest scan. This is fine for the base_scan because it is a planar laser that updates
+#at 20Hz. However, consider the case where we have an actuated sensor, such as a tilting laser. In that
+#case, we would set the observation_persistence to be equal to the tilting period. So, if the laser takes
+#2 seconds to do a full sweep of the world, we'll want to set the observation_persistence parameter to 2
+#seconds to make sure that we keep scans for that amount of time.
+ observation_persistence: 0.0
+
+#The marking and clearing parameters specify what functions the topic should be used for. If marking is set
+#to true, observations from the topic will be put into the costmap as obstacles. If marking is set to
+#false, observations from the topic won't be put into the costmap as obstacles. If clearing is set to true,
+#observations from the topic will be used to clear out freespace in the costmap. If clearing is set to false,
+#observations from the topic won't be used to clear out freespace. In the case of the base_scan, we want to
+#both put obstacles in and clear obstacles from the costmap so we'll set both clearing and marking to be true.
+ marking: true
+ clearing: true
+
+#The max_obstacle_height parameter specifies the maximum height reading from a sensor to be considered when
+#either clearing or marking. The min_obstacle_height parameter specifies the minimum height reading from a
+#sensor to be considered when clearing or marking. The base_scan corresponds to a planar laser sensor, so it
+#doesn't matter what we set these values to as long as the actual height of the laser falls in-between them.
+ max_obstacle_height: 0.4
+ min_obstacle_height: 0.08
+
+#This parameter controls whether or not the Costmap2DROS object should initialize itself from the static map.
+#If this parameter is set to true, the Costmap2DROS object will make a service call to the map_server and
+#initialize itself based on the map returned. If the static_map parameter is set to false, the Costmap2DROS
+#object will be initialized only with the data that it receives from its sensors. Since we want to demonstrate
+#creating costmaps of arbitrary sizes, we'll set static_map to false here.
static_map: false
+
+#When the rolling_window parameter is set to true, the Costmap2DROS object will always maintain a map that is
+#centered around the current position of the robot. As the robot moves in the world, so too will the costmap.
+#This means that the edges of the costmap will be clipped as the robot moves. If this parameter is not set, the
+#map will stay fixed at its original origin. If the robot moves off the map in this situation, the costmap will
+#not move with it. All queries to regions outside of the costmap will return errors.
rolling_window: true
+
+#The width and height parameters set the width and height of the costmap in meters. To keep a map of 10 meters
+#by 10 meters with the robot at the center, we'll set the values accordingly.
width: 10.0
height: 10.0
-resolution: 0.05
+resolution: 0.025
map_type: voxel
origin_z: 0.0
Modified: pkg/trunk/nav/nav_apps/costmap_2d_tutorials/mainpage.dox
===================================================================
--- pkg/trunk/nav/nav_apps/costmap_2d_tutorials/mainpage.dox 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/nav/nav_apps/costmap_2d_tutorials/mainpage.dox 2009-06-29 21:30:21 UTC (rev 17895)
@@ -2,8 +2,6 @@
\mainpage
\htmlinclude manifest.html
-\b costmap_2d_tutorials is ...
-
<!--
In addition to providing an overview of your package,
this is the section where the specification and design/architecture
@@ -12,9 +10,30 @@
You can then link to this documentation page from the Wiki.
-->
+\b costmap_2d_tutorials provides example code for the costmap_2d package.
+Specifically, it details the construction of a Costmap2DROS object and its use.
-\section codeapi Code API
+\section overview Overview
+There are two main ways to use a costmap_2d::Costmap2DROS object. The first is to create a costmap::Costmap2D
+object and manage updating it yourself. The second, and encouraged method, is
+to use a ROS wrapper (costmap_2d::Costmap2DROS) for the costmap that manages the map for
+you, but allows you to get a copy of the underlying costmap_2d::Costmap2D object at any time.
+See below for an example of costmap_2d::Costmap2DROS construction and configuration.
+\section construction Costmap2DROS Construction
+Constructing a costmap_2d::Costmap2DROS object is a simple as passing in a name and a reference to a tf::TransformListener.
+All the configuration of the costmap_2d::Costmap2DROS is handled by setting parameters on the parameter sever.
+\dontinclude src/costmap_test.cpp
+\skip main
+\until }
+
+\section configuration Costmap2DROS Configuration
+Each costmap_2d::Costmap2DROS object can be configured via the parameter server.
+Below is an example configuration of a simple costmap that subscribes to the "base_laser"
+sensor.
+
+\include launch_example/costmap_params.yaml
+
<!--
Provide links to specific auto-generated API documentation within your
package that is of particular interest to a reader. Doxygen will
@@ -116,4 +135,4 @@
END: Command-Line Tools Section -->
-*/
\ No newline at end of file
+*/
Modified: pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/observation_buffer.h
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/observation_buffer.h 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/observation_buffer.h 2009-06-29 21:30:21 UTC (rev 17895)
@@ -58,7 +58,7 @@
/**
* @brief Constructs an observation buffer
* @param topic_name The topic of the observations, used as an identifier for error and warning messages
- * @param observation_keep_time Defines the persistance of observations in seconds, 0 means only keep the latest
+ * @param observation_keep_time Defines the persistence of observations in seconds, 0 means only keep the latest
* @param expected_update_rate How often this buffer is expected to be updated, 0 means there is no limit
* @param min_obstacle_height The minimum height of a hitpoint to be considered legal
* @param max_obstacle_height The minimum height of a hitpoint to be considered legal
Modified: pkg/trunk/stacks/world_models/costmap_2d/launch_costmap_2d_ros.xml
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/launch_costmap_2d_ros.xml 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/stacks/world_models/costmap_2d/launch_costmap_2d_ros.xml 2009-06-29 21:30:21 UTC (rev 17895)
@@ -30,13 +30,13 @@
<param name="costmap/observation_topics" value="tilt_scan" />
<param name="costmap/base_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/base_scan/observation_persistance" value="0.0" />
+ <param name="costmap/base_scan/observation_persistence" value="0.0" />
<param name="costmap/base_scan/expected_update_rate" value="0.2" />
<param name="costmap/base_scan/data_type" value="LaserScan" />
<param name="costmap/base_scan/clearing" value="true" />
<param name="costmap/tilt_scan/sensor_frame" value="frame_from_message" />
- <param name="costmap/tilt_scan/observation_persistance" value="10.0" />
+ <param name="costmap/tilt_scan/observation_persistence" value="10.0" />
<param name="costmap/tilt_scan/expected_update_rate" value="0.2" />
<param name="costmap/tilt_scan/data_type" value="LaserScan" />
<param name="costmap/tilt_scan/clearing" value="true" />
Modified: pkg/trunk/stacks/world_models/costmap_2d/mainpage.dox
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/mainpage.dox 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/stacks/world_models/costmap_2d/mainpage.dox 2009-06-29 21:30:21 UTC (rev 17895)
@@ -27,7 +27,7 @@
//set parameters before construction of the Costmap2DROS object... we'll use the base laser to add data to this costmap
ros_node_.setParam("~costmap/observation_topics", "base_scan");
- ros_node_.setParam("~costmap/base_scan/observation_persistance", 0.0);
+ ros_node_.setParam("~costmap/base_scan/observation_persistence", 0.0);
ros_node_.setParam("~costmap/base_scan/expected_update_rate", 0.2);
ros_node_.setParam("~costmap/base_scan/data_type", "LaserScan");
ros_node_.setParam("~costmap/base_scan/clearing", "true");
@@ -91,7 +91,7 @@
<ul>
<li><b>~topic_name/sensor_frame</b>, <i>string</i> <br>The frame of the origin of the sensor. Set to "frame_from_message" to attempt to read the frame from sensor data.</li>
<br><br>
- <li><b>~topic_name/observation_persistance</b>, <i>double</i> <br>How long to keep each sensor reading in seconds. A value of 0.0 will only keep the most recent reading.</li>
+ <li><b>~topic_name/observation_persistence</b>, <i>double</i> <br>How long to keep each sensor reading in seconds. A value of 0.0 will only keep the most recent reading.</li>
<br><br>
<li><b>~topic_name/expected_update_rate</b>, <i>double</i> <br>How often to expect a reading from a sensor in secongs. A value of 0.0 will allow infinite time between readings.</li>
<br><br>
Modified: pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-06-29 21:28:40 UTC (rev 17894)
+++ pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-06-29 21:30:21 UTC (rev 17895)
@@ -87,7 +87,7 @@
double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
std::string sensor_frame, data_type;
ros_node_.param("~" + topic + "/sensor_frame", sensor_frame, std::string("frame_from_message"));
- ros_node_.param("~" + topic + "/observation_persistance", observation_keep_time, 0.0);
+ ros_node_.param("~" + topic + "/observation_persistence", observation_keep_time, 0.0);
ros_node_.param("~" + topic + "/expected_update_rate", expected_update_rate, 0.0);
ros_node_.param("~" + topic + "/data_type", data_type, std::string("PointCloud"));
ros_node_.param("~" + topic + "/min_obstacle_height", min_obstacle_height, 0.05);
@@ -111,7 +111,7 @@
if(clearing)
clearing_buffers_.push_back(observation_buffers_.back());
- ROS_DEBUG("Created an observation buffer for topic %s, expected update rate: %.2f, observation persistance: %.2f", topic.c_str(), expected_update_rate, observation_keep_time);
+ ROS_DEBUG("Created an observation buffer for topic %s, expected update rate: %.2f, observation persistence: %.2f", topic.c_str(), expected_update_rate, observation_keep_time);
//create a callback for the topic
if(data_type == "LaserScan"){
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-06-29 23:11:58
|
Revision: 17914
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17914&view=rev
Author: tfoote
Date: 2009-06-29 23:10:52 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
created nav_msgs and moved ParticleCloud there #1300
Modified Paths:
--------------
pkg/trunk/nav/amcl/manifest.xml
pkg/trunk/nav/amcl/src/amcl_node.cpp
pkg/trunk/nav/fake_localization/fake_localization.cpp
pkg/trunk/nav/fake_localization/manifest.xml
pkg/trunk/stacks/visualization/rviz/manifest.xml
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/nav_msgs/
pkg/trunk/stacks/common_msgs/nav_msgs/CMakeLists.txt
pkg/trunk/stacks/common_msgs/nav_msgs/Makefile
pkg/trunk/stacks/common_msgs/nav_msgs/mainpage.dox
pkg/trunk/stacks/common_msgs/nav_msgs/manifest.xml
pkg/trunk/stacks/common_msgs/nav_msgs/msg/
pkg/trunk/stacks/common_msgs/nav_msgs/msg/ParticleCloud.msg
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_msgs/msg/ParticleCloud.msg
Modified: pkg/trunk/nav/amcl/manifest.xml
===================================================================
--- pkg/trunk/nav/amcl/manifest.xml 2009-06-29 23:08:35 UTC (rev 17913)
+++ pkg/trunk/nav/amcl/manifest.xml 2009-06-29 23:10:52 UTC (rev 17914)
@@ -9,6 +9,7 @@
<depend package="tf" />
<depend package="robot_srvs" />
<depend package="robot_msgs" />
+ <depend package="nav_msgs" />
<depend package="std_srvs" />
<depend package="laser_scan" />
<depend package="visualization_msgs"/>
Modified: pkg/trunk/nav/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-29 23:08:35 UTC (rev 17913)
+++ pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-29 23:10:52 UTC (rev 17914)
@@ -66,7 +66,7 @@
Publishes to (name type):
- @b "amcl_pose" robot_msgs/PoseWithCovariance : robot's estimated pose in the map, with covariance
-- @b "particlecloud" robot_msgs/ParticleCloud : the set of pose estimates being maintained by the filter.
+- @b "particlecloud" nav_msgs/ParticleCloud : the set of pose estimates being maintained by the filter.
- @b "tf_message" tf/tfMessage : publishes the transform from "odom" (which can be remapped via the ~odom_frame_id parameter) to "map"
- @b "gui_laser" visualization_msgs/Polyline : re-projected laser scans (for visualization)
@@ -158,7 +158,7 @@
// Messages that I need
#include "laser_scan/LaserScan.h"
#include "robot_msgs/PoseWithCovariance.h"
-#include "robot_msgs/ParticleCloud.h"
+#include "nav_msgs/ParticleCloud.h"
#include "robot_msgs/Pose.h"
#include "robot_srvs/StaticMap.h"
#include "std_srvs/Empty.h"
@@ -440,7 +440,7 @@
laser_likelihood_max_dist);
ros::Node::instance()->advertise<robot_msgs::PoseWithCovariance>("amcl_pose",2);
- ros::Node::instance()->advertise<robot_msgs::ParticleCloud>("particlecloud",2);
+ ros::Node::instance()->advertise<nav_msgs::ParticleCloud>("particlecloud",2);
ros::Node::instance()->advertise<visualization_msgs::Polyline>("gui_laser",2);
ros::Node::instance()->advertiseService("global_localization",
&AmclNode::globalLocalizationCallback,
@@ -726,7 +726,7 @@
// Publish the resulting cloud
// TODO: set maximum rate for publishing
- robot_msgs::ParticleCloud cloud_msg;
+ nav_msgs::ParticleCloud cloud_msg;
cloud_msg.set_particles_size(set->sample_count);
for(int i=0;i<set->sample_count;i++)
{
Modified: pkg/trunk/nav/fake_localization/fake_localization.cpp
===================================================================
--- pkg/trunk/nav/fake_localization/fake_localization.cpp 2009-06-29 23:08:35 UTC (rev 17913)
+++ pkg/trunk/nav/fake_localization/fake_localization.cpp 2009-06-29 23:10:52 UTC (rev 17914)
@@ -60,7 +60,7 @@
Publishes to (name / type):
- @b "amcl_pose" robot_msgs/PoseWithCovariance : robot's estimated pose in the map, with covariance
-- @b "particlecloud" robot_msgs/ParticleCloud : fake set of particles being maintained by the filter (one paricle only).
+- @b "particlecloud" nav_msgs/ParticleCloud : fake set of particles being maintained by the filter (one paricle only).
<hr>
@@ -74,7 +74,7 @@
#include <ros/time.h>
#include <robot_msgs/PoseWithRatesStamped.h>
-#include <robot_msgs/ParticleCloud.h>
+#include <nav_msgs/ParticleCloud.h>
#include <robot_msgs/PoseWithCovariance.h>
#include <angles/angles.h>
@@ -92,7 +92,7 @@
FakeOdomNode(void) : ros::Node("fake_localization")
{
advertise<robot_msgs::PoseWithCovariance>("amcl_pose",1);
- advertise<robot_msgs::ParticleCloud>("particlecloud",1);
+ advertise<nav_msgs::ParticleCloud>("particlecloud",1);
m_tfServer = new tf::TransformBroadcaster();
m_tfListener = new tf::TransformListener(*this);
m_lastUpdate = ros::Time::now();
@@ -138,7 +138,7 @@
bool m_base_pos_received;
robot_msgs::PoseWithRatesStamped m_basePosMsg;
- robot_msgs::ParticleCloud m_particleCloud;
+ nav_msgs::ParticleCloud m_particleCloud;
robot_msgs::PoseWithCovariance m_currentPos;
//parameter for what odom to use
Modified: pkg/trunk/nav/fake_localization/manifest.xml
===================================================================
--- pkg/trunk/nav/fake_localization/manifest.xml 2009-06-29 23:08:35 UTC (rev 17913)
+++ pkg/trunk/nav/fake_localization/manifest.xml 2009-06-29 23:10:52 UTC (rev 17914)
@@ -5,6 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp" />
<depend package="rosconsole" />
+ <depend package="nav_msgs" />
<depend package="robot_msgs" />
<depend package="tf" />
<depend package="angles" />
Added: pkg/trunk/stacks/common_msgs/nav_msgs/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/CMakeLists.txt (rev 0)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/CMakeLists.txt 2009-06-29 23:10:52 UTC (rev 17914)
@@ -0,0 +1,30 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+# Set the build type. Options are:
+# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage
+# Debug : w/ debug symbols, w/o optimization
+# Release : w/o debug symbols, w/ optimization
+# RelWithDebInfo : w/ debug symbols, w/ optimization
+# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries
+#set(ROS_BUILD_TYPE RelWithDebInfo)
+
+rospack(nav_msgs)
+
+#set the default path for built executables to the "bin" directory
+set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set the default path for built libraries to the "lib" directory
+set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+
+#uncomment if you have defined messages
+genmsg()
+#uncomment if you have defined services
+#gensrv()
+
+#common commands for building c++ executables and libraries
+#rospack_add_library(${PROJECT_NAME} src/example.cpp)
+#target_link_libraries(${PROJECT_NAME} another_library)
+#rospack_add_boost_directories()
+#rospack_link_boost(${PROJECT_NAME} thread)
+#rospack_add_executable(example examples/example.cpp)
+#target_link_libraries(example ${PROJECT_NAME})
Added: pkg/trunk/stacks/common_msgs/nav_msgs/Makefile
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/Makefile (rev 0)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/Makefile 2009-06-29 23:10:52 UTC (rev 17914)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
Added: pkg/trunk/stacks/common_msgs/nav_msgs/mainpage.dox
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/mainpage.dox (rev 0)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/mainpage.dox 2009-06-29 23:10:52 UTC (rev 17914)
@@ -0,0 +1,119 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b nav_msgs is ...
+
+<!--
+In addition to providing an overview of your package,
+this is the section where the specification and design/architecture
+should be detailed. While the original specification may be done on the
+wiki, it should be transferred here once your package starts to take shape.
+You can then link to this documentation page from the Wiki.
+-->
+
+
+\section codeapi Code API
+
+<!--
+Provide links to specific auto-generated API documentation within your
+package that is of particular interest to a reader. Doxygen will
+document pretty much every part of your code, so do your best here to
+point the reader to the actual API.
+
+If your codebase is fairly large or has different sets of APIs, you
+should use the doxygen 'group' tag to keep these APIs together. For
+example, the roscpp documentation has 'libros' group.
+-->
+
+\section rosapi ROS API
+
+<!--
+Names are very important in ROS because they can be remapped on the
+command-line, so it is VERY IMPORTANT THAT YOU LIST NAMES AS THEY
+APPEAR IN THE CODE. You should list names of every topic, service and
+parameter used in your code. There is a template below that you can
+use to document each node separately.
+
+List of nodes:
+- \b node_name1
+- \b node_name2
+-->
+
+<!-- START: copy from here to 'END' for each node
+
+<hr>
+
+\subsection node_name node_name
+
+node_name does (provide a basic description of your node)
+
+\subsubsection Usage
+\verbatim
+$ node_type1 [standard ROS args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ node_type1
+\endverbatim
+
+
+\subsubsection topics ROS topics
+
+Subscribes to:
+- \b "in": [std_msgs/FooType] description of in
+
+Publishes to:
+- \b "out": [std_msgs/FooType] description of out
+
+
+\subsubsection parameters ROS parameters
+
+Reads the following parameters from the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+- \b "~my_param" : \b [string] description of my_param
+
+Sets the following parameters on the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+
+
+\subsubsection services ROS services
+- \b "foo_service": [std_srvs/FooType] description of foo_service
+
+
+END: copy for each node -->
+
+
+<!-- START: Uncomment if you have any command-line tools
+
+\section commandline Command-line tools
+
+This section is a catch-all for any additional tools that your package
+provides or uses that may be of use to the reader. For example:
+
+- tools/scripts (e.g. rospack, roscd)
+- roslaunch .launch files
+- xmlparam files
+
+\subsection script_name script_name
+
+Description of what this script/file does.
+
+\subsubsection Usage
+\verbatim
+$ ./script_name [args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ ./script_name foo bar
+\endverbatim
+
+END: Command-Line Tools Section -->
+
+*/
\ No newline at end of file
Added: pkg/trunk/stacks/common_msgs/nav_msgs/manifest.xml
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/manifest.xml (rev 0)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/manifest.xml 2009-06-29 23:10:52 UTC (rev 17914)
@@ -0,0 +1,18 @@
+<package>
+ <description brief="Messages for the nav stack">
+
+ These messages are the common messages used to interact with the nav stack
+
+ </description>
+ <author>Tully Foote</author>
+ <license>BSD</license>
+ <review status="API conditionally cleared" notes="http://pr.willowgarage.com/wiki/robot_msgs/2009-05-05_API_Reviewx"/>
+ <url>http://pr.willowgarage.com/wiki/nav_msgs</url>
+ <depend package="robot_msgs"/>
+ <export>
+ <cpp cflags="-I${prefix}/msg/cpp"/>
+ </export>
+
+</package>
+
+
Copied: pkg/trunk/stacks/common_msgs/nav_msgs/msg/ParticleCloud.msg (from rev 17898, pkg/trunk/stacks/common_msgs/robot_msgs/msg/ParticleCloud.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/msg/ParticleCloud.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/msg/ParticleCloud.msg 2009-06-29 23:10:52 UTC (rev 17914)
@@ -0,0 +1 @@
+robot_msgs/Pose[] particles
Property changes on: pkg/trunk/stacks/common_msgs/nav_msgs/msg/ParticleCloud.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/robot_msgs/msg/ParticleCloud.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/ParticleCloud.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/ParticleCloud.msg 2009-06-29 23:08:35 UTC (rev 17913)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/ParticleCloud.msg 2009-06-29 23:10:52 UTC (rev 17914)
@@ -1 +0,0 @@
-robot_msgs/Pose[] particles
Modified: pkg/trunk/stacks/visualization/rviz/manifest.xml
===================================================================
--- pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-06-29 23:08:35 UTC (rev 17913)
+++ pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-06-29 23:10:52 UTC (rev 17914)
@@ -14,6 +14,7 @@
<depend package="rosconsole"/>
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
+ <depend package="nav_msgs"/>
<depend package="mechanism_msgs" />
<depend package="deprecated_msgs"/>
<depend package="tf"/>
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp 2009-06-29 23:08:35 UTC (rev 17913)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp 2009-06-29 23:10:52 UTC (rev 17914)
@@ -172,7 +172,7 @@
topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &ParticleCloud2DDisplay::getTopic, this ),
boost::bind( &ParticleCloud2DDisplay::setTopic, this, _1 ), category_, this );
ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
- topic_prop->setMessageType(robot_msgs::ParticleCloud::__s_getDataType());
+ topic_prop->setMessageType(nav_msgs::ParticleCloud::__s_getDataType());
}
void ParticleCloud2DDisplay::fixedFrameChanged()
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h 2009-06-29 23:08:35 UTC (rev 17913)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.h 2009-06-29 23:10:52 UTC (rev 17914)
@@ -35,7 +35,7 @@
#include "helpers/color.h"
#include "properties/forwards.h"
-#include <robot_msgs/ParticleCloud.h>
+#include <nav_msgs/ParticleCloud.h>
namespace ogre_tools
{
@@ -102,7 +102,7 @@
Ogre::ManualObject* manual_object_;
bool new_message_;
- robot_msgs::ParticleCloud message_;
+ nav_msgs::ParticleCloud message_;
ColorPropertyWPtr color_property_;
ROSTopicStringPropertyWPtr topic_property_;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-06-29 23:54:48
|
Revision: 17918
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17918&view=rev
Author: tfoote
Date: 2009-06-29 23:52:46 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
moving MapMetaData and OccGrid into nav_msgs #1303
Modified Paths:
--------------
pkg/trunk/nav/map_server/src/main.cpp
pkg/trunk/stacks/common_msgs/robot_srvs/manifest.xml
pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/poly_line_2d_display.h
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/nav_msgs/msg/MapMetaData.msg
pkg/trunk/stacks/common_msgs/nav_msgs/msg/OccGrid.msg
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_msgs/msg/MapMetaData.msg
pkg/trunk/stacks/common_msgs/robot_msgs/msg/OccGrid.msg
Modified: pkg/trunk/nav/map_server/src/main.cpp
===================================================================
--- pkg/trunk/nav/map_server/src/main.cpp 2009-06-29 23:31:41 UTC (rev 17917)
+++ pkg/trunk/nav/map_server/src/main.cpp 2009-06-29 23:52:46 UTC (rev 17918)
@@ -108,7 +108,7 @@
#include "ros/ros.h"
#include "ros/console.h"
#include "map_server/image_loader.h"
-#include "robot_msgs/MapMetaData.h"
+#include "nav_msgs/MapMetaData.h"
class MapServer
{
@@ -134,7 +134,7 @@
meta_data_message_ = map_resp_.map.info;
service = n.advertiseService("static_map", &MapServer::mapCallback, this);
- pub = n.advertise<robot_msgs::MapMetaData>("map_metadata", 1,
+ pub = n.advertise<nav_msgs::MapMetaData>("map_metadata", 1,
boost::bind(&MapServer::metadataSubscriptionCallback, *this, _1));
}
@@ -164,7 +164,7 @@
pub.publish( meta_data_message_ );
}
- robot_msgs::MapMetaData meta_data_message_;
+ nav_msgs::MapMetaData meta_data_message_;
};
int main(int argc, char **argv)
Copied: pkg/trunk/stacks/common_msgs/nav_msgs/msg/MapMetaData.msg (from rev 17898, pkg/trunk/stacks/common_msgs/robot_msgs/msg/MapMetaData.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/msg/MapMetaData.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/msg/MapMetaData.msg 2009-06-29 23:52:46 UTC (rev 17918)
@@ -0,0 +1,11 @@
+# The time at which the map was loaded
+time map_load_time
+# The map resolution [m/cell]
+float32 resolution
+# Map width [cells]
+uint32 width
+# Map height [cells]
+uint32 height
+# The origin of the map [m, m, rad]. This is the real-world pose of the
+# cell (0,0) in the map.
+robot_msgs/Pose origin
\ No newline at end of file
Property changes on: pkg/trunk/stacks/common_msgs/nav_msgs/msg/MapMetaData.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/robot_msgs/msg/MapMetaData.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Copied: pkg/trunk/stacks/common_msgs/nav_msgs/msg/OccGrid.msg (from rev 17898, pkg/trunk/stacks/common_msgs/robot_msgs/msg/OccGrid.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/nav_msgs/msg/OccGrid.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/nav_msgs/msg/OccGrid.msg 2009-06-29 23:52:46 UTC (rev 17918)
@@ -0,0 +1,10 @@
+# A 2-D grid map, in which each cell represents the probability of
+# occupancy. Occupancy values are integers in the range [0,100], or -1
+# for unknown.
+
+#MetaData for the map
+MapMetaData info
+
+# The map data, in row-major order, starting with (0,0). Occupancy
+# probabilities are in the range [0,100]. Unknown is -1.
+byte[] data
Property changes on: pkg/trunk/stacks/common_msgs/nav_msgs/msg/OccGrid.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/robot_msgs/msg/OccGrid.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/MapMetaData.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/MapMetaData.msg 2009-06-29 23:31:41 UTC (rev 17917)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/MapMetaData.msg 2009-06-29 23:52:46 UTC (rev 17918)
@@ -1,11 +0,0 @@
-# The time at which the map was loaded
-time map_load_time
-# The map resolution [m/cell]
-float32 resolution
-# Map width [cells]
-uint32 width
-# Map height [cells]
-uint32 height
-# The origin of the map [m, m, rad]. This is the real-world pose of the
-# cell (0,0) in the map.
-robot_msgs/Pose origin
\ No newline at end of file
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/OccGrid.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/OccGrid.msg 2009-06-29 23:31:41 UTC (rev 17917)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/OccGrid.msg 2009-06-29 23:52:46 UTC (rev 17918)
@@ -1,10 +0,0 @@
-# A 2-D grid map, in which each cell represents the probability of
-# occupancy. Occupancy values are integers in the range [0,100], or -1
-# for unknown.
-
-#MetaData for the map
-MapMetaData info
-
-# The map data, in row-major order, starting with (0,0). Occupancy
-# probabilities are in the range [0,100]. Unknown is -1.
-byte[] data
Modified: pkg/trunk/stacks/common_msgs/robot_srvs/manifest.xml
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_srvs/manifest.xml 2009-06-29 23:31:41 UTC (rev 17917)
+++ pkg/trunk/stacks/common_msgs/robot_srvs/manifest.xml 2009-06-29 23:52:46 UTC (rev 17918)
@@ -11,6 +11,7 @@
<logo>http://www.willowgarage.com/files/willowgarage/robot10.jpg</logo>
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
+ <depend package="nav_msgs"/><!-- will not be needed when StaticMap is moved to nav_srvs -->
<export>
<cpp cflags="-I${prefix}/srv/cpp"/>
</export>
Modified: pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv 2009-06-29 23:31:41 UTC (rev 17917)
+++ pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv 2009-06-29 23:52:46 UTC (rev 17918)
@@ -1,2 +1,2 @@
---
-robot_msgs/OccGrid map
+nav_msgs/OccGrid map
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h 2009-06-29 23:31:41 UTC (rev 17917)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h 2009-06-29 23:52:46 UTC (rev 17918)
@@ -37,7 +37,7 @@
#include <OGRE/OgreMaterial.h>
#include <OGRE/OgreVector3.h>
-#include <robot_msgs/MapMetaData.h>
+#include <nav_msgs/MapMetaData.h>
#include <ros/time.h>
#include "ros/node.h" //\todo Convert to node handle API
@@ -127,7 +127,7 @@
float map_request_timer_;
bool new_metadata_;
- robot_msgs::MapMetaData metadata_message_;
+ nav_msgs::MapMetaData metadata_message_;
ros::Time last_loaded_map_time_;
boost::thread request_thread_;
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/poly_line_2d_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/poly_line_2d_display.h 2009-06-29 23:31:41 UTC (rev 17917)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/poly_line_2d_display.h 2009-06-29 23:52:46 UTC (rev 17918)
@@ -36,7 +36,7 @@
#include "properties/forwards.h"
#include <visualization_msgs/Polyline.h>
-#include <robot_msgs/MapMetaData.h>
+#include <nav_msgs/MapMetaData.h>
#include <boost/shared_ptr.hpp>
@@ -147,7 +147,7 @@
tf::MessageNotifier<visualization_msgs::Polyline>* notifier_;
bool new_metadata_;
- robot_msgs::MapMetaData metadata_message_;
+ nav_msgs::MapMetaData metadata_message_;
ColorPropertyWPtr color_property_;
ROSTopicStringPropertyWPtr topic_property_;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-06-30 00:04:40
|
Revision: 17922
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17922&view=rev
Author: tfoote
Date: 2009-06-30 00:03:14 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
creating nav stack
Added Paths:
-----------
pkg/trunk/stacks/nav/
pkg/trunk/stacks/nav/stack.xml
Removed Paths:
-------------
pkg/trunk/nav/stack.xml
Deleted: pkg/trunk/nav/stack.xml
===================================================================
--- pkg/trunk/nav/stack.xml 2009-06-29 23:59:32 UTC (rev 17921)
+++ pkg/trunk/nav/stack.xml 2009-06-30 00:03:14 UTC (rev 17922)
@@ -1,15 +0,0 @@
-<stack name="nav" version="0.1">
- <description brief="nav stack">
- The 2D navigation stack
- </description>
- <version>0.1</version>
- <author>Eitan ei...@wi...</author>
- <license>BSD</license>
- <review status="unreviewed" notes=""/>
- <url>http://pr.willowgarage.com/wiki/nav</url>
-
- <depend stack="ros" version="0.5"/>
- <depend stack="ros-pkg_common" version="0.1"/>
- <depend stack="ros-pkg_visualization_core" version="0.1"/>
-</stack>
-
Copied: pkg/trunk/stacks/nav/stack.xml (from rev 17919, pkg/trunk/nav/stack.xml)
===================================================================
--- pkg/trunk/stacks/nav/stack.xml (rev 0)
+++ pkg/trunk/stacks/nav/stack.xml 2009-06-30 00:03:14 UTC (rev 17922)
@@ -0,0 +1,15 @@
+<stack name="nav" version="0.1">
+ <description brief="nav stack">
+ The 2D navigation stack
+ </description>
+ <version>0.1</version>
+ <author>Eitan ei...@wi...</author>
+ <license>BSD</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/nav</url>
+
+ <depend stack="ros" version="0.5"/>
+ <depend stack="ros-pkg_common" version="0.1"/>
+ <depend stack="ros-pkg_visualization_core" version="0.1"/>
+</stack>
+
Property changes on: pkg/trunk/stacks/nav/stack.xml
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/nav/stack.xml:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-06-30 00:05:46
|
Revision: 17923
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17923&view=rev
Author: tfoote
Date: 2009-06-30 00:04:30 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
moving navfn into nav stack
Added Paths:
-----------
pkg/trunk/stacks/nav/navfn/
Removed Paths:
-------------
pkg/trunk/motion_planning/navfn/
Property changes on: pkg/trunk/stacks/nav/navfn
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/motion_planning/navfn:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-06-30 01:00:42
|
Revision: 17929
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17929&view=rev
Author: tfoote
Date: 2009-06-30 00:56:54 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
moving StaticMap from robot_srvs to nav_srvs #1707
Modified Paths:
--------------
pkg/trunk/nav/amcl/manifest.xml
pkg/trunk/nav/amcl/src/amcl_node.cpp
pkg/trunk/nav/map_server/include/map_server/image_loader.h
pkg/trunk/nav/map_server/manifest.xml
pkg/trunk/nav/map_server/src/image_loader.cpp
pkg/trunk/nav/map_server/src/main.cpp
pkg/trunk/nav/map_server/src/map_saver.cpp
pkg/trunk/nav/map_server/test/consumer.py
pkg/trunk/nav/map_server/test/rtest.cpp
pkg/trunk/nav/map_server/test/utest.cpp
pkg/trunk/nav/nav_view/manifest.xml
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h
pkg/trunk/nav/wavefront/manifest.xml
pkg/trunk/nav/wavefront/src/wavefront_node.cpp
pkg/trunk/stacks/common/nav_srvs/manifest.xml
pkg/trunk/stacks/visualization/rviz/manifest.xml
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h
pkg/trunk/stacks/world_models/costmap_2d/manifest.xml
pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp
pkg/trunk/stacks/world_models/costmap_2d/src/costmap_test.cpp
Added Paths:
-----------
pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv
Modified: pkg/trunk/nav/amcl/manifest.xml
===================================================================
--- pkg/trunk/nav/amcl/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/amcl/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -10,6 +10,7 @@
<depend package="robot_srvs" />
<depend package="robot_msgs" />
<depend package="nav_msgs" />
+ <depend package="nav_srvs" />
<depend package="std_srvs" />
<depend package="laser_scan" />
<depend package="visualization_msgs"/>
Modified: pkg/trunk/nav/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -160,7 +160,7 @@
#include "robot_msgs/PoseWithCovariance.h"
#include "nav_msgs/ParticleCloud.h"
#include "robot_msgs/Pose.h"
-#include "robot_srvs/StaticMap.h"
+#include "nav_srvs/StaticMap.h"
#include "std_srvs/Empty.h"
#include "visualization_msgs/Polyline.h"
@@ -462,8 +462,8 @@
ROS_ASSERT(map);
// get map via RPC
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
ROS_INFO("Requesting the map...");
while(!ros::service::call("static_map", req, resp))
{
Modified: pkg/trunk/nav/map_server/include/map_server/image_loader.h
===================================================================
--- pkg/trunk/nav/map_server/include/map_server/image_loader.h 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/include/map_server/image_loader.h 2009-06-30 00:56:54 UTC (rev 17929)
@@ -33,7 +33,7 @@
* Author: Brian Gerkey
*/
-#include "robot_srvs/StaticMap.h"
+#include "nav_srvs/StaticMap.h"
namespace map_server
{
@@ -51,7 +51,7 @@
*
* @throws std::runtime_error If the image file can't be loaded
* */
-void loadMapFromFile(robot_srvs::StaticMap::Response* resp,
+void loadMapFromFile(nav_srvs::StaticMap::Response* resp,
const char* fname, double res, bool negate,
double occ_th, double free_th);
}
Modified: pkg/trunk/nav/map_server/manifest.xml
===================================================================
--- pkg/trunk/nav/map_server/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -11,7 +11,7 @@
<depend package="rosconsole"/>
<depend package="roscpp"/>
<depend package="rospy" />
- <depend package="robot_srvs"/>
+ <depend package="nav_srvs"/>
<depend package="bullet"/>
<export>
<cpp cflags="-I${prefix}/include `rosboost-cfg --cflags`" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib `rosboost-cfg --lflags thread`"/>
Modified: pkg/trunk/nav/map_server/src/image_loader.cpp
===================================================================
--- pkg/trunk/nav/map_server/src/image_loader.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/src/image_loader.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -51,7 +51,7 @@
{
void
-loadMapFromFile(robot_srvs::StaticMap::Response* resp,
+loadMapFromFile(nav_srvs::StaticMap::Response* resp,
const char* fname, double res, bool negate,
double occ_th, double free_th)
{
Modified: pkg/trunk/nav/map_server/src/main.cpp
===================================================================
--- pkg/trunk/nav/map_server/src/main.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/src/main.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -70,7 +70,7 @@
@section services ROS services
Offers (name/type):
-- @b "static_map"/robot_srvs::StaticMap : Retrieve the map via this service
+- @b "static_map"/nav_srvs::StaticMap : Retrieve the map via this service
@section parameters ROS parameters
@@ -144,8 +144,8 @@
ros::ServiceServer service;
/** Callback invoked when someone requests our service */
- bool mapCallback(robot_srvs::StaticMap::Request &req,
- robot_srvs::StaticMap::Response &res )
+ bool mapCallback(nav_srvs::StaticMap::Request &req,
+ nav_srvs::StaticMap::Response &res )
{
// request is empty; we ignore it
@@ -157,7 +157,7 @@
/** The map response is cached here, to be sent out to service callers
*/
- robot_srvs::StaticMap::Response map_resp_;
+ nav_srvs::StaticMap::Response map_resp_;
void metadataSubscriptionCallback(const ros::SingleSubscriberPublisher& pub)
{
Modified: pkg/trunk/nav/map_server/src/map_saver.cpp
===================================================================
--- pkg/trunk/nav/map_server/src/map_saver.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/src/map_saver.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -57,14 +57,14 @@
@section topic ROS services
Uses (name type):
-- @b static_map robot_srvs/StaticMap : map service.
+- @b static_map nav_srvs/StaticMap : map service.
**/
#include <cstdio>
#include "ros/node.h"
#include "ros/console.h"
-#include "robot_srvs/StaticMap.h"
+#include "nav_srvs/StaticMap.h"
#include "LinearMath/btMatrix3x3.h"
using namespace std;
@@ -84,8 +84,8 @@
ros::Node n("map_generator");
const static std::string servname = "static_map";
ROS_INFO("Requesting the map from %s...", n.mapName(servname).c_str());
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
while(n.ok() && !ros::service::call(servname, req, resp))
{
ROS_WARN("request to %s failed; trying again...", n.mapName(servname).c_str());
Modified: pkg/trunk/nav/map_server/test/consumer.py
===================================================================
--- pkg/trunk/nav/map_server/test/consumer.py 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/test/consumer.py 2009-06-30 00:56:54 UTC (rev 17929)
@@ -41,7 +41,7 @@
import sys, unittest, time
import rospy, rostest
-from robot_srvs.srv import *
+from nav_srvs.srv import StaticMap
class TestConsumer(unittest.TestCase):
def __init__(self, *args):
Modified: pkg/trunk/nav/map_server/test/rtest.cpp
===================================================================
--- pkg/trunk/nav/map_server/test/rtest.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/test/rtest.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -32,7 +32,7 @@
#include <gtest/gtest.h>
#include <ros/service.h>
#include <ros/node.h>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
#include "test_constants.h"
@@ -65,8 +65,8 @@
{
try
{
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
// Try a few times, because the server may not be up yet.
int i=10;
bool call_result;
Modified: pkg/trunk/nav/map_server/test/utest.cpp
===================================================================
--- pkg/trunk/nav/map_server/test/utest.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/map_server/test/utest.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -43,7 +43,7 @@
{
try
{
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, g_valid_png_file, g_valid_image_res, false, 0.65, 0.1);
EXPECT_FLOAT_EQ(map_resp.map.info.resolution, g_valid_image_res);
EXPECT_EQ(map_resp.map.info.width, g_valid_image_width);
@@ -63,7 +63,7 @@
{
try
{
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, g_valid_bmp_file, g_valid_image_res, false, 0.65, 0.1);
EXPECT_FLOAT_EQ(map_resp.map.info.resolution, g_valid_image_res);
EXPECT_EQ(map_resp.map.info.width, g_valid_image_width);
@@ -83,7 +83,7 @@
{
try
{
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Response map_resp;
map_server::loadMapFromFile(&map_resp, "foo", 0.1, false, 0.65, 0.1);
}
catch(std::runtime_error &e)
Modified: pkg/trunk/nav/nav_view/manifest.xml
===================================================================
--- pkg/trunk/nav/nav_view/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/nav_view/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -4,7 +4,9 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="roscpp"/>
+ <depend package="nav_srvs"/>
<depend package="robot_srvs"/>
+ <depend package="nav_msgs"/>
<depend package="tf"/>
<depend package="ogre"/>
<depend package="ogre_tools"/>
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 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -31,7 +31,7 @@
#include "ogre_tools/wx_ogre_render_window.h"
-#include "robot_srvs/StaticMap.h"
+#include "nav_srvs/StaticMap.h"
#include "ros/common.h"
#include "ros/node.h"
@@ -199,8 +199,8 @@
void NavViewPanel::loadMap()
{
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
printf("Requesting the map...\n");
if( !ros::service::call("/static_map", req, resp) )
{
Modified: pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h
===================================================================
--- pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h 2009-06-30 00:56:54 UTC (rev 17929)
@@ -32,7 +32,7 @@
#include "nav_view_panel_generated.h"
-#include "robot_msgs/ParticleCloud.h"
+#include "nav_msgs/ParticleCloud.h"
#include "robot_msgs/PoseStamped.h"
#include "visualization_msgs/Polyline.h"
#include "robot_msgs/PoseWithCovariance.h"
@@ -205,7 +205,7 @@
int map_height_;
Ogre::TexturePtr map_texture_;
- robot_msgs::ParticleCloud cloud_;
+ nav_msgs::ParticleCloud cloud_;
robot_msgs::PoseStamped goal_;
visualization_msgs::Polyline path_line_;
visualization_msgs::Polyline local_path_;
Modified: pkg/trunk/nav/wavefront/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/wavefront/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -5,7 +5,7 @@
<review status="unreviewed" notes=""/>
<depend package="roscpp" />
<depend package="laser_scan" />
- <depend package="robot_srvs" />
+ <depend package="nav_srvs" />
<depend package="robot_msgs" />
<depend package="robot_actions" />
<depend package="nav_robot_actions" />
Modified: pkg/trunk/nav/wavefront/src/wavefront_node.cpp
===================================================================
--- pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -106,7 +106,7 @@
#include <robot_msgs/PoseDot.h>
#include <robot_msgs/PointCloud.h>
#include <laser_scan/LaserScan.h>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
// For GUI debug
#include <visualization_msgs/Polyline.h>
@@ -295,8 +295,8 @@
gui_publish_rate = ros::Duration(1.0/tmp);
// get map via RPC
- robot_srvs::StaticMap::Request req;
- robot_srvs::StaticMap::Response resp;
+ nav_srvs::StaticMap::Request req;
+ nav_srvs::StaticMap::Response resp;
puts("Requesting the map...");
while(!ros::service::call("/static_map", req, resp))
{
Modified: pkg/trunk/stacks/common/nav_srvs/manifest.xml
===================================================================
--- pkg/trunk/stacks/common/nav_srvs/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/common/nav_srvs/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -5,6 +5,7 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="robot_msgs"/>
+ <depend package="nav_msgs"/>
<export>
<cpp cflags="-I${prefix}/srv/cpp"/>
</export>
Copied: pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv (from rev 17919, pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv)
===================================================================
--- pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv (rev 0)
+++ pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv 2009-06-30 00:56:54 UTC (rev 17929)
@@ -0,0 +1,2 @@
+---
+nav_msgs/OccGrid map
Property changes on: pkg/trunk/stacks/common/nav_srvs/srv/StaticMap.srv
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/robot_srvs/srv/StaticMap.srv:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Deleted: pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/common_msgs/robot_srvs/srv/StaticMap.srv 2009-06-30 00:56:54 UTC (rev 17929)
@@ -1,2 +0,0 @@
----
-nav_msgs/OccGrid map
Modified: pkg/trunk/stacks/visualization/rviz/manifest.xml
===================================================================
--- pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -15,6 +15,7 @@
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="nav_msgs"/>
+ <depend package="nav_srvs"/>
<depend package="mechanism_msgs" />
<depend package="deprecated_msgs"/>
<depend package="tf"/>
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -190,7 +190,7 @@
{
if (!loaded_ || reload_)
{
- robot_srvs::StaticMap srv;
+ nav_srvs::StaticMap srv;
ROS_DEBUG("Requesting the map...");
if( !ros::service::call(service_, srv) )
{
@@ -444,7 +444,7 @@
const char* MapDisplay::getDescription()
{
- return "Displays an image of a map gotten through a robot_srvs::StaticMap service.";
+ return "Displays an image of a map gotten through a nav_srvs::StaticMap service.";
}
} // namespace rviz
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/map_display.h 2009-06-30 00:56:54 UTC (rev 17929)
@@ -44,7 +44,7 @@
#include <boost/thread/thread.hpp>
#include <boost/thread/mutex.hpp>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
namespace Ogre
{
@@ -131,7 +131,7 @@
ros::Time last_loaded_map_time_;
boost::thread request_thread_;
- robot_srvs::StaticMap map_srv_;
+ nav_srvs::StaticMap map_srv_;
bool new_map_;
boost::mutex map_mutex_;
bool reload_;
Modified: pkg/trunk/stacks/world_models/costmap_2d/manifest.xml
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/manifest.xml 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/world_models/costmap_2d/manifest.xml 2009-06-30 00:56:54 UTC (rev 17929)
@@ -10,7 +10,7 @@
<depend package="laser_scan" />
<depend package="tf" />
<depend package="voxel_grid" />
-<depend package="robot_srvs" />
+<depend package="nav_srvs" />
<depend package="visualization_msgs" />
<export>
<cpp cflags="-I${prefix}/include -I${prefix}/msg/cpp `rosboost-cfg --cflags`" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib `rosboost-cfg --lflags thread` -lcostmap_2d"/>
Modified: pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -36,7 +36,7 @@
*********************************************************************/
#include <costmap_2d/costmap_2d_ros.h>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
namespace costmap_2d {
@@ -155,8 +155,8 @@
map_height = (unsigned int)(map_height_meters / map_resolution);
if(static_map){
- robot_srvs::StaticMap::Request map_req;
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Request map_req;
+ nav_srvs::StaticMap::Response map_resp;
ROS_INFO("Requesting the map...\n");
while(!ros::service::call("/static_map", map_req, map_resp))
{
Modified: pkg/trunk/stacks/world_models/costmap_2d/src/costmap_test.cpp
===================================================================
--- pkg/trunk/stacks/world_models/costmap_2d/src/costmap_test.cpp 2009-06-30 00:49:42 UTC (rev 17928)
+++ pkg/trunk/stacks/world_models/costmap_2d/src/costmap_test.cpp 2009-06-30 00:56:54 UTC (rev 17929)
@@ -38,7 +38,7 @@
#include <ros/console.h>
#include <new_costmap/costmap_2d.h>
#include <new_costmap/observation_buffer.h>
-#include <robot_srvs/StaticMap.h>
+#include <nav_srvs/StaticMap.h>
#include <visualization_msgs/Polyline.h>
#include <map>
#include <vector>
@@ -71,8 +71,8 @@
boost::bind(&CostmapTester::baseScanCallback, this, _1, (int) 1),
"base_scan", global_frame_, 50);
- robot_srvs::StaticMap::Request map_req;
- robot_srvs::StaticMap::Response map_resp;
+ nav_srvs::StaticMap::Request map_req;
+ nav_srvs::StaticMap::Response map_resp;
ROS_INFO("Requesting the map...\n");
while(!ros::service::call("static_map", map_req, map_resp))
{
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tpr...@us...> - 2009-06-30 01:02:32
|
Revision: 17926
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17926&view=rev
Author: tpratkanis
Date: 2009-06-30 00:44:22 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
Change robot actions to use the new ros::NodeHandle API.
Modified Paths:
--------------
pkg/trunk/highlevel/test_robot_actions/test/utest.cc
pkg/trunk/stacks/common/robot_actions/include/robot_actions/action.h
pkg/trunk/stacks/common/robot_actions/include/robot_actions/action_client.h
pkg/trunk/stacks/common/robot_actions/include/robot_actions/action_runner.h
pkg/trunk/stacks/common/robot_actions/include/robot_actions/message_adapter.h
pkg/trunk/stacks/common/robot_actions/src/action_runner.cpp
Modified: pkg/trunk/highlevel/test_robot_actions/test/utest.cc
===================================================================
--- pkg/trunk/highlevel/test_robot_actions/test/utest.cc 2009-06-30 00:35:56 UTC (rev 17925)
+++ pkg/trunk/highlevel/test_robot_actions/test/utest.cc 2009-06-30 00:44:22 UTC (rev 17926)
@@ -5,6 +5,7 @@
#include <std_msgs/Float32.h>
#include <test_robot_actions/TestState.h>
#include <gtest/gtest.h>
+#include <ros/ros.h>
using namespace robot_actions;
using namespace test_robot_actions;
@@ -296,16 +297,22 @@
}
+void spinThread() {
+ ros::spin();
+}
+
int main(int argc, char** argv){
- ros::init(argc, argv);
-
- ros::Node node("robot_actions_test");
+ ros::init(argc, argv, "robot_actions_test");
+ ros::NodeHandle n;
+
+ boost::thread* spinthread = new boost::thread(boost::bind(&spinThread));
+
testing::InitGoogleTest(&argc, argv);
int result = RUN_ALL_TESTS();
- node.shutdown();
+ delete spinthread;
return result;
}
Modified: pkg/trunk/stacks/common/robot_actions/include/robot_actions/action.h
===================================================================
--- pkg/trunk/stacks/common/robot_actions/include/robot_actions/action.h 2009-06-30 00:35:56 UTC (rev 17925)
+++ pkg/trunk/stacks/common/robot_actions/include/robot_actions/action.h 2009-06-30 00:44:22 UTC (rev 17926)
@@ -49,10 +49,11 @@
#include <robot_actions/ActionStatus.h>
#include <boost/bind.hpp>
#include <boost/thread.hpp>
-#include <ros/node.h>
#include <diagnostic_msgs/DiagnosticMessage.h>
-#include "ros/assert.h"
+#include "ros/assert.h"
+#include "ros/ros.h"
+
namespace robot_actions {
/**
@@ -192,7 +193,8 @@
Action(const std::string& name)
: _name(name), _preempt_request(false), _result_status(SUCCESS), _terminated(false), _action_thread(NULL), _callback(NULL),_diagnostics_statuses(1){
_status.value = ActionStatus::RESET;
- ros::Node::instance()->advertise<diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 1) ;
+ _node = new ros::NodeHandle();
+ _diagnostics_publisher = _node->advertise<diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 1) ;
}
virtual ~Action(){
@@ -201,7 +203,7 @@
_action_thread->join();
delete _action_thread;
}
- ros::Node::instance()->unadvertise("/diagnostics") ;
+ delete _node;
}
/**
@@ -292,7 +294,7 @@
_diagnostics_statuses[0] = diagnostics_status;
_diagnostics_message.status = _diagnostics_statuses;
_diagnostics_message.header.stamp = ros::Time::now();
- ros::Node::instance()->publish("/diagnostics",_diagnostics_message);
+ _diagnostics_publisher.publish(_diagnostics_message);
}
@@ -309,6 +311,8 @@
boost::function< void(const ActionStatus&, const Goal&, const Feedback&) > _callback; /*!< Callback function for sending updates */
diagnostic_msgs::DiagnosticMessage _diagnostics_message;
std::vector<diagnostic_msgs::DiagnosticStatus> _diagnostics_statuses;
+ ros::NodeHandle *_node;
+ ros::Publisher _diagnostics_publisher;
};
}
#endif
Modified: pkg/trunk/stacks/common/robot_actions/include/robot_actions/action_client.h
===================================================================
--- pkg/trunk/stacks/common/robot_actions/include/robot_actions/action_client.h 2009-06-30 00:35:56 UTC (rev 17925)
+++ pkg/trunk/stacks/common/robot_actions/include/robot_actions/action_client.h 2009-06-30 00:44:22 UTC (rev 17926)
@@ -78,31 +78,41 @@
private:
- void callbackHandler(); // Just a no-op
+ void callbackHandler(const boost::shared_ptr<State const> &input); // Just a no-op
State _state_update_msg;
const std::string _goal_topic;
const std::string _preempt_topic;
const std::string _feedback_topic;
bool _is_active;
+ ros::NodeHandle _node;
+ ros::Publisher _goal_publisher, _preempt_publisher;
+ ros::Subscriber _feedback_subscriber;
};
template <class Goal, class State, class Feedback>
+ void ActionClient<Goal, State, Feedback>::callbackHandler(const boost::shared_ptr<State const>& input) {
+ _state_update_msg = *input;
+ _is_active = (_state_update_msg.status.value == _state_update_msg.status.ACTIVE);
+ }
+
+
+ template <class Goal, class State, class Feedback>
ActionClient<Goal, State, Feedback>::ActionClient(const std::string& name)
: _goal_topic(name + "/activate"), _preempt_topic(name + "/preempt"), _feedback_topic(name + "/feedback"),_is_active(false){
// Subscribe to state updates
- ros::Node::instance()->subscribe(_feedback_topic, _state_update_msg, &ActionClient<Goal, State, Feedback>::callbackHandler, this, 1);
+ _feedback_subscriber = _node.subscribe(_feedback_topic, 1, &ActionClient<Goal, State, Feedback>::callbackHandler, this);
// Advertize goal requests.
- ros::Node::instance()->advertise<Goal>(_goal_topic, 1);
+ _goal_publisher = _node.advertise<Goal>(_goal_topic, 1);
// Advertize goal preemptions.
- ros::Node::instance()->advertise<std_msgs::Empty>(_preempt_topic, 1);
+ _preempt_publisher = _node.advertise<std_msgs::Empty>(_preempt_topic, 1);
// wait until we have at least 1 subscriber per advertised topic
ros::Time start_time = ros::Time::now();
ros::Duration timeout(10.0);
- while (ros::Node::instance()->numSubscribers(_goal_topic) < 1 || ros::Node::instance()->numSubscribers(_preempt_topic) < 1 ){
+ while (_goal_publisher.getNumSubscribers() < 1 || _preempt_publisher.getNumSubscribers() < 1 ){
if (ros::Time::now() > start_time+timeout){
ROS_ERROR("Action client did not receive subscribers on the %s or %s topic", _goal_topic.c_str(), _preempt_topic.c_str());
break;
@@ -113,9 +123,6 @@
template <class Goal, class State, class Feedback>
ActionClient<Goal, State, Feedback>::~ActionClient(){
- ros::Node::instance()->unadvertise(_goal_topic);
- ros::Node::instance()->unadvertise(_preempt_topic);
- ros::Node::instance()->unsubscribe(_state_update_msg);
}
template <class Goal, class State, class Feedback>
@@ -127,7 +134,7 @@
ResultStatus result = robot_actions::PREEMPTED;
// Post the goal
- ros::Node::instance()->publish(_goal_topic, goal);
+ _goal_publisher.publish(goal);
// Wait for activation. If we do not activate in time, we will preempt. Will not block for preemption
// callback since the action may be bogus.
@@ -140,7 +147,7 @@
if(duration_bound != NO_DURATION_BOUND){
ros::Duration elapsed_time = ros::Time::now() - start_time;
if(elapsed_time > duration_bound){
- ros::Node::instance()->publish(_preempt_topic, std_msgs::Empty());
+ _preempt_publisher.publish(std_msgs::Empty());
return result;
}
}
@@ -153,7 +160,7 @@
if(duration_bound != NO_DURATION_BOUND){
ros::Duration elapsed_time = ros::Time::now() - start_time;
if(elapsed_time > duration_bound){
- ros::Node::instance()->publish(_preempt_topic, std_msgs::Empty());
+ _preempt_publisher.publish(std_msgs::Empty());
}
}
@@ -173,15 +180,10 @@
ResultStatus ActionClient<Goal, State, Feedback>::execute(const Goal& goal, Feedback& feedback){
return execute(goal, feedback, ros::Duration());
}
-
- template <class Goal, class State, class Feedback>
- void ActionClient<Goal, State, Feedback>::callbackHandler(){
- _is_active = (_state_update_msg.status.value == _state_update_msg.status.ACTIVE);
- }
template <class Goal, class State, class Feedback>
void ActionClient<Goal, State, Feedback>::preempt(){
- ros::Node::instance()->publish(_preempt_topic, std_msgs::Empty());
+ _preempt_publisher.publish(std_msgs::Empty());
}
}
Modified: pkg/trunk/stacks/common/robot_actions/include/robot_actions/action_runner.h
===================================================================
--- pkg/trunk/stacks/common/robot_actions/include/robot_actions/action_runner.h 2009-06-30 00:35:56 UTC (rev 17925)
+++ pkg/trunk/stacks/common/robot_actions/include/robot_actions/action_runner.h 2009-06-30 00:44:22 UTC (rev 17926)
@@ -40,6 +40,7 @@
#include <robot_actions/message_adapter.h>
#include <boost/thread.hpp>
#include <ros/console.h>
+#include "ros/ros.h"
namespace robot_actions {
@@ -112,6 +113,7 @@
double _update_rate; /*!< The duration for each control cycle */
boost::thread* _update_thread; /*!< Thread running the planner loop */
std::vector<AbstractAdapter*> _adapters; /*!< Collection of action adapters to run */
+ ros::NodeHandle _node;
};
}
Modified: pkg/trunk/stacks/common/robot_actions/include/robot_actions/message_adapter.h
===================================================================
--- pkg/trunk/stacks/common/robot_actions/include/robot_actions/message_adapter.h 2009-06-30 00:35:56 UTC (rev 17925)
+++ pkg/trunk/stacks/common/robot_actions/include/robot_actions/message_adapter.h 2009-06-30 00:44:22 UTC (rev 17926)
@@ -41,7 +41,7 @@
#include <robot_actions/ActionStatus.h>
#include <std_msgs/Empty.h>
#include <boost/thread.hpp>
-#include <ros/node.h>
+#include <ros/ros.h>
#include <ros/console.h>
#include <boost/thread.hpp>
@@ -128,22 +128,19 @@
_action.connect(boost::bind(&MessageAdapter<Goal, State, Feedback>::notify, this, _1, _2, _3));
// Advertize state updates
- ros::Node::instance()->advertise<State>(_feedback_topic, QUEUE_MAX());
+ _feedback_publisher = _node.advertise<State>(_feedback_topic, QUEUE_MAX());
// Subscribe to goal requests.
- ros::Node::instance()->subscribe(_goal_topic, _request_msg, &MessageAdapter<Goal, State, Feedback>::requestHandler, this, 1);
+ _goal_subscriber = _node.subscribe<Goal>(_goal_topic, 1, &MessageAdapter<Goal, State, Feedback>::requestHandler, this);
// Subscribe to goal preemptions.
- ros::Node::instance()->subscribe(_preempt_topic, _preemption_msg, &MessageAdapter<Goal, State, Feedback>::preemptionHandler, this, 1);
+ _preempt_subscriber = _node.subscribe<std_msgs::Empty>(_preempt_topic, 1, &MessageAdapter<Goal, State, Feedback>::preemptionHandler, this);
}
/**
* @brief Do ROS cleanup
*/
virtual ~MessageAdapter(){
- ros::Node::instance()->unsubscribe(_request_msg);
- ros::Node::instance()->unsubscribe(_preemption_msg);
- ros::Node::instance()->unadvertise(_feedback_topic);
}
// Call back invoked from the action. Packages up as a state message and ships
@@ -152,7 +149,7 @@
state_msg.status = status;
state_msg.goal = goal;
state_msg.feedback = feedback;
- ros::Node::instance()->publish(_feedback_topic, state_msg);
+ _feedback_publisher.publish(state_msg);
}
virtual void publish(){
@@ -172,7 +169,8 @@
/**
* @brief Handle a new request.
*/
- void requestHandler(){
+ void requestHandler(const boost::shared_ptr<Goal const> &input){
+ _request_msg = *input;
if(isOk()){
_action.activate(_request_msg);
}
@@ -181,7 +179,8 @@
/**
* @brief Handle a preemption. Will ignore the request unless the action is currently active. Delegates to subclass for details.
*/
- void preemptionHandler(){
+ void preemptionHandler(const boost::shared_ptr<std_msgs::Empty const> &input){
+ _preemption_msg = *input;
if(isOk())
_action.preempt();
}
@@ -199,6 +198,9 @@
Goal _request_msg; /*!< Message populated by handler for a request */
std_msgs::Empty _preemption_msg; /*!< Message populated by handler for a preemption. */
State _state_msg; /*!< Message published. */
+ ros::NodeHandle _node; /*!< Node handle */
+ ros::Subscriber _goal_subscriber, _preempt_subscriber; /*!< Subscribers */
+ ros::Publisher _feedback_publisher; /*!< publisher */
};
}
Modified: pkg/trunk/stacks/common/robot_actions/src/action_runner.cpp
===================================================================
--- pkg/trunk/stacks/common/robot_actions/src/action_runner.cpp 2009-06-30 00:35:56 UTC (rev 17925)
+++ pkg/trunk/stacks/common/robot_actions/src/action_runner.cpp 2009-06-30 00:44:22 UTC (rev 17926)
@@ -39,7 +39,6 @@
namespace robot_actions {
ActionRunner::ActionRunner(double update_rate): _initialized(false), _terminated(false), _update_rate(update_rate), _update_thread(NULL){
-
ROS_ASSERT(_update_rate > 0);
// Start the action_runner_thread
@@ -82,7 +81,7 @@
}
void ActionRunner::updateLoop(){
- while(ros::Node::instance()->ok() && !isTerminated()) {
+ while(_node.ok() && !isTerminated()) {
ros::Time curr = ros::Time::now();
if(_initialized){
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <vij...@us...> - 2009-06-30 01:03:25
|
Revision: 17925
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17925&view=rev
Author: vijaypradeep
Date: 2009-06-30 00:35:56 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
Adding a message cache in the prototype message_filter design. Also still working on C++ dense laser assembler stuff. First cut of DenseLaserSnapshotter seems to work
Modified Paths:
--------------
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/CMakeLists.txt
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml
pkg/trunk/sandbox/message_filters/CMakeLists.txt
Added Paths:
-----------
pkg/trunk/calibration/calibration_msgs/
pkg/trunk/calibration/calibration_msgs/CMakeLists.txt
pkg/trunk/calibration/calibration_msgs/Makefile
pkg/trunk/calibration/calibration_msgs/manifest.xml
pkg/trunk/calibration/calibration_msgs/msg/
pkg/trunk/calibration/calibration_msgs/msg/DenseLaserSnapshot.msg
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/build_dense_laser_snapshot.cpp
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_assembler_srv.cpp
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_snapshotter.cpp
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/joint_extractor_display.cpp
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/tagged_laser_cache_display.cpp
pkg/trunk/sandbox/message_filters/include/message_filters/msg_cache.h
pkg/trunk/sandbox/message_filters/src/filter_example.cpp
pkg/trunk/sandbox/message_filters/test/
pkg/trunk/sandbox/message_filters/test/CMakeLists.txt
pkg/trunk/sandbox/message_filters/test/msg_cache_unittest.cpp
Removed Paths:
-------------
pkg/trunk/sandbox/message_filters/src/sync_test.cpp
Added: pkg/trunk/calibration/calibration_msgs/CMakeLists.txt
===================================================================
--- pkg/trunk/calibration/calibration_msgs/CMakeLists.txt (rev 0)
+++ pkg/trunk/calibration/calibration_msgs/CMakeLists.txt 2009-06-30 00:35:56 UTC (rev 17925)
@@ -0,0 +1,7 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+rospack(calibration_msgs)
+
+genmsg()
+
Added: pkg/trunk/calibration/calibration_msgs/Makefile
===================================================================
--- pkg/trunk/calibration/calibration_msgs/Makefile (rev 0)
+++ pkg/trunk/calibration/calibration_msgs/Makefile 2009-06-30 00:35:56 UTC (rev 17925)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
Added: pkg/trunk/calibration/calibration_msgs/manifest.xml
===================================================================
--- pkg/trunk/calibration/calibration_msgs/manifest.xml (rev 0)
+++ pkg/trunk/calibration/calibration_msgs/manifest.xml 2009-06-30 00:35:56 UTC (rev 17925)
@@ -0,0 +1,20 @@
+<package>
+ <description brief="calibration_msgs">
+ Messages for collecting datasets to perform various robot calibrations.
+ </description>
+ <author>Vijay Pradeep / vpr...@wi...</author>
+ <license>BSD</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/calibration_msgs</url>
+
+ <depend package="std_msgs" />
+ <depend package="robot_msgs" />
+ <depend package="image_msgs" />
+
+ <export>
+ <cpp cflags="-I${prefix}/msg/cpp" />
+ </export>
+
+</package>
+
+
Added: pkg/trunk/calibration/calibration_msgs/msg/DenseLaserSnapshot.msg
===================================================================
--- pkg/trunk/calibration/calibration_msgs/msg/DenseLaserSnapshot.msg (rev 0)
+++ pkg/trunk/calibration/calibration_msgs/msg/DenseLaserSnapshot.msg 2009-06-30 00:35:56 UTC (rev 17925)
@@ -0,0 +1,38 @@
+# Provides all the state & sensor information for
+# a single sweep of laser attached to some mechanism.
+# Most likely, this 'mechanism' will be the tilting stage
+Header header
+
+# Store the laser intrinsics. This is very similar to the
+# intrinsics commonly stored in
+float32 angle_min # start angle of the scan [rad]
+float32 angle_max # end angle of the scan [rad]
+float32 angle_increment # angular distance between measurements [rad]
+float32 time_increment # time between measurements [seconds]
+float32 range_min # minimum range value [m]
+float32 range_max # maximum range value [m]
+
+# Define the size of the binary data
+uint32 readings_per_scan # (Width)
+uint32 num_scans # (Height)
+
+# 2D Arrays storing laser data.
+# We can think of each type data as being a single channel image.
+# Each row of the image has data from a single scan, and scans are
+# concatenated to form the entire 'image'.
+float32[] ranges # (Image data)
+float32[] intensities # (Image data)
+
+# Joint information
+# Store joint information associated with each scan
+uint32 joint_encoding
+float64[] joint_positions
+string[] joint_names
+uint32 POS_PER_PIXEL = 0
+uint32 POS_PER_ROW_START = 1
+uint32 POS_PER_ROW_START_AND_END = 2
+
+# 1D Data storing meta information for each scan/row
+# Currently in stable, time vectors are not serialized correctly
+#time[] scan_start
+
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/CMakeLists.txt
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/CMakeLists.txt 2009-06-30 00:07:03 UTC (rev 17924)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/CMakeLists.txt 2009-06-30 00:35:56 UTC (rev 17925)
@@ -8,23 +8,24 @@
# RelWithDebInfo : w/ debug symbols, w/ optimization
# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries
#set(ROS_BUILD_TYPE RelWithDebInfo)
+set(ROS_BUILD_TYPE Debug)
rospack(dense_laser_assembler)
-#set the default path for built executables to the "bin" directory
+rospack_add_library(dense_laser_assembler src/build_dense_laser_snapshot.cpp)
+rospack_add_executable(dense_laser_assembler_srv src/dense_laser_assembler_srv.cpp)
+target_link_libraries(dense_laser_assembler_srv dense_laser_assembler)
+
+#rospack_add_executable(joint_extractor_display src/joint_extractor_display.cpp)
+#rospack_add_executable(tagged_laser_cache_display src/tagged_laser_cache_display.cpp)
+
+rospack_add_executable(dense_laser_snapshotter src/dense_laser_snapshotter.cpp)
+
+#rospack_add_executable(talker src/talker.cpp)
+#rospack_add_executable(listener src/listener.cpp)
+
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
-#set the default path for built libraries to the "lib" directory
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
-#uncomment if you have defined messages
genmsg()
-#uncomment if you have defined services
-#gensrv()
-
-#common commands for building c++ executables and libraries
-#rospack_add_library(${PROJECT_NAME} src/example.cpp)
-#target_link_libraries(${PROJECT_NAME} another_library)
-#rospack_add_boost_directories()
-#rospack_link_boost(${PROJECT_NAME} thread)
-#rospack_add_executable(example examples/example.cpp)
-#target_link_libraries(example ${PROJECT_NAME})
+gensrv()
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-06-30 00:07:03 UTC (rev 17924)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-06-30 00:35:56 UTC (rev 17925)
@@ -17,9 +17,12 @@
<depend package="laser_scan"/>
<depend package="pr2_mechanism_controllers"/>
<depend package="image_msgs" />
-
+ <depend package="mechanism_msgs" />
+ <depend package="message_filters" />
+ <depend package="calibration_msgs" />
+
<export>
- <cpp cflags="-I${prefix}/msg/cpp"/>
+ <cpp cflags="-I${prefix}/msg/cpp -I${prefix}/srv/cpp -I{prefix}/include" />
</export>
</package>
Added: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/build_dense_laser_snapshot.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/build_dense_laser_snapshot.cpp (rev 0)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/build_dense_laser_snapshot.cpp 2009-06-30 00:35:56 UTC (rev 17925)
@@ -0,0 +1,160 @@
+/*********************************************************************
+* 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 "dense_laser_assembler/build_dense_laser_snapshot.h"
+
+using namespace std ;
+using namespace boost ;
+
+namespace dense_laser_assembler
+{
+
+bool verifyMetadata(const calibration_msgs::DenseLaserSnapshot& snapshot, const laser_scan::LaserScan& scan) ;
+
+bool buildDenseLaserSnapshot(const vector<shared_ptr<const JointTaggedLaserScan> >& scans,
+ const vector<string>& joint_names,
+ calibration_msgs::DenseLaserSnapshot& snapshot)
+{
+ if (scans.size() == 0)
+ {
+ ROS_WARN("Trying to build empty cloud") ;
+ snapshot.angle_min = 0.0 ;
+ snapshot.angle_max = 0.0 ;
+ snapshot.angle_increment = 0.0 ;
+ snapshot.time_increment = 0.0 ;
+ snapshot.range_min = 0.0 ;
+ snapshot.range_max = 0.0 ;
+ snapshot.readings_per_scan = 0 ;
+ snapshot.num_scans = 0 ;
+ snapshot.ranges.clear() ;
+ snapshot.intensities.clear() ;
+ snapshot.joint_encoding = 0 ;
+ snapshot.joint_names.clear() ;
+ snapshot.joint_positions.clear() ;
+ //snapshot.scan_start.clear() ;
+ return true ;
+ }
+
+ snapshot.header.stamp = scans[scans.size()-1]->scan->header.stamp ;
+
+ // Fill in all the metadata
+ snapshot.header.frame_id = scans[0]->scan->header.frame_id ;
+ snapshot.angle_min = scans[0]->scan->angle_min ;
+ snapshot.angle_max = scans[0]->scan->angle_max ;
+ snapshot.angle_increment = scans[0]->scan->angle_increment ;
+ snapshot.time_increment = scans[0]->scan->time_increment ;
+ snapshot.range_min = scans[0]->scan->range_min ;
+ snapshot.range_max = scans[0]->scan->range_max ;
+
+ // Define the data dimensions
+ snapshot.readings_per_scan = scans[0]->scan->ranges.size() ;
+ snapshot.num_scans = scans.size() ;
+ const unsigned int& w = snapshot.readings_per_scan ;
+ const unsigned int& h = snapshot.num_scans ;
+
+ // Do a consistency check on the metadata
+ for (unsigned int i=0; i<scans.size(); i++)
+ {
+ if (!verifyMetadata(snapshot, *scans[i]->scan))
+ {
+ ROS_WARN("Metadata doesn't match") ;
+ return false ;
+ }
+ }
+
+ // Set up joint data vectors
+ const unsigned int num_joints = joint_names.size() ;
+ snapshot.joint_names = joint_names ;
+ snapshot.joint_encoding = calibration_msgs::DenseLaserSnapshot::POS_PER_ROW_START_AND_END ;
+ snapshot.joint_positions.resize(num_joints*h*2) ; // 2 Positions per joint per row (beginning and end of row)
+
+ // Set up other data vectors
+ //snapshot.scan_start.resize(h) ;
+ snapshot.ranges.resize(w*h) ;
+ snapshot.intensities.resize(w*h) ;
+
+ const unsigned int range_elem_size = sizeof(scans[0]->scan->ranges[0]) ;
+ const unsigned int intensity_elem_size = sizeof(scans[0]->scan->intensities[0]) ;
+
+ for (unsigned int i=0; i<h; i++)
+ {
+ memcpy(&snapshot.ranges[i*w], &scans[i]->scan->ranges[0], w*range_elem_size) ;
+ memcpy(&snapshot.intensities[i*w], &scans[i]->scan->intensities[0], w*intensity_elem_size) ;
+
+ // Copy joint positions
+ for (unsigned int j=0; j<num_joints; j++)
+ {
+ snapshot.joint_positions[i*j*2 + 0] = scans[i]->before->positions[j] ;
+ snapshot.joint_positions[i*j*2 + 1] = scans[i]->after->positions[j] ;
+ }
+
+ // Copy time stamp
+ //snapshot.scan_start[i] = scans[i]->header.stamp ;
+ }
+
+ ROS_INFO("Done building snapshot that is [%u rows] x [%u cols]\n", h, w) ;
+
+ return true ;
+}
+
+static const double eps = 1e-9 ;
+
+#define CHECK(a) \
+{ \
+ if ( (snapshot.a - scan.a < -eps) || (snapshot.a - scan.a > eps)) \
+ return false ; \
+}
+
+bool verifyMetadata(const calibration_msgs::DenseLaserSnapshot& snapshot, const laser_scan::LaserScan& scan)
+{
+ CHECK(angle_min) ;
+ CHECK(angle_max) ;
+ CHECK(angle_increment) ;
+ CHECK(time_increment) ;
+ CHECK(range_min) ;
+ CHECK(range_max) ;
+
+ if (snapshot.header.frame_id.compare(scan.header.frame_id) != 0)
+ return false ;
+
+ if (snapshot.readings_per_scan != scan.ranges.size())
+ return false ;
+ if (snapshot.readings_per_scan != scan.intensities.size())
+ return false ;
+
+
+ return true ;
+}
+
+}
Added: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_assembler_srv.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_assembler_srv.cpp (rev 0)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_assembler_srv.cpp 2009-06-30 00:35:56 UTC (rev 17925)
@@ -0,0 +1,161 @@
+/*********************************************************************
+* 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.
+*********************************************************************/
+
+//! \author Vijay Pradeep / vpr...@wi...
+
+#include "ros/ros.h"
+#include "dense_laser_assembler/build_dense_laser_snapshot.h"
+#include "dense_laser_assembler/joint_extractor.h"
+#include "dense_laser_assembler/laser_scan_tagger.h"
+#include "message_filters/msg_cache.h"
+
+//#include "dense_laser_assembler/test_func.h"
+
+// Messages/Services
+#include "dense_laser_assembler/BuildLaserSnapshot.h"
+
+#define CONSTRUCT_INT(param, default_val) \
+ int param ;\
+ if (!n_.getParam("~" #param, param) ) \
+ { \
+ ROS_WARN("[~" #param "] not set. Setting to default value of [%u]", default_val) ; \
+ param = default_val ; \
+ } \
+ else \
+ { \
+ ROS_INFO("[~" #param "] set to value of [%u]", param) ; \
+ }
+
+using namespace dense_laser_assembler ;
+using namespace std ;
+
+class DenseLaserAssemblerSrv
+{
+public:
+ DenseLaserAssemblerSrv()
+ {
+ CONSTRUCT_INT(laser_queue_size, 40) ;
+ CONSTRUCT_INT(laser_cache_size, 1000) ;
+ CONSTRUCT_INT(mech_state_cache_size, 100) ;
+
+ bool found_joint = true ;
+ int joint_count = 0 ;
+
+ char param_buf[1024] ;
+ while(found_joint)
+ {
+ sprintf(param_buf, "~joint_name_%02u", joint_count) ;
+ string param_name = param_buf ;
+ string cur_joint_name ;
+ found_joint = n_.getParam(param_name, cur_joint_name) ;
+ if (found_joint)
+ {
+ ROS_INFO("[%s] -> %s\n", param_name.c_str(), cur_joint_name.c_str()) ;
+ joint_names_.push_back(cur_joint_name) ;
+ }
+ }
+
+
+ // Configure the joint extractor
+ joint_extractor_.setJointNames(joint_names_) ;
+ joint_cache_.setCacheSize(mech_state_cache_size) ;
+ joint_cache_.subscribe(joint_extractor_) ;
+
+ // Set up the laser tagger (and link it to the joint_cache)
+ laser_tagger_.setTagCache(joint_cache_) ;
+ laser_tagger_.setQueueSize(laser_queue_size) ;
+
+ // Trigger laser_tagger off updates to the joint_cache
+ joint_cache_.addOutputCallback(boost::bind(&LaserJointTagger::update, &laser_tagger_)) ;
+
+ // Set up the cache for tagged laser scans (and link it to the laser_tagger)
+ tagged_laser_cache_.setCacheSize(laser_cache_size) ;
+ tagged_laser_cache_.subscribe(laser_tagger_) ;
+
+ // Link the joint extractor to a topic
+ mech_sub_ = n_.subscribe("mechanism_state", 1, &JointExtractor::processMechState, &joint_extractor_) ;
+
+ // Link the laser_tagger to a topic
+ laser_sub_ = n_.subscribe("tilt_scan", 1, &LaserJointTagger::processLaserScan, &laser_tagger_) ;
+
+ // Advertise services
+ snapshot_adv_ = n_.advertiseService("~build_laser_snapshot", &DenseLaserAssemblerSrv::buildLaserSnapshotSrv, this) ;
+ }
+
+ bool buildLaserSnapshotSrv(BuildLaserSnapshot::Request& req, BuildLaserSnapshot::Response& resp)
+ {
+ vector<boost::shared_ptr<const JointTaggedLaserScan> > scans = tagged_laser_cache_.getInterval(req.start, req.end) ;
+ bool success = true ;
+ success = buildDenseLaserSnapshot(scans, joint_names_, resp.snapshot) ;
+
+ /*printf("Displaying times:\n") ;
+ for (unsigned int i=0; i<resp.snapshot.scan_start.size(); i++)
+ {
+ printf(" %u: %f\n", i, resp.snapshot.scan_start[i].toSec()) ;
+ }*/
+
+ return success ;
+ }
+
+private:
+ ros::NodeHandle n_ ;
+ ros::Subscriber mech_sub_ ;
+ ros::Subscriber laser_sub_ ;
+ ros::ServiceServer snapshot_adv_ ;
+
+ //! Extracts positions data for a subset of joints in MechanismState
+ JointExtractor joint_extractor_ ;
+ //! Stores a time history of position data for a subset of joints in MechanismState
+ message_filters::MsgCache<JointExtractor::JointArray> joint_cache_ ;
+
+ //! Combines a laser scan with the set of pertinent joint positions
+ LaserJointTagger laser_tagger_ ;
+
+ //! Stores a time history of laser scans that are annotated with joint positions.
+ JointTaggedLaserScanCache tagged_laser_cache_ ;
+
+ vector<string> joint_names_ ;
+} ;
+
+
+
+
+int main(int argc, char** argv)
+{
+ ros::init(argc, argv, "dense_laser_assembler_srv") ;
+
+ DenseLaserAssemblerSrv assembler ;
+
+ ros::spin() ;
+}
Added: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_snapshotter.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_snapshotter.cpp (rev 0)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_snapshotter.cpp 2009-06-30 00:35:56 UTC (rev 17925)
@@ -0,0 +1,132 @@
+/*********************************************************************
+* 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/ros.h"
+
+// Services
+#include "dense_laser_assembler/BuildLaserSnapshot.h"
+
+// Messages
+#include "calibration_msgs/DenseLaserSnapshot.h"
+#include "pr2_mechanism_controllers/LaserScannerSignal.h"
+
+
+using namespace dense_laser_assembler ;
+
+class DenseLaserSnapshotter
+{
+
+public:
+
+ DenseLaserSnapshotter()
+ {
+ prev_signal_.header.stamp.fromNSec(0) ;
+
+ snapshot_pub_ = n_.advertise<calibration_msgs::DenseLaserSnapshot> ("dense_laser_snapshot", 1) ;
+ signal_sub_ = n_.subscribe("laser_scanner_signal", 40, &DenseLaserSnapshotter::scannerSignalCallback, this) ;
+
+ first_time_ = true ;
+ }
+
+ ~DenseLaserSnapshotter()
+ {
+
+ }
+
+ void scannerSignalCallback(const pr2_mechanism_controllers::LaserScannerSignalConstPtr& cur_signal)
+ {
+ if (cur_signal->signal == 128 || cur_signal->signal == 129) // These codes imply that this is the first signal during a given profile type
+ first_time_ = true ;
+
+
+ if (first_time_)
+ {
+ prev_signal_ = *cur_signal ;
+ first_time_ = false ;
+ }
+ else
+ {
+ printf("About to make request\n") ;
+
+ BuildLaserSnapshot::Request req ;
+ BuildLaserSnapshot::Response resp ;
+
+ req.start = prev_signal_.header.stamp ;
+ req.end = cur_signal->header.stamp ;
+
+
+
+ if (!ros::service::call("dense_laser_assembler_srv/build_laser_snapshot", req, resp))
+ ROS_ERROR("Failed to call service on dense laser assembler.");
+
+ printf("Displaying Data") ;
+ printf("header.stamp: %f\n", resp.snapshot.header.stamp.toSec()) ;
+ printf("header.frame_id: %s", resp.snapshot.header.frame_id.c_str()) ;
+ printf("ranges.size()=%u\n", resp.snapshot.ranges.size()) ;
+ printf("intensities.size()=%u\n", resp.snapshot.intensities.size()) ;
+ printf("joint_positions.size()=%u\n", resp.snapshot.joint_positions.size()) ;
+ //printf("scan_start.size()=%u\n", resp.snapshot.scan_start.size()) ;
+
+ /*printf("Displaying times:\n") ;
+ for (unsigned int i=0; i<resp.snapshot.scan_start.size(); i++)
+ {
+ printf(" %u: %f\n", i, resp.snapshot.scan_start[i].toSec()) ;
+ }*/
+
+ /*printf("About to publish\n") ;
+ snapshot_pub_.publish(resp.snapshot) ;
+ printf("Done publishing\n") ;*/
+
+ prev_signal_ = *cur_signal ;
+ }
+ }
+
+private:
+ ros::NodeHandle n_ ;
+ ros::Subscriber signal_sub_ ;
+ ros::Publisher snapshot_pub_ ;
+
+ pr2_mechanism_controllers::LaserScannerSignal prev_signal_;
+
+ bool first_time_ ;
+} ;
+
+int main(int argc, char **argv)
+{
+ ros::init(argc, argv, "dense_laser_snapshotter") ;
+ DenseLaserSnapshotter snapshotter ;
+ ros::spin() ;
+
+ return 0;
+}
Copied: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/joint_extractor_display.cpp (from rev 17924, pkg/trunk/sandbox/message_filters/src/sync_test.cpp)
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/joint_extractor_display.cpp (rev 0)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/joint_extractor_display.cpp 2009-06-30 00:35:56 UTC (rev 17925)
@@ -0,0 +1,78 @@
+/*********************************************************************
+* 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.
+*********************************************************************/
+
+/*! \mainpage
+ * \htmlinclude manifest.html
+ */
+
+#include "ros/ros.h"
+#include "dense_laser_assembler/joint_extractor.h"
+
+using namespace std ;
+//using namespace message_filters ;
+using namespace dense_laser_assembler ;
+
+
+
+void display_joints(vector<string> joint_names, const boost::shared_ptr<JointExtractor::JointArray const>& joint_array_ptr)
+{
+ printf("Joints:\n") ;
+ for (unsigned int i=0; i< joint_names.size(); i++)
+ {
+ printf(" %s: %f\n", joint_names[i].c_str(), joint_array_ptr->positions[i]) ;
+ }
+
+}
+
+int main(int argc, char** argv)
+{
+ ros::init(argc, argv, "joint_extractor_display") ;
+
+ ros::NodeHandle nh ;
+
+ vector<string> joint_names ;
+ joint_names.push_back("laser_tilt_mount_joint") ;
+ joint_names.push_back("torso_lift_link") ;
+
+ JointExtractor joint_extractor(joint_names) ;
+
+ joint_extractor.addOutputCallback(boost::bind(&display_joints, joint_names, _1) ) ;
+
+ ros::Subscriber sub = nh.subscribe("mechanism_state", 1, &JointExtractor::processMechState, &joint_extractor) ;
+
+ ros::spin() ;
+
+
+ return 0 ;
+}
Added: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/tagged_laser_cache_display.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/tagged_laser_cache_display.cpp (rev 0)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/tagged_laser_cache_display.cpp 2009-06-30 00:35:56 UTC (rev 17925)
@@ -0,0 +1,106 @@
+/*********************************************************************
+* 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 p...
[truncated message content] |
|
From: <tf...@us...> - 2009-06-30 02:34:34
|
Revision: 17938
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17938&view=rev
Author: tfoote
Date: 2009-06-30 02:30:45 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
moving LaserScan from laser_scan package to sensor_msgs package #1254
Modified Paths:
--------------
pkg/trunk/calibration/laser_camera_calibration/gatherdata.py
pkg/trunk/calibration/laser_camera_calibration/manifest.xml
pkg/trunk/calibration/laser_cb_processing/manifest.xml
pkg/trunk/calibration/laser_cb_processing/src/laser_cb_processing.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp
pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml
pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg
pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/scripts/assembler_node.py
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h
pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp
pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_scan.py
pkg/trunk/mapping/door_tracker/manifest.xml
pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
pkg/trunk/mapping/hallway_tracker/manifest.xml
pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
pkg/trunk/nav/amcl/manifest.xml
pkg/trunk/nav/amcl/src/amcl_node.cpp
pkg/trunk/nav/base_local_planner/include/base_local_planner/trajectory_planner_ros.h
pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp
pkg/trunk/nav/wavefront/manifest.xml
pkg/trunk/nav/wavefront/src/wavefront_node.cpp
pkg/trunk/stacks/common/laser_scan/CMakeLists.txt
pkg/trunk/stacks/common/laser_scan/include/laser_scan/footprint_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/intensity_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_processor.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/laser_scan.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/median_filter.h
pkg/trunk/stacks/common/laser_scan/include/laser_scan/scan_shadows_filter.h
pkg/trunk/stacks/common/laser_scan/manifest.xml
pkg/trunk/stacks/common/laser_scan/src/generic_laser_filter_node.cpp
pkg/trunk/stacks/common/laser_scan/src/laser_processor.cpp
pkg/trunk/stacks/common/laser_scan/src/laser_scan.cc
pkg/trunk/stacks/common/laser_scan/src/scan_shadows_filter.cpp
pkg/trunk/stacks/common/laser_scan/src/scan_to_cloud.cpp
pkg/trunk/stacks/common/laser_scan/test/projection_test.cpp
pkg/trunk/stacks/laser_drivers/hokuyo_node/manifest.xml
pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp
pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/manifest.xml
pkg/trunk/stacks/laser_drivers/sicktoolbox_wrapper/ros/sicklms/sicklms.cpp
pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.cpp
pkg/trunk/stacks/map_building/slam_gmapping/src/slam_gmapping.h
pkg/trunk/stacks/map_building/slam_gmapping/src/tftest.cpp
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/manifest.xml
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/laser_scan_assembler_srv.cpp
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_assembler_srv.cpp
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/test/test_assembler.cpp
pkg/trunk/stacks/simulators/stage/manifest.xml
pkg/trunk/stacks/simulators/stage/src/stageros.cpp
pkg/trunk/stacks/visualization/rviz/manifest.xml
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/laser_scan_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/laser_scan_display.h
pkg/trunk/stacks/world_models/costmap_2d/include/costmap_2d/costmap_2d_ros.h
pkg/trunk/stacks/world_models/costmap_2d/manifest.xml
pkg/trunk/stacks/world_models/costmap_2d/src/costmap_2d_ros.cpp
pkg/trunk/stacks/world_models/costmap_2d/src/costmap_test.cpp
pkg/trunk/util/logsetta/carmen/carmen_logger/carmen_logger.cpp
pkg/trunk/util/logsetta/carmen/genlog_carmen/genlog_carmen.cpp
pkg/trunk/util/logsetta/laser/laser_extract.cpp
pkg/trunk/util/logsetta/manifest.xml
pkg/trunk/vision/people/manifest.xml
pkg/trunk/vision/people/src/calc_leg_features.cpp
pkg/trunk/vision/people/src/calc_leg_features.h
pkg/trunk/vision/people/src/leg_detector.cpp
pkg/trunk/vision/people/src/train_leg_detector.cpp
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/LaserScan.msg
Removed Paths:
-------------
pkg/trunk/stacks/common/laser_scan/msg/LaserScan.msg
Modified: pkg/trunk/calibration/laser_camera_calibration/gatherdata.py
===================================================================
--- pkg/trunk/calibration/laser_camera_calibration/gatherdata.py 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/laser_camera_calibration/gatherdata.py 2009-06-30 02:30:45 UTC (rev 17938)
@@ -46,7 +46,7 @@
import rospy
from roslib import rostime
-from laser_scan.msg import LaserScan
+from sensor_msgs.msg import LaserScan
from mechanism_msgs.msg import MechanismState
from checkerboard_detector.msg import ObjectDetection
import copy
Modified: pkg/trunk/calibration/laser_camera_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/laser_camera_calibration/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/laser_camera_calibration/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -11,7 +11,7 @@
<review status="unreviewed" notes=""/>
<depend package="robot_msgs"/>
<depend package="std_msgs"/>
- <depend package="laser_scan"/>
+ <depend package="sensor_msgs"/>
<depend package="rospy"/>
<depend package="rosoct"/>
<depend package="openraveros"/>
Modified: pkg/trunk/calibration/laser_cb_processing/manifest.xml
===================================================================
--- pkg/trunk/calibration/laser_cb_processing/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/laser_cb_processing/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -10,7 +10,7 @@
<depend package="topic_synchronizer" />
<depend package="robot_msgs" />
<depend package="opencv_latest" />
- <depend package="laser_scan" />
+ <depend package="sensor_msgs" />
<depend package="dense_laser_assembler" />
<!-- For the pr2 tilt-laser projector -->
Modified: pkg/trunk/calibration/laser_cb_processing/src/laser_cb_processing.cpp
===================================================================
--- pkg/trunk/calibration/laser_cb_processing/src/laser_cb_processing.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/laser_cb_processing/src/laser_cb_processing.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -38,7 +38,7 @@
#include "dense_laser_assembler/Float32MultiArrayStamped.h"
#include "robot_msgs/PointCloud.h"
#include "robot_msgs/Point32.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "topic_synchronizer/topic_synchronizer.h"
@@ -162,7 +162,7 @@
}
- inline float pointingAngle(const laser_scan::LaserScan& info, const float& ray)
+ inline float pointingAngle(const sensor_msgs::LaserScan& info, const float& ray)
{
return info.angle_min + info.angle_increment * ray;
}
@@ -198,7 +198,7 @@
robot_msgs::PointCloud pixel_corners_;
dense_laser_assembler::Float32MultiArrayStamped dense_range_;
dense_laser_assembler::Float32MultiArrayStamped joint_info_;
- laser_scan::LaserScan scan_info_;
+ sensor_msgs::LaserScan scan_info_;
};
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -39,7 +39,7 @@
#include "tf/tfMessage.h"
#include "tf/transform_datatypes.h"
#include "mechanism_msgs/MechanismState.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "image_msgs/RawStereo.h"
class LaserHeadKinematics
@@ -57,7 +57,7 @@
this) ;
// Tilt Scan Updates
- laser_pub_ = nh.advertise<laser_scan::LaserScan>("tilt_scan_cal", 100) ;
+ laser_pub_ = nh.advertise<sensor_msgs::LaserScan>("tilt_scan_cal", 100) ;
laser_sub_ = nh.subscribe("tilt_scan", 100,
&LaserHeadKinematics::updateTiltScan, this) ;
@@ -75,9 +75,9 @@
stereo_pub_.publish(msg_out) ;
}
- void updateTiltScan(const laser_scan::LaserScanConstPtr& msg_in)
+ void updateTiltScan(const sensor_msgs::LaserScanConstPtr& msg_in)
{
- laser_scan::LaserScan msg_out ;
+ sensor_msgs::LaserScan msg_out ;
msg_out = *msg_in ;
msg_out.header.frame_id = "laser_tilt_link_cal" ;
laser_pub_.publish(msg_out) ;
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -39,7 +39,7 @@
#include "tf/tfMessage.h"
#include "tf/transform_datatypes.h"
#include "mechanism_msgs/MechanismState.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "image_msgs/RawStereo.h"
class LaserHeadKinematics
@@ -57,7 +57,7 @@
this) ;
// Tilt Scan Updates
- laser_pub_ = nh.advertise<laser_scan::LaserScan>("tilt_scan_cal", 100) ;
+ laser_pub_ = nh.advertise<sensor_msgs::LaserScan>("tilt_scan_cal", 100) ;
laser_sub_ = nh.subscribe("tilt_scan", 100,
&LaserHeadKinematics::updateTiltScan, this) ;
@@ -76,9 +76,9 @@
stereo_pub_.publish(msg_out) ;
}
- void updateTiltScan(const laser_scan::LaserScanConstPtr& msg_in)
+ void updateTiltScan(const sensor_msgs::LaserScanConstPtr& msg_in)
{
- laser_scan::LaserScan msg_out ;
+ sensor_msgs::LaserScan msg_out ;
msg_out = *msg_in ;
msg_out.header.frame_id = "laser_tilt_link_cal" ;
laser_pub_.publish(msg_out) ;
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -39,7 +39,7 @@
#include "tf/tfMessage.h"
#include "tf/transform_datatypes.h"
#include "mechanism_msgs/MechanismState.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "image_msgs/RawStereo.h"
class LaserHeadKinematics
@@ -57,7 +57,7 @@
this) ;
// Tilt Scan Updates
- laser_pub_ = nh.advertise<laser_scan::LaserScan>("tilt_scan_cal", 100) ;
+ laser_pub_ = nh.advertise<sensor_msgs::LaserScan>("tilt_scan_cal", 100) ;
laser_sub_ = nh.subscribe("tilt_scan", 100,
&LaserHeadKinematics::updateTiltScan, this) ;
@@ -76,9 +76,9 @@
stereo_pub_.publish(msg_out) ;
}
- void updateTiltScan(const laser_scan::LaserScanConstPtr& msg_in)
+ void updateTiltScan(const sensor_msgs::LaserScanConstPtr& msg_in)
{
- laser_scan::LaserScan msg_out ;
+ sensor_msgs::LaserScan msg_out ;
msg_out = *msg_in ;
msg_out.header.frame_id = "laser_tilt_link_cal" ;
laser_pub_.publish(msg_out) ;
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -6,7 +6,7 @@
<license>BSD</license>
<review status="experimental" notes=""/>
<url>http://pr.willowgarage.com</url>
-<depend package="laser_scan"/>
+<depend package="sensor_msgs"/>
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="roscpp"/>
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/msg/LaserScanAnnotated.msg 2009-06-30 02:30:45 UTC (rev 17938)
@@ -1,2 +1,2 @@
-laser_scan/LaserScan scan # The original laser scan
+sensor_msgs/LaserScan scan # The original laser scan
robot_msgs/PoseStamped[] poses # The pose during each ray of the laserscan
\ No newline at end of file
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -28,14 +28,13 @@
*/
#include "ros/node.h"
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "tf/transform_listener.h"
#include "tf/message_notifier.h"
#include "laser_scan_annotator/LaserScanAnnotated.h"
#include "boost/thread.hpp"
using namespace std ;
-using namespace laser_scan ;
namespace laser_scan_annotator
{
@@ -105,7 +104,7 @@
}
protected:
- laser_scan::LaserScan scan_in_ ;
+ sensor_msgs::LaserScan scan_in_ ;
string fixed_frame_ ;
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -14,7 +14,7 @@
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
<depend package="mechanism_msgs" />
- <depend package="laser_scan"/>
+ <depend package="sensor_msgs"/>
<depend package="pr2_mechanism_controllers"/>
<depend package="image_msgs" />
<depend package="mechanism_msgs" />
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/scripts/assembler_node.py
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/scripts/assembler_node.py 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/scripts/assembler_node.py 2009-06-30 02:30:45 UTC (rev 17938)
@@ -39,7 +39,7 @@
import rospy
import threading
from time import sleep
-from laser_scan.msg import *
+from sensor_msgs.msg import LaserScan
from robot_msgs.msg import *
from mechanism_msgs.msg import MechanismState
from std_msgs.msg import *
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_laser.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -32,7 +32,7 @@
#include <ros/ros.h>
#include <boost/thread/mutex.hpp>
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
namespace gazebo
{
@@ -45,7 +45,7 @@
\brief ROS Laser Scanner Controller Plugin
This controller gathers range data from a simulated ray sensor, publishes range data through
- laser_scan::LaserScan ROS topic.
+ sensor_msgs::LaserScan ROS topic.
Example Usage:
\verbatim
@@ -81,7 +81,7 @@
/**
\brief ROS laser scan controller.
\li Starts a ROS node if none exists.
- \li Simulates a laser range sensor and publish laser_scan::LaserScan.msg over ROS.
+ \li Simulates a laser range sensor and publish sensor_msgs::LaserScan.msg over ROS.
\li Example Usage:
\verbatim
<model:physical name="ray_model">
@@ -145,7 +145,7 @@
private: ros::Publisher pub_;
/// \brief ros message
- private: laser_scan::LaserScan laserMsg;
+ private: sensor_msgs::LaserScan laserMsg;
/// \brief topic name
private: std::string topicName;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -19,7 +19,7 @@
<depend package="mechanism_msgs" />
<depend package="image_msgs" />
<depend package="opencv_latest" />
- <depend package="laser_scan" />
+ <depend package="sensor_msgs" />
<depend package="pr2_msgs" />
<depend package="robot_msgs" />
<depend package="diagnostic_msgs" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_laser.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -81,7 +81,7 @@
{
this->topicName = node->GetString("topicName","default_ros_laser",0); //read from xml file
ROS_DEBUG("================= %s", this->topicName.c_str());
- this->pub_ = this->rosnode_->advertise<laser_scan::LaserScan>(this->topicName,10);
+ this->pub_ = this->rosnode_->advertise<sensor_msgs::LaserScan>(this->topicName,10);
this->frameName = node->GetString("frameName","default_ros_laser",0); //read from xml file
this->gaussianNoise = node->GetDouble("gaussianNoise",0.0,0); //read from xml file
}
Modified: pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_scan.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_scan.py 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_scan.py 2009-06-30 02:30:45 UTC (rev 17938)
@@ -46,7 +46,7 @@
import sys, unittest
import os, os.path, threading, time
import rospy, rostest
-from laser_scan.msg import *
+from sensor_msgs.msg import LaserScan
TEST_DURATION = 15
ERROR_TOL = 0.05
Modified: pkg/trunk/mapping/door_tracker/manifest.xml
===================================================================
--- pkg/trunk/mapping/door_tracker/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/mapping/door_tracker/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -10,6 +10,8 @@
<depend package="eigen" />
<depend package="roscpp" />
+ <depend package="laser_scan" />
+ <depend package="sensor_msgs" />
<depend package="robot_msgs" />
<depend package="door_msgs" />
<depend package="robot_srvs" />
Modified: pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
===================================================================
--- pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -80,7 +80,7 @@
#include <sys/time.h>
// Clouds and scans
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
#include <laser_scan/laser_scan.h>
//Filters
@@ -109,7 +109,7 @@
tf::TransformListener *tf_;
- tf::MessageNotifier<laser_scan::LaserScan>* message_notifier_;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* message_notifier_;
door_msgs::Door door_msg_;
@@ -121,7 +121,7 @@
bool active_;
- filters::FilterChain<laser_scan::LaserScan> filter_chain_;
+ filters::FilterChain<sensor_msgs::LaserScan> filter_chain_;
tf::Stamped<tf::Pose> global_pose_;
@@ -352,7 +352,7 @@
node_->advertise<door_msgs::Door>( "~door_message", 0 );
node_->advertiseService ("~doors_detector", &DoorTracker::detectDoorService, this);
- message_notifier_ = new tf::MessageNotifier<laser_scan::LaserScan> (tf_, node_, boost::bind(&DoorTracker::laserCallBack, this, _1), base_laser_topic_.c_str (), fixed_frame_, 1);
+ message_notifier_ = new tf::MessageNotifier<sensor_msgs::LaserScan> (tf_, node_, boost::bind(&DoorTracker::laserCallBack, this, _1), base_laser_topic_.c_str (), fixed_frame_, 1);
message_notifier_->setTolerance(ros::Duration(.02));
active_ = true;
}
@@ -406,7 +406,7 @@
- void laserCallBack(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& scan_msg)
+ void laserCallBack(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& scan_msg)
{
if(!active_)
return;
@@ -417,7 +417,7 @@
cloud_msg_mutex_.lock();
done_detection_ = false;
- laser_scan::LaserScan filtered_scan;
+ sensor_msgs::LaserScan filtered_scan;
filter_chain_.update (*scan_msg, filtered_scan);
// Transform into a PointCloud message
int mask = laser_scan::MASK_INTENSITY | laser_scan::MASK_DISTANCE | laser_scan::MASK_INDEX | laser_scan::MASK_TIMESTAMP;
Modified: pkg/trunk/mapping/hallway_tracker/manifest.xml
===================================================================
--- pkg/trunk/mapping/hallway_tracker/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/mapping/hallway_tracker/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -14,6 +14,7 @@
<depend package="kdl" />
<depend package="point_cloud_mapping" />
<depend package="std_msgs" />
+ <depend package="sensor_msgs" />
<depend package="laser_scan" />
<depend package="filters" />
<depend package="visualization_msgs" />
Modified: pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
===================================================================
--- pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -75,7 +75,7 @@
// Clouds and scans
#include <robot_msgs/PointCloud.h>
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
#include <laser_scan/laser_scan.h>
@@ -104,8 +104,8 @@
laser_scan::LaserProjection projector_; // Used to project laser scans into point clouds
tf::TransformListener *tf_;
- tf::MessageNotifier<laser_scan::LaserScan>* message_notifier_;
- filters::FilterChain<laser_scan::LaserScan> filter_chain_;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* message_notifier_;
+ filters::FilterChain<sensor_msgs::LaserScan> filter_chain_;
/********** Parameters from the param server *******/
std::string base_laser_topic_; // Topic for the laser scan message.
@@ -156,7 +156,7 @@
node_->advertise<robot_msgs::PointCloud>("parallel_lines_model",0);
// Subscribe to the scans.
- message_notifier_ = new tf::MessageNotifier<laser_scan::LaserScan> (tf_, node_, boost::bind(&HallwayTracker::laserCallBack, this, _1), base_laser_topic_.c_str(), fixed_frame_, 1);
+ message_notifier_ = new tf::MessageNotifier<sensor_msgs::LaserScan> (tf_, node_, boost::bind(&HallwayTracker::laserCallBack, this, _1), base_laser_topic_.c_str(), fixed_frame_, 1);
message_notifier_->setTolerance(ros::Duration(.02));
}
@@ -170,9 +170,9 @@
/**
* \brief Laser callback. Processes a laser scan by converting it into a point cloud, removing points that are too far away, finding two parallel lines and publishing the results.
*/
- void laserCallBack(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& scan_msg)
+ void laserCallBack(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& scan_msg)
{
- laser_scan::LaserScan filtered_scan;
+ sensor_msgs::LaserScan filtered_scan;
filter_chain_.update (*scan_msg, filtered_scan);
Modified: pkg/trunk/nav/amcl/manifest.xml
===================================================================
--- pkg/trunk/nav/amcl/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/amcl/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -12,8 +12,8 @@
<depend package="nav_msgs" />
<depend package="nav_srvs" />
<depend package="std_srvs" />
- <depend package="laser_scan" />
<depend package="visualization_msgs"/>
+ <depend package="sensor_msgs" />
<!-- For tests -->
<depend package="map_server"/>
Modified: pkg/trunk/nav/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -61,7 +61,7 @@
@section topic ROS topics
Subscribes to (name type):
-- @b "scan" laser_scan/LaserScan : laser scans
+- @b "scan" sensor_msgs/LaserScan : laser scans
- @b "tf_message" tf/tfMessage : transforms
Publishes to (name type):
@@ -156,7 +156,7 @@
#include "ros/node.h"
// Messages that I need
-#include "laser_scan/LaserScan.h"
+#include "sensor_msgs/LaserScan.h"
#include "robot_msgs/PoseWithCovariance.h"
#include "nav_msgs/ParticleCloud.h"
#include "robot_msgs/Pose.h"
@@ -231,7 +231,7 @@
// Message callbacks
bool globalLocalizationCallback(std_srvs::Empty::Request& req,
std_srvs::Empty::Response& res);
- void laserReceived(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& laser_scan);
+ void laserReceived(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& laser_scan);
void initialPoseReceived();
double getYaw(tf::Pose& t);
@@ -254,7 +254,7 @@
double resolution;
bool have_laser_pose;
- tf::MessageNotifier<laser_scan::LaserScan>* laser_scan_notifer;
+ tf::MessageNotifier<sensor_msgs::LaserScan>* laser_scan_notifer;
// Particle filter
pf_t *pf_;
@@ -446,7 +446,7 @@
&AmclNode::globalLocalizationCallback,
this);
laser_scan_notifer =
- new tf::MessageNotifier<laser_scan::LaserScan>
+ new tf::MessageNotifier<sensor_msgs::LaserScan>
(tf_, ros::Node::instance(),
boost::bind(&AmclNode::laserReceived,
this, _1),
@@ -578,7 +578,7 @@
}
void
-AmclNode::laserReceived(const tf::MessageNotifier<laser_scan::LaserScan>::MessagePtr& laser_scan)
+AmclNode::laserReceived(const tf::MessageNotifier<sensor_msgs::LaserScan>::MessagePtr& laser_scan)
{
// Do we have the base->base_laser Tx yet?
if(!have_laser_pose)
Modified: pkg/trunk/nav/base_local_planner/include/base_local_planner/trajectory_planner_ros.h
===================================================================
--- pkg/trunk/nav/base_local_planner/include/base_local_planner/trajectory_planner_ros.h 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/base_local_planner/include/base_local_planner/trajectory_planner_ros.h 2009-06-30 02:30:45 UTC (rev 17938)
@@ -56,10 +56,8 @@
#include <robot_msgs/PoseDot.h>
#include <robot_msgs/Point.h>
-#include <laser_scan/LaserScan.h>
#include <tf/message_notifier.h>
#include <tf/transform_listener.h>
-#include <laser_scan/laser_scan.h>
#include <boost/thread.hpp>
Modified: pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp
===================================================================
--- pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -44,7 +44,6 @@
using namespace std;
using namespace robot_msgs;
using namespace costmap_2d;
-using namespace laser_scan;
namespace base_local_planner {
//register this base local planner with the BaseLocalPlanner factory
Modified: pkg/trunk/nav/wavefront/manifest.xml
===================================================================
--- pkg/trunk/nav/wavefront/manifest.xml 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/wavefront/manifest.xml 2009-06-30 02:30:45 UTC (rev 17938)
@@ -6,6 +6,7 @@
<depend package="roscpp" />
<depend package="laser_scan" />
<depend package="nav_srvs" />
+ <depend package="sensor_msgs" />
<depend package="robot_msgs" />
<depend package="robot_actions" />
<depend package="nav_robot_actions" />
Modified: pkg/trunk/nav/wavefront/src/wavefront_node.cpp
===================================================================
--- pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-06-30 02:23:50 UTC (rev 17937)
+++ pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-06-30 02:30:45 UTC (rev 17938)
@@ -63,7 +63,7 @@
Subscribes to (name/type):
- @b "tf_message" tf/tfMessage: robot's pose in the "map" frame
- @b "goal" robot_msgs/PoseStamped : goal for the robot.
-- @b "scan" laser_scan/LaserScan : laser scans. Used to temporarily modify the map for dynamic obstacles.
+- @b "scan" sensor_msgs/LaserScan : laser scans. Used to temporarily modify the map for dynamic obstacles.
Publishes to (name / type):
- @b "cmd_vel" robot_msgs/PoseDot : velocity commands to robot
@@ -105,7 +105,7 @@
#include <robot_msgs/PoseStamped.h>
#include <robot_msgs/PoseDot.h>
#include <robot_msgs/PointCloud.h>
-#include <laser_scan/LaserScan.h>
+#include <sensor_msgs/LaserScan.h>
#include <nav_srvs/StaticMap.h>
//...
[truncated message content] |
|
From: <is...@us...> - 2009-06-30 03:49:04
|
Revision: 17945
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17945&view=rev
Author: isucan
Date: 2009-06-30 03:49:01 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
moving tabletop messages
Modified Paths:
--------------
pkg/trunk/demos/tabletop_manipulation/manifest.xml
pkg/trunk/mapping/collision_map/manifest.xml
pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
pkg/trunk/mapping/table_object_detector/manifest.xml
pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp
pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/manifest.xml
pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/tabletop_msgs/
pkg/trunk/stacks/common_msgs/tabletop_msgs/CMakeLists.txt
pkg/trunk/stacks/common_msgs/tabletop_msgs/Makefile
pkg/trunk/stacks/common_msgs/tabletop_msgs/mainpage.dox
pkg/trunk/stacks/common_msgs/tabletop_msgs/manifest.xml
pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/
pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/AttachedObject.msg
pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/ObjectOnTable.msg
pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/Table.msg
pkg/trunk/stacks/common_msgs/tabletop_srvs/
pkg/trunk/stacks/common_msgs/tabletop_srvs/CMakeLists.txt
pkg/trunk/stacks/common_msgs/tabletop_srvs/Makefile
pkg/trunk/stacks/common_msgs/tabletop_srvs/mainpage.dox
pkg/trunk/stacks/common_msgs/tabletop_srvs/manifest.xml
pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/
pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/FindTable.srv
pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/RecordStaticMapTrigger.srv
pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/SubtractObjectFromCollisionMap.srv
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_msgs/msg/AttachedObject.msg
pkg/trunk/stacks/common_msgs/robot_msgs/msg/ObjectOnTable.msg
pkg/trunk/stacks/common_msgs/robot_msgs/msg/Table.msg
pkg/trunk/stacks/common_msgs/robot_srvs/srv/FindTable.srv
pkg/trunk/stacks/common_msgs/robot_srvs/srv/RecordStaticMapTrigger.srv
pkg/trunk/stacks/common_msgs/robot_srvs/srv/SubtractObjectFromCollisionMap.srv
Modified: pkg/trunk/demos/tabletop_manipulation/manifest.xml
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/manifest.xml 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/demos/tabletop_manipulation/manifest.xml 2009-06-30 03:49:01 UTC (rev 17945)
@@ -19,6 +19,8 @@
<depend package="manipulation_msgs" />
<depend package="motion_planning_msgs" />
<depend package="motion_planning_srvs" />
+ <depend package="tabletop_msgs" />
+ <depend package="tabletop_srvs" />
<depend package="move_base" />
<depend package="move_arm" />
<depend package="pr2_ik" />
Modified: pkg/trunk/mapping/collision_map/manifest.xml
===================================================================
--- pkg/trunk/mapping/collision_map/manifest.xml 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/mapping/collision_map/manifest.xml 2009-06-30 03:49:01 UTC (rev 17945)
@@ -14,6 +14,8 @@
<depend package="robot_msgs" />
<depend package="robot_srvs" />
<depend package="visualization_msgs" />
+ <depend package="tabletop_msgs" />
+ <depend package="tabletop_srvs" />
<depend package="point_cloud_mapping" />
<depend package="robot_self_filter" />
</package>
Modified: pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-06-30 03:49:01 UTC (rev 17945)
@@ -56,8 +56,8 @@
#include <robot_msgs/OrientedBoundingBox.h>
#include <robot_msgs/CollisionMap.h>
-#include <robot_srvs/RecordStaticMapTrigger.h>
-#include <robot_srvs/SubtractObjectFromCollisionMap.h>
+#include <tabletop_srvs/RecordStaticMapTrigger.h>
+#include <tabletop_srvs/SubtractObjectFromCollisionMap.h>
#include <tf/transform_listener.h>
#include <sys/time.h>
@@ -65,7 +65,7 @@
using namespace std;
using namespace robot_msgs;
using namespace robot_msgs;
-using namespace robot_srvs;
+using namespace tabletop_srvs;
using namespace visualization_msgs;
struct Leaf
Modified: pkg/trunk/mapping/table_object_detector/manifest.xml
===================================================================
--- pkg/trunk/mapping/table_object_detector/manifest.xml 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/mapping/table_object_detector/manifest.xml 2009-06-30 03:49:01 UTC (rev 17945)
@@ -14,5 +14,6 @@
<depend package="point_cloud_mapping" />
<depend package="robot_msgs" />
<depend package="robot_srvs" />
-
+ <depend package="tabletop_msgs" />
+ <depend package="tabletop_srvs" />
</package>
Modified: pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp
===================================================================
--- pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp 2009-06-30 03:49:01 UTC (rev 17945)
@@ -70,14 +70,15 @@
#include <sys/time.h>
-#include <robot_srvs/FindTable.h>
-#include <robot_msgs/Table.h>
-#include <robot_msgs/ObjectOnTable.h>
+#include <tabletop_srvs/FindTable.h>
+#include <tabletop_msgs/Table.h>
+#include <tabletop_msgs/ObjectOnTable.h>
using namespace std;
using namespace std_msgs;
using namespace robot_msgs;
-using namespace robot_srvs;
+using namespace tabletop_msgs;
+using namespace tabletop_srvs;
// Comparison operator for a vector of vectors
bool
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h 2009-06-30 03:49:01 UTC (rev 17945)
@@ -42,7 +42,7 @@
#include <tf/message_notifier.h>
#include <robot_msgs/CollisionMap.h>
-#include <robot_msgs/AttachedObject.h>
+#include <tabletop_msgs/AttachedObject.h>
#include <boost/thread/mutex.hpp>
@@ -147,7 +147,7 @@
void updateCollisionSpace(const robot_msgs::CollisionMapConstPtr &collisionMap, bool clear);
void collisionMapCallback(const robot_msgs::CollisionMapConstPtr &collisionMap);
void collisionMapUpdateCallback(const robot_msgs::CollisionMapConstPtr &collisionMap);
- void attachObjectCallback(const robot_msgs::AttachedObjectConstPtr &attachedObject);
+ void attachObjectCallback(const tabletop_msgs::AttachedObjectConstPtr &attachedObject);
CollisionModels *cm_;
collision_space::EnvironmentModel *collisionSpace_;
@@ -158,7 +158,7 @@
ros::Time lastMapUpdate_;
tf::MessageNotifier<robot_msgs::CollisionMap> *collisionMapNotifier_;
tf::MessageNotifier<robot_msgs::CollisionMap> *collisionMapUpdateNotifier_;
- tf::MessageNotifier<robot_msgs::AttachedObject> *attachedBodyNotifier_;
+ tf::MessageNotifier<tabletop_msgs::AttachedObject> *attachedBodyNotifier_;
boost::function<void(const robot_msgs::CollisionMapConstPtr)> onBeforeMapUpdate_;
boost::function<void(const robot_msgs::CollisionMapConstPtr)> onAfterMapUpdate_;
Modified: pkg/trunk/motion_planning/planning_environment/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_environment/manifest.xml 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/motion_planning/planning_environment/manifest.xml 2009-06-30 03:49:01 UTC (rev 17945)
@@ -15,6 +15,7 @@
<depend package="angles" />
<depend package="pr2_defs" />
<depend package="robot_msgs" />
+ <depend package="tabletop_msgs" />
<depend package="mechanism_msgs" />
<depend package="motion_planning_msgs" />
<depend package="geometric_shapes" />
Modified: pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp 2009-06-30 03:49:01 UTC (rev 17945)
@@ -97,7 +97,7 @@
if (cm_->loadedModels())
{
- attachedBodyNotifier_ = new tf::MessageNotifier<robot_msgs::AttachedObject>(*tf_, boost::bind(&CollisionSpaceMonitor::attachObjectCallback, this, _1), "attach_object", "", 1);
+ attachedBodyNotifier_ = new tf::MessageNotifier<tabletop_msgs::AttachedObject>(*tf_, boost::bind(&CollisionSpaceMonitor::attachObjectCallback, this, _1), "attach_object", "", 1);
attachedBodyNotifier_->setTargetFrame(cm_->getCollisionCheckLinks());
ROS_DEBUG("Listening to attach_object using message notifier with target frame %s", attachedBodyNotifier_->getTargetFramesString().c_str());
}
@@ -227,7 +227,7 @@
onAfterMapUpdate_(collisionMap);
}
-void planning_environment::CollisionSpaceMonitor::attachObjectCallback(const robot_msgs::AttachedObjectConstPtr &attachedObject)
+void planning_environment::CollisionSpaceMonitor::attachObjectCallback(const tabletop_msgs::AttachedObjectConstPtr &attachedObject)
{
collisionSpace_->lock();
planning_models::KinematicModel::Link *link = kmodel_->getLink(attachedObject->link_name);
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/AttachedObject.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/AttachedObject.msg 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/AttachedObject.msg 2009-06-30 03:49:01 UTC (rev 17945)
@@ -1,8 +0,0 @@
-# This mesage defines what objects are attached to a link. The objects
-# are assumed to be defined in the reference frame of the link they
-# are attached to
-
-Header header
-string robot_name
-string link_name
-ObjectOnTable[] objects
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/ObjectOnTable.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/ObjectOnTable.msg 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/ObjectOnTable.msg 2009-06-30 03:49:01 UTC (rev 17945)
@@ -1,3 +0,0 @@
-robot_msgs/Point32 center
-robot_msgs/Point32 min_bound
-robot_msgs/Point32 max_bound
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/Table.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/Table.msg 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/Table.msg 2009-06-30 03:49:01 UTC (rev 17945)
@@ -1,5 +0,0 @@
-Header header
-Polygon3D table
-Point table_min
-Point table_max
-ObjectOnTable[] objects
Deleted: pkg/trunk/stacks/common_msgs/robot_srvs/srv/FindTable.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_srvs/srv/FindTable.srv 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/stacks/common_msgs/robot_srvs/srv/FindTable.srv 2009-06-30 03:49:01 UTC (rev 17945)
@@ -1,2 +0,0 @@
----
-robot_msgs/Table table
Deleted: pkg/trunk/stacks/common_msgs/robot_srvs/srv/RecordStaticMapTrigger.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_srvs/srv/RecordStaticMapTrigger.srv 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/stacks/common_msgs/robot_srvs/srv/RecordStaticMapTrigger.srv 2009-06-30 03:49:01 UTC (rev 17945)
@@ -1,3 +0,0 @@
-time map_time
----
-uint8 status
Deleted: pkg/trunk/stacks/common_msgs/robot_srvs/srv/SubtractObjectFromCollisionMap.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_srvs/srv/SubtractObjectFromCollisionMap.srv 2009-06-30 03:08:52 UTC (rev 17944)
+++ pkg/trunk/stacks/common_msgs/robot_srvs/srv/SubtractObjectFromCollisionMap.srv 2009-06-30 03:49:01 UTC (rev 17945)
@@ -1,4 +0,0 @@
-Header header
-robot_msgs/ObjectOnTable object
----
-uint8 status
Added: pkg/trunk/stacks/common_msgs/tabletop_msgs/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_msgs/CMakeLists.txt (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_msgs/CMakeLists.txt 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,5 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+rospack(tabletop_msgs)
+genmsg()
Added: pkg/trunk/stacks/common_msgs/tabletop_msgs/Makefile
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_msgs/Makefile (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_msgs/Makefile 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
Added: pkg/trunk/stacks/common_msgs/tabletop_msgs/mainpage.dox
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_msgs/mainpage.dox (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_msgs/mainpage.dox 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,119 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b tabletop_msgs is ...
+
+<!--
+In addition to providing an overview of your package,
+this is the section where the specification and design/architecture
+should be detailed. While the original specification may be done on the
+wiki, it should be transferred here once your package starts to take shape.
+You can then link to this documentation page from the Wiki.
+-->
+
+
+\section codeapi Code API
+
+<!--
+Provide links to specific auto-generated API documentation within your
+package that is of particular interest to a reader. Doxygen will
+document pretty much every part of your code, so do your best here to
+point the reader to the actual API.
+
+If your codebase is fairly large or has different sets of APIs, you
+should use the doxygen 'group' tag to keep these APIs together. For
+example, the roscpp documentation has 'libros' group.
+-->
+
+\section rosapi ROS API
+
+<!--
+Names are very important in ROS because they can be remapped on the
+command-line, so it is VERY IMPORTANT THAT YOU LIST NAMES AS THEY
+APPEAR IN THE CODE. You should list names of every topic, service and
+parameter used in your code. There is a template below that you can
+use to document each node separately.
+
+List of nodes:
+- \b node_name1
+- \b node_name2
+-->
+
+<!-- START: copy from here to 'END' for each node
+
+<hr>
+
+\subsection node_name node_name
+
+node_name does (provide a basic description of your node)
+
+\subsubsection Usage
+\verbatim
+$ node_type1 [standard ROS args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ node_type1
+\endverbatim
+
+
+\subsubsection topics ROS topics
+
+Subscribes to:
+- \b "in": [std_msgs/FooType] description of in
+
+Publishes to:
+- \b "out": [std_msgs/FooType] description of out
+
+
+\subsubsection parameters ROS parameters
+
+Reads the following parameters from the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+- \b "~my_param" : \b [string] description of my_param
+
+Sets the following parameters on the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+
+
+\subsubsection services ROS services
+- \b "foo_service": [std_srvs/FooType] description of foo_service
+
+
+END: copy for each node -->
+
+
+<!-- START: Uncomment if you have any command-line tools
+
+\section commandline Command-line tools
+
+This section is a catch-all for any additional tools that your package
+provides or uses that may be of use to the reader. For example:
+
+- tools/scripts (e.g. rospack, roscd)
+- roslaunch .launch files
+- xmlparam files
+
+\subsection script_name script_name
+
+Description of what this script/file does.
+
+\subsubsection Usage
+\verbatim
+$ ./script_name [args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ ./script_name foo bar
+\endverbatim
+
+END: Command-Line Tools Section -->
+
+*/
\ No newline at end of file
Added: pkg/trunk/stacks/common_msgs/tabletop_msgs/manifest.xml
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_msgs/manifest.xml (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_msgs/manifest.xml 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,21 @@
+<package>
+ <description brief="tabletop_msgs">
+
+ tabletop_msgs
+
+ </description>
+ <author>Ioan Sucan</author>
+ <license>BSD</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/tabletop_msgs</url>
+
+ <depend package="robot_msgs" />
+ <depend package="std_msgs"/>
+
+ <export>
+ <cpp cflags="-I${prefix}/msg/cpp"/>
+ </export>
+
+</package>
+
+
Added: pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/AttachedObject.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/AttachedObject.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/AttachedObject.msg 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,8 @@
+# This mesage defines what objects are attached to a link. The objects
+# are assumed to be defined in the reference frame of the link they
+# are attached to
+
+Header header
+string robot_name
+string link_name
+ObjectOnTable[] objects
Added: pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/ObjectOnTable.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/ObjectOnTable.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/ObjectOnTable.msg 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,3 @@
+robot_msgs/Point32 center
+robot_msgs/Point32 min_bound
+robot_msgs/Point32 max_bound
Added: pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/Table.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/Table.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_msgs/msg/Table.msg 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,5 @@
+Header header
+robot_msgs/Polygon3D table
+robot_msgs/Point table_min
+robot_msgs/Point table_max
+ObjectOnTable[] objects
Added: pkg/trunk/stacks/common_msgs/tabletop_srvs/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_srvs/CMakeLists.txt (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_srvs/CMakeLists.txt 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,5 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+rospack(tabletop_srvs)
+gensrv()
Added: pkg/trunk/stacks/common_msgs/tabletop_srvs/Makefile
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_srvs/Makefile (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_srvs/Makefile 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
Added: pkg/trunk/stacks/common_msgs/tabletop_srvs/mainpage.dox
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_srvs/mainpage.dox (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_srvs/mainpage.dox 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,119 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b tabletop_srvs is ...
+
+<!--
+In addition to providing an overview of your package,
+this is the section where the specification and design/architecture
+should be detailed. While the original specification may be done on the
+wiki, it should be transferred here once your package starts to take shape.
+You can then link to this documentation page from the Wiki.
+-->
+
+
+\section codeapi Code API
+
+<!--
+Provide links to specific auto-generated API documentation within your
+package that is of particular interest to a reader. Doxygen will
+document pretty much every part of your code, so do your best here to
+point the reader to the actual API.
+
+If your codebase is fairly large or has different sets of APIs, you
+should use the doxygen 'group' tag to keep these APIs together. For
+example, the roscpp documentation has 'libros' group.
+-->
+
+\section rosapi ROS API
+
+<!--
+Names are very important in ROS because they can be remapped on the
+command-line, so it is VERY IMPORTANT THAT YOU LIST NAMES AS THEY
+APPEAR IN THE CODE. You should list names of every topic, service and
+parameter used in your code. There is a template below that you can
+use to document each node separately.
+
+List of nodes:
+- \b node_name1
+- \b node_name2
+-->
+
+<!-- START: copy from here to 'END' for each node
+
+<hr>
+
+\subsection node_name node_name
+
+node_name does (provide a basic description of your node)
+
+\subsubsection Usage
+\verbatim
+$ node_type1 [standard ROS args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ node_type1
+\endverbatim
+
+
+\subsubsection topics ROS topics
+
+Subscribes to:
+- \b "in": [std_msgs/FooType] description of in
+
+Publishes to:
+- \b "out": [std_msgs/FooType] description of out
+
+
+\subsubsection parameters ROS parameters
+
+Reads the following parameters from the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+- \b "~my_param" : \b [string] description of my_param
+
+Sets the following parameters on the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+
+
+\subsubsection services ROS services
+- \b "foo_service": [std_srvs/FooType] description of foo_service
+
+
+END: copy for each node -->
+
+
+<!-- START: Uncomment if you have any command-line tools
+
+\section commandline Command-line tools
+
+This section is a catch-all for any additional tools that your package
+provides or uses that may be of use to the reader. For example:
+
+- tools/scripts (e.g. rospack, roscd)
+- roslaunch .launch files
+- xmlparam files
+
+\subsection script_name script_name
+
+Description of what this script/file does.
+
+\subsubsection Usage
+\verbatim
+$ ./script_name [args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ ./script_name foo bar
+\endverbatim
+
+END: Command-Line Tools Section -->
+
+*/
\ No newline at end of file
Added: pkg/trunk/stacks/common_msgs/tabletop_srvs/manifest.xml
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_srvs/manifest.xml (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_srvs/manifest.xml 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,22 @@
+<package>
+ <description brief="tabletop_srvs">
+
+ tabletop_srvs
+
+ </description>
+ <author>Ioan Sucan</author>
+ <license>BSD</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/tabletop_srvs</url>
+
+ <depend package="std_msgs"/>
+ <depend package="robot_msgs"/>
+ <depend package="tabletop_msgs"/>
+
+ <export>
+ <cpp cflags="-I${prefix}/srv/cpp"/>
+ </export>
+
+</package>
+
+
Added: pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/FindTable.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/FindTable.srv (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/FindTable.srv 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,2 @@
+---
+tabletop_msgs/Table table
Added: pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/RecordStaticMapTrigger.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/RecordStaticMapTrigger.srv (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/RecordStaticMapTrigger.srv 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,3 @@
+time map_time
+---
+uint8 status
Added: pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/SubtractObjectFromCollisionMap.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/SubtractObjectFromCollisionMap.srv (rev 0)
+++ pkg/trunk/stacks/common_msgs/tabletop_srvs/srv/SubtractObjectFromCollisionMap.srv 2009-06-30 03:49:01 UTC (rev 17945)
@@ -0,0 +1,4 @@
+Header header
+tabletop_msgs/ObjectOnTable object
+---
+uint8 status
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-06-30 06:14:07
|
Revision: 17958
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17958&view=rev
Author: tfoote
Date: 2009-06-30 06:12:46 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
consolidating costmap_2d voxel_grid map_server and move_base into nav_stack
Added Paths:
-----------
pkg/trunk/stacks/nav/costmap_2d/
pkg/trunk/stacks/nav/map_server/
pkg/trunk/stacks/nav/move_base/
pkg/trunk/stacks/nav/nav_view/
pkg/trunk/stacks/nav/voxel_grid/
Removed Paths:
-------------
pkg/trunk/highlevel/move_base/
pkg/trunk/nav/map_server/
pkg/trunk/nav/nav_view/
pkg/trunk/stacks/world_models/costmap_2d/
pkg/trunk/stacks/world_models/voxel_grid/
Property changes on: pkg/trunk/stacks/nav/map_server
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/nav/map_server:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Property changes on: pkg/trunk/stacks/nav/move_base
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/highlevel/move_base:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Property changes on: pkg/trunk/stacks/nav/nav_view
___________________________________________________________________
Added: svn:ignore
+ nav_view
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/nav/nav_view:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Added: svk:merge
+ 920d6130-5740-4ec1-bb1a-45963d5fd813:/users/josh-pr/nav/nav_view:10853
f5854215-dd47-0410-b2c4-cdd35faa7885:/pkg/branches/rosbus/nav/nav_view:216
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-06-30 06:50:16
|
Revision: 17963
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17963&view=rev
Author: tfoote
Date: 2009-06-30 06:49:01 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
base_local_planner and nav_robot_actions into nav stack and tf_conversions out of geometry into standbox for it's not reviewed and will be replaced with the tf extension API
Added Paths:
-----------
pkg/trunk/sandbox/tf_conversions/
pkg/trunk/stacks/nav/base_local_planner/
pkg/trunk/stacks/nav/nav_robot_actions/
Removed Paths:
-------------
pkg/trunk/nav/base_local_planner/
pkg/trunk/nav/nav_robot_actions/
pkg/trunk/stacks/geometry/tf_conversions/
Property changes on: pkg/trunk/stacks/nav/base_local_planner
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/nav/base_local_planner:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Property changes on: pkg/trunk/stacks/nav/nav_robot_actions
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/nav/nav_robot_actions:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-06-30 06:51:02
|
Revision: 17957
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17957&view=rev
Author: tfoote
Date: 2009-06-30 06:08:42 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
moving amcl and fake_localization into nav stack
Added Paths:
-----------
pkg/trunk/stacks/nav/amcl/
pkg/trunk/stacks/nav/fake_localization/
Removed Paths:
-------------
pkg/trunk/nav/amcl/
pkg/trunk/nav/fake_localization/
Property changes on: pkg/trunk/stacks/nav/amcl
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/nav/amcl:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Property changes on: pkg/trunk/stacks/nav/fake_localization
___________________________________________________________________
Added: svn:ignore
+ fake_localization
build
.build_version
lib
ground_truth_controller
bin
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/nav/fake_localization:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <tf...@us...> - 2009-06-30 07:15:01
|
Revision: 17965
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17965&view=rev
Author: tfoote
Date: 2009-06-30 07:14:30 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
moving configuration dictionary into sandbox
Modified Paths:
--------------
pkg/trunk/vision/image_segmentation/.build_version
Added Paths:
-----------
pkg/trunk/sandbox/configuration_dictionary/
Removed Paths:
-------------
pkg/trunk/stacks/common/configuration_dictionary/
Property changes on: pkg/trunk/sandbox/configuration_dictionary
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/configuration_dictionary:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Modified: pkg/trunk/vision/image_segmentation/.build_version
===================================================================
--- pkg/trunk/vision/image_segmentation/.build_version 2009-06-30 07:09:31 UTC (rev 17964)
+++ pkg/trunk/vision/image_segmentation/.build_version 2009-06-30 07:14:30 UTC (rev 17965)
@@ -1 +1 @@
-:
+https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/trunk/vision/image_segmentation:17956
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|