You can subscribe to this list here.
| 2008 |
Jan
|
Feb
|
Mar
(43) |
Apr
(196) |
May
(316) |
Jun
(518) |
Jul
(1293) |
Aug
(1446) |
Sep
(930) |
Oct
(1271) |
Nov
(1275) |
Dec
(1385) |
|---|---|---|---|---|---|---|---|---|---|---|---|---|
| 2009 |
Jan
(1622) |
Feb
(1546) |
Mar
(1236) |
Apr
(1512) |
May
(1782) |
Jun
(1551) |
Jul
(2300) |
Aug
(3088) |
Sep
(452) |
Oct
|
Nov
|
Dec
|
|
From: <ge...@us...> - 2009-09-04 23:56:17
|
Revision: 23880
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23880&view=rev
Author: gerkey
Date: 2009-09-04 23:56:10 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
removed bogus rosdep
Modified Paths:
--------------
pkg/trunk/stacks/joystick_drivers/ps3joy/manifest.xml
Modified: pkg/trunk/stacks/joystick_drivers/ps3joy/manifest.xml
===================================================================
--- pkg/trunk/stacks/joystick_drivers/ps3joy/manifest.xml 2009-09-04 21:47:48 UTC (rev 23879)
+++ pkg/trunk/stacks/joystick_drivers/ps3joy/manifest.xml 2009-09-04 23:56:10 UTC (rev 23880)
@@ -15,7 +15,6 @@
<url>http://www.ros.org/wiki/ps3joy</url>
<rosdep name="libusb"/>
<rosdep name="joystick"/>
- <rosdep name="bluez"/>
<rosdep name="python-bluez"/>
</package>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2009-09-04 21:47:56
|
Revision: 23879
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23879&view=rev
Author: jleibs
Date: 2009-09-04 21:47:48 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Making ntp_monitor check time relative to itself as well.
Modified Paths:
--------------
pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py
Modified: pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py
===================================================================
--- pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py 2009-09-04 21:44:40 UTC (rev 23878)
+++ pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py 2009-09-04 21:47:48 UTC (rev 23879)
@@ -47,7 +47,13 @@
NAME = 'ntp_monitor'
-def ntp_monitor(ntp_hostname, offset=500):
+def ntp_monitor(ntp_hostname, offset=500, self_offset=500):
+ try:
+ offset = int(offset)
+ self_offset = int(self_offset)
+ except:
+ parser.error("offset must be a number")
+
pub = rospy.Publisher("/diagnostics", DiagnosticArray)
rospy.init_node(NAME, anonymous=True)
@@ -59,51 +65,54 @@
stat.message = "Acceptable synchronization"
stat.hardware_id = hostname
stat.values = []
+
+ self_stat = DiagnosticStatus()
+ self_stat.level = 0
+ self_stat.name = "NTP offset from: "+ hostname + " to: self."
+ self_stat.message = "Acceptable synchronization"
+ self_stat.hardware_id = hostname
+ self_stat.values = []
while not rospy.is_shutdown():
- try:
- p = Popen(["ntpdate", "-q", ntp_hostname], stdout=PIPE, stdin=PIPE, stderr=PIPE)
- res = p.wait()
- (o,e) = p.communicate()
- except OSError, (errno, msg):
- if errno == 4:
- break #ctrl-c interrupt
- else:
- raise
- if (res == 0):
- measured_offset = float(re.search("offset (.*),", o).group(1))*1000000
+ for st,host,off in [(stat,ntp_hostname,offset), (self_stat, hostname,self_offset)]:
- stat.level = 0
- stat.message = "Acceptable synchronization"
- stat.values = [ KeyValue("offset (us)", str(measured_offset)) ]
+ try:
+ p = Popen(["ntpdate", "-q", host], stdout=PIPE, stdin=PIPE, stderr=PIPE)
+ res = p.wait()
+ (o,e) = p.communicate()
+ except OSError, (errno, msg):
+ if errno == 4:
+ break #ctrl-c interrupt
+ else:
+ raise
+ if (res == 0):
+ measured_offset = float(re.search("offset (.*),", o).group(1))*1000000
+
+ st.level = 0
+ st.message = "Acceptable synchronization"
+ st.values = [ KeyValue("offset (us)", str(measured_offset)) ]
- if (abs(measured_offset) > offset):
- stat.level = 2
- stat.message = "Offset too great"
+ if (abs(measured_offset) > off):
+ st.level = 2
+ st.message = "Offset too great"
- else:
- stat.level = 2
- stat.message = "Error running ntpupdate"
- stat.values = [ KeyValue("offset (us)", "N/A") ]
+ else:
+ st.level = 2
+ st.message = "Error running ntpupdate"
+ st.values = [ KeyValue("offset (us)", "N/A") ]
- pub.publish(DiagnosticArray(None, [stat]))
+
+ pub.publish(DiagnosticArray(None, [stat, self_stat]))
time.sleep(1)
def ntp_monitor_main(argv=sys.argv):
import optparse
- parser = optparse.OptionParser(usage="usage: ntp_monitor ntp-hostname [offset-tolerance]")
+ parser = optparse.OptionParser(usage="usage: ntp_monitor ntp-hostname [offset-tolerance=500] [self_offset-tolerance=500]")
options, args = parser.parse_args(argv[1:])
- if len(args) == 1:
- ntp_hostname, offset = args[0], 500
- elif len(args) == 2:
- ntp_hostname, offset = args
- try:
- offset = int(offset)
- except:
- parser.error("offset must be a number")
+ if (len(args) > 0 and len(args) <= 3):
+ apply(ntp_monitor, args)
else:
parser.error("Invalid arguments")
- ntp_monitor(ntp_hostname, offset)
if __name__ == "__main__":
try:
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ei...@us...> - 2009-09-04 21:44:50
|
Revision: 23878
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23878&view=rev
Author: eitanme
Date: 2009-09-04 21:44:40 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Updating for new version of ros::Rate
Modified Paths:
--------------
pkg/trunk/stacks/navigation/costmap_2d/src/costmap_2d_publisher.cpp
pkg/trunk/stacks/navigation/costmap_2d/src/costmap_2d_ros.cpp
Modified: pkg/trunk/stacks/navigation/costmap_2d/src/costmap_2d_publisher.cpp
===================================================================
--- pkg/trunk/stacks/navigation/costmap_2d/src/costmap_2d_publisher.cpp 2009-09-04 21:35:19 UTC (rev 23877)
+++ pkg/trunk/stacks/navigation/costmap_2d/src/costmap_2d_publisher.cpp 2009-09-04 21:44:40 UTC (rev 23878)
@@ -68,8 +68,11 @@
new_data_ = false;
publishCostmap();
}
- if(!r.sleep())
- ROS_WARN("Map publishing loop missed its desired rate of %.4f the actual time the loop took was %.4f sec", frequency, r.cycleTime().toSec());
+
+ r.sleep();
+ //make sure to sleep for the remainder of our cycle time
+ if(r.cycleTime() > ros::Duration(1 / frequency))
+ ROS_WARN("Map update loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", frequency, r.cycleTime().toSec());
}
}
Modified: pkg/trunk/stacks/navigation/costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/stacks/navigation/costmap_2d/src/costmap_2d_ros.cpp 2009-09-04 21:35:19 UTC (rev 23877)
+++ pkg/trunk/stacks/navigation/costmap_2d/src/costmap_2d_ros.cpp 2009-09-04 21:44:40 UTC (rev 23878)
@@ -444,8 +444,11 @@
end_t = end.tv_sec + double(end.tv_usec) / 1e6;
t_diff = end_t - start_t;
ROS_DEBUG("Map update time: %.9f", t_diff);
- if(!r.sleep())
- ROS_WARN("Map update loop missed its desired rate of %.4f the actual time the loop took was %.4f sec", frequency, r.cycleTime().toSec());
+
+ r.sleep();
+ //make sure to sleep for the remainder of our cycle time
+ if(r.cycleTime() > ros::Duration(1 / frequency))
+ ROS_WARN("Map update loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", frequency, r.cycleTime().toSec());
}
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <vij...@us...> - 2009-09-04 21:35:34
|
Revision: 23877
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23877&view=rev
Author: vijaypradeep
Date: 2009-09-04 21:35:19 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Adding a LaserCbDetectorNode. Not yet tested
Modified Paths:
--------------
pkg/trunk/stacks/calibration/laser_cb_detector/CMakeLists.txt
Added Paths:
-----------
pkg/trunk/stacks/calibration/laser_cb_detector/src/laser_cb_detector_node.cpp
Modified: pkg/trunk/stacks/calibration/laser_cb_detector/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/calibration/laser_cb_detector/CMakeLists.txt 2009-09-04 21:34:06 UTC (rev 23876)
+++ pkg/trunk/stacks/calibration/laser_cb_detector/CMakeLists.txt 2009-09-04 21:35:19 UTC (rev 23877)
@@ -19,6 +19,9 @@
rosbuild_add_library(${PROJECT_NAME} src/cv_laser_bridge.cpp
src/laser_cb_detector.cpp)
+rosbuild_add_executable(laser_cb_detector_node src/laser_cb_detector_node.cpp)
+target_link_libraries(laser_cb_detector_node ${PROJECT_NAME})
+
rosbuild_genmsg()
# rosbuild_gensrv()
Added: pkg/trunk/stacks/calibration/laser_cb_detector/src/laser_cb_detector_node.cpp
===================================================================
--- pkg/trunk/stacks/calibration/laser_cb_detector/src/laser_cb_detector_node.cpp (rev 0)
+++ pkg/trunk/stacks/calibration/laser_cb_detector/src/laser_cb_detector_node.cpp 2009-09-04 21:35:19 UTC (rev 23877)
@@ -0,0 +1,145 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2009, 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
+
+#include <ros/ros.h>
+#include <laser_cb_detector/laser_cb_detector.h>
+#include <sstream>
+
+using namespace laser_cb_detector;
+using namespace std;
+
+
+#define ROS_INFO_CONFIG(name) \
+{\
+ ostringstream ss;\
+ ss << "[" << #name << "] -> " << config.name;\
+ ROS_INFO(ss.str().c_str());\
+}
+
+
+
+laser_cb_detector::ConfigGoal getParamConfig(ros::NodeHandle &n)
+{
+ laser_cb_detector::ConfigGoal config;
+
+ int num_x;
+ n.param("~num_x", num_x, 3);
+ config.num_x = (unsigned int) num_x;
+
+ int num_y;
+ n.param("~num_y", num_y, 3);
+ config.num_y = (unsigned int) num_y;
+
+ double spacing_x;
+ n.param("~spacing_x", spacing_x, 1.0);
+ config.spacing_x = spacing_x;
+
+ double spacing_y;
+ n.param("~spacing_y", spacing_y, 1.0);
+ config.spacing_y = spacing_y;
+
+ double width_scaling;
+ n.param("~width_scaling", width_scaling, 1.0);
+ config.width_scaling = width_scaling;
+
+ double height_scaling;
+ n.param("~height_scaling", height_scaling, 1.0);
+ config.height_scaling = height_scaling;
+
+ double min_intensity;
+ n.param("~min_intensity", min_intensity, 500.0);
+ config.min_intensity = min_intensity;
+
+ double max_intensity;
+ n.param("~max_intensity", max_intensity, 5000.0);
+ config.max_intensity = max_intensity;
+
+ int subpixel_window;
+ n.param("~subpixel_window", subpixel_window, 2);
+ config.subpixel_window = config.subpixel_window;
+
+ n.param("~subpixel_zero_zone", config.subpixel_zero_zone, -1);
+
+ ROS_INFO_CONFIG(num_x);
+ ROS_INFO_CONFIG(num_y);
+ ROS_INFO_CONFIG(spacing_x);
+ ROS_INFO_CONFIG(spacing_y);
+ ROS_INFO_CONFIG(width_scaling);
+ ROS_INFO_CONFIG(height_scaling);
+ ROS_INFO_CONFIG(min_intensity);
+ ROS_INFO_CONFIG(max_intensity);
+ ROS_INFO_CONFIG(subpixel_window);
+ ROS_INFO_CONFIG(subpixel_zero_zone);
+
+ return config;
+}
+
+void snapshotCallback(ros::Publisher* pub, LaserCbDetector* detector, const calibration_msgs::DenseLaserSnapshotConstPtr& msg)
+{
+ bool detect_result;
+ camera_calibration::CalibrationPattern result;
+ detect_result = detector->detect(*msg, result);
+
+ if (!detect_result)
+ ROS_ERROR("Error during checkerboard detection. (This error is worse than simply not seeing a checkerboard");
+ else
+ {
+ pub->publish(result);
+ }
+}
+
+int main(int argc, char** argv)
+{
+ ros::init(argc, argv, "laser_cb_detector");
+
+ ros::NodeHandle n;
+
+ // Set up the LaserCbDetector
+ laser_cb_detector::ConfigGoal config = getParamConfig(n);
+ LaserCbDetector detector;
+ detector.configure(config);
+
+ // Output
+ ros::Publisher pub = n.advertise<camera_calibration::CalibrationPattern>("laser_checkerboard", 1);
+
+ // Input
+ boost::function<void (const calibration_msgs::DenseLaserSnapshotConstPtr&)> cb
+ = boost::bind(&snapshotCallback, &pub, &detector, _1);
+
+ ros::Subscriber sub = n.subscribe(std::string("snapshot"), 1, cb);
+
+ ros::spin();
+}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mc...@us...> - 2009-09-04 21:34:13
|
Revision: 23876
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23876&view=rev
Author: mcgann
Date: 2009-09-04 21:34:06 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
No need for this additional devConfig
Modified Paths:
--------------
pkg/trunk/stacks/trex/trex_core/nddl_tester
Removed Paths:
-------------
pkg/trunk/stacks/trex/trex_core/devConfig
Deleted: pkg/trunk/stacks/trex/trex_core/devConfig
===================================================================
--- pkg/trunk/stacks/trex/trex_core/devConfig 2009-09-04 21:18:00 UTC (rev 23875)
+++ pkg/trunk/stacks/trex/trex_core/devConfig 2009-09-04 21:34:06 UTC (rev 23876)
@@ -1,11 +0,0 @@
-# This file is a strawman for setting environment variables. It assumes TREX, PLASMA and PlanWorks are peers in the direectory tree.
-# 1. TREX - which should point to the TREX root directory
-# 2. PLASMA_HOME - which should point to the PLASMA root directory
-# 3. TREX_LOG_DIR - which should point to the location for outputting log files generated by the agent. It is not mandatory
-# 4. LD_LIBRARY_PATH - required for loading shared libraries from PLASMA and TREX
-export TREX=`pwd`/TREX
-export PLASMA_HOME=`pwd`/PLASMA
-export PLASMA=$PLASMA_HOME/src/PLASMA
-export TREX_LOG_DIR=$TREX/logs
-export LD_LIBRARY_PATH=$PLASMA_HOME/build/lib:$LD_LIBRARY_PATH
-export PYTHONPATH=$TREX/tools/modules:$PYTHONPATH
\ No newline at end of file
Modified: pkg/trunk/stacks/trex/trex_core/nddl_tester
===================================================================
--- pkg/trunk/stacks/trex/trex_core/nddl_tester 2009-09-04 21:18:00 UTC (rev 23875)
+++ pkg/trunk/stacks/trex/trex_core/nddl_tester 2009-09-04 21:34:06 UTC (rev 23876)
@@ -4,7 +4,7 @@
START=`pwd`
cd `rospack find trex_core`
pwd
-. devConfig
+. TREX/devConfig
cd $START
pwd
rosrun trex nddl-reader_g_rt $1
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ei...@us...> - 2009-09-04 21:18:08
|
Revision: 23875
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23875&view=rev
Author: eitanme
Date: 2009-09-04 21:18:00 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Adding a filter to interpolate between laser readings to generate range readings for scans that return errors
Modified Paths:
--------------
pkg/trunk/stacks/laser_pipeline/laser_filters/examples/shadow_filter_example.yaml
pkg/trunk/stacks/laser_pipeline/laser_filters/laser_filters_plugins.xml
pkg/trunk/stacks/laser_pipeline/laser_filters/src/laser_scan_filters.cpp
Added Paths:
-----------
pkg/trunk/stacks/laser_pipeline/laser_filters/include/laser_filters/interpolation_filter.h
Modified: pkg/trunk/stacks/laser_pipeline/laser_filters/examples/shadow_filter_example.yaml
===================================================================
--- pkg/trunk/stacks/laser_pipeline/laser_filters/examples/shadow_filter_example.yaml 2009-09-04 21:10:23 UTC (rev 23874)
+++ pkg/trunk/stacks/laser_pipeline/laser_filters/examples/shadow_filter_example.yaml 2009-09-04 21:18:00 UTC (rev 23875)
@@ -12,3 +12,5 @@
lower_threshold: 100
upper_threshold: 10000
disp_histogram: 0
+#- name: interpolation
+# type: InterpolationFilter
Added: pkg/trunk/stacks/laser_pipeline/laser_filters/include/laser_filters/interpolation_filter.h
===================================================================
--- pkg/trunk/stacks/laser_pipeline/laser_filters/include/laser_filters/interpolation_filter.h (rev 0)
+++ pkg/trunk/stacks/laser_pipeline/laser_filters/include/laser_filters/interpolation_filter.h 2009-09-04 21:18:00 UTC (rev 23875)
@@ -0,0 +1,115 @@
+/*********************************************************************
+* 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.
+*********************************************************************/
+
+#ifndef INTERPOLATION_FILTER_H
+#define INTERPOLATION_FILTER_H
+/**
+\author Eitan Marder-Eppstein
+@b InterpolationFilter takes input scans and for readings that come back as errors, interpolates between valid readings to generate range values for them.
+
+**/
+
+
+#include "filters/filter_base.h"
+#include "sensor_msgs/LaserScan.h"
+
+namespace laser_filters
+{
+
+class InterpolationFilter : public filters::FilterBase<sensor_msgs::LaserScan>
+{
+public:
+
+ bool configure()
+ {
+ return true;
+ }
+
+ virtual ~InterpolationFilter()
+ {
+ }
+
+ bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan)
+ {
+ double previous_valid_range = input_scan.range_max - .01;
+ double next_valid_range = input_scan.range_max - .01;
+ filtered_scan= input_scan;
+
+ unsigned int i = 0;
+ while(i < input_scan.ranges.size()) // Need to check every reading in the current scan
+ {
+ //check if the reading is out of range for some reason
+ if (filtered_scan.ranges[i] <= input_scan.range_min ||
+ filtered_scan.ranges[i] >= input_scan.range_max){
+
+ //we need to find the next valid range reading
+ unsigned int j = i + 1;
+ unsigned int start_index = i;
+ unsigned int end_index = i;
+ while(j < input_scan.ranges.size()){
+ if (filtered_scan.ranges[j] <= input_scan.range_min ||
+ filtered_scan.ranges[j] >= input_scan.range_max){
+ end_index = j;
+ }
+ else{
+ next_valid_range = filtered_scan.ranges[j];
+ break;
+ }
+ ++j;
+ }
+
+ //for now, we'll just take the average between the two valid range readings
+ double average_range = (previous_valid_range + next_valid_range) / 2.0;
+
+ for(unsigned int k = start_index; k <= end_index; k++){
+ filtered_scan.ranges[k] = average_range;
+ }
+
+ //make sure to update our previous valid range reading
+ previous_valid_range = next_valid_range;
+ i = j + 1;
+ }
+ else{
+ previous_valid_range = filtered_scan.ranges[i];
+ ++i;
+ }
+
+ }
+ return true;
+ }
+};
+
+}
+
+#endif // LASER_SCAN_INTENSITY_FILTER_H
Modified: pkg/trunk/stacks/laser_pipeline/laser_filters/laser_filters_plugins.xml
===================================================================
--- pkg/trunk/stacks/laser_pipeline/laser_filters/laser_filters_plugins.xml 2009-09-04 21:10:23 UTC (rev 23874)
+++ pkg/trunk/stacks/laser_pipeline/laser_filters/laser_filters_plugins.xml 2009-09-04 21:18:00 UTC (rev 23875)
@@ -27,6 +27,12 @@
the veiling effect.
</description>
</class>
+ <class name="InterpolationFilter" type="laser_filters::InterpolationFilter"
+ base_class_type="filters::FilterBase<sensor_msgs::LaserScan>">
+ <description>
+ This is a filter that will generate range readings for error readings in a scan by interpolating between valid readings on either side of the error
+ </description>
+ </class>
</library>
<library path="lib/libpointcloud_filters">
<class name="PointCloudFootprintFilter" type="laser_filters::PointCloudFootprintFilter"
Modified: pkg/trunk/stacks/laser_pipeline/laser_filters/src/laser_scan_filters.cpp
===================================================================
--- pkg/trunk/stacks/laser_pipeline/laser_filters/src/laser_scan_filters.cpp 2009-09-04 21:10:23 UTC (rev 23874)
+++ pkg/trunk/stacks/laser_pipeline/laser_filters/src/laser_scan_filters.cpp 2009-09-04 21:18:00 UTC (rev 23875)
@@ -31,6 +31,7 @@
#include "laser_filters/intensity_filter.h"
#include "laser_filters/scan_shadows_filter.h"
#include "laser_filters/footprint_filter.h"
+#include "laser_filters/interpolation_filter.h"
#include "sensor_msgs/LaserScan.h"
#include "filters/filter_base.h"
@@ -41,3 +42,4 @@
PLUGINLIB_REGISTER_CLASS(LaserScanIntensityFilter, laser_filters::LaserScanIntensityFilter, filters::FilterBase<sensor_msgs::LaserScan>)
PLUGINLIB_REGISTER_CLASS(LaserScanFootprintFilter, laser_filters::LaserScanFootprintFilter, filters::FilterBase<sensor_msgs::LaserScan>)
PLUGINLIB_REGISTER_CLASS(ScanShadowsFilter, laser_filters::ScanShadowsFilter, filters::FilterBase<sensor_msgs::LaserScan>)
+PLUGINLIB_REGISTER_CLASS(InterpolationFilter, laser_filters::InterpolationFilter, filters::FilterBase<sensor_msgs::LaserScan>)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <rob...@us...> - 2009-09-04 21:10:30
|
Revision: 23874
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23874&view=rev
Author: rob_wheeler
Date: 2009-09-04 21:10:23 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Add reset view functionality.
Space toolbar buttons
Modified Paths:
--------------
pkg/trunk/sandbox/web/navigation_application/src/navigation_application/jslib/map_viewer.js
Modified: pkg/trunk/sandbox/web/navigation_application/src/navigation_application/jslib/map_viewer.js
===================================================================
--- pkg/trunk/sandbox/web/navigation_application/src/navigation_application/jslib/map_viewer.js 2009-09-04 21:09:32 UTC (rev 23873)
+++ pkg/trunk/sandbox/web/navigation_application/src/navigation_application/jslib/map_viewer.js 2009-09-04 21:10:23 UTC (rev 23874)
@@ -52,16 +52,22 @@
{'name': 'zoomin', 'desc': 'Zoom In'},
{'name': 'zoomout', 'desc': 'Zoom Out'},
{'name': 'reset', 'desc': 'Reset the view'},
+ {'name': '',},
{'name': 'pan', 'desc': 'Pan'},
{'name': 'goal', 'desc': 'Set the robot\'s goal'},
{'name': 'pose', 'desc': 'Set the robot\'s initial pose'},
+ {'name': '',},
{'name': 'pin', 'desc': 'Follow the robot'},
],
addButton: function(b) {
- this.buttonbar.insert('<img id="' + b.name + '_button" title="'+b.desc+'" style="margin:1;border:1px solid" src="' + window.location.pathname + '/images/'+b.name+'_disable.png"><br>');
- $(b.name + '_button').observe('click', this.handleClick.bind(this));
- $(b.name + '_button').observe('mousedown', function(e) {e.stop()});
+ if (b.name == '') {
+ this.buttonbar.insert('<br>');
+ } else {
+ this.buttonbar.insert('<img id="' + b.name + '_button" title="'+b.desc+'" style="margin:1;border:1px solid" src="' + window.location.pathname + '/images/'+b.name+'_disable.png"><br>');
+ $(b.name + '_button').observe('click', this.handleClick.bind(this));
+ $(b.name + '_button').observe('mousedown', function(e) {e.stop()});
+ }
},
mode : {'PAN' : 0, 'GOAL' : 1, 'POSE': 2},
@@ -72,6 +78,8 @@
this.zoom(-0.25, this.dim.width/2, this.dim.height/2);
} else if (button.id == "zoomout_button") {
this.zoom(0.25, this.dim.width/2, this.dim.height/2);
+ } else if (button.id == "reset_button") {
+ this.zoom(this.sourceWidth/this.dim.width, this.dim.width/2, this.dim.height/2, true);
} else if (button.id == "pan_button") {
this.currentMode = this.mode.PAN;
button.src = window.location.pathname + '/images/pan_enable.png'
@@ -209,9 +217,12 @@
}
},
- zoom : function(factor, center_x, center_y) {
+ zoom : function(factor, center_x, center_y, absolute) {
var center = this.pixelToMap([center_x, center_y]);
- this.scale += factor;
+ if (absolute)
+ this.scale = factor;
+ else
+ this.scale += factor;
var x = Math.floor(center.x / this.scale / this.sourceResolution);
var y = this.sourceHeight / this.scale - Math.floor(center.y / this.scale / this.sourceResolution);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2009-09-04 21:09:40
|
Revision: 23873
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23873&view=rev
Author: hsujohnhsu
Date: 2009-09-04 21:09:32 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
fix demo
Modified Paths:
--------------
pkg/trunk/stacks/simulator_gazebo/gazebo_worlds/worlds/test_friction.world
Modified: pkg/trunk/stacks/simulator_gazebo/gazebo_worlds/worlds/test_friction.world
===================================================================
--- pkg/trunk/stacks/simulator_gazebo/gazebo_worlds/worlds/test_friction.world 2009-09-04 21:09:13 UTC (rev 23872)
+++ pkg/trunk/stacks/simulator_gazebo/gazebo_worlds/worlds/test_friction.world 2009-09-04 21:09:32 UTC (rev 23873)
@@ -25,7 +25,7 @@
<!-- here's the global contact cfm/erp -->
<physics:ode>
<stepTime>0.001</stepTime>
- <gravity>0 0 -9.8</gravity>
+ <gravity>0.0 -1.0 -1.0</gravity>
<cfm>0.0000000001</cfm>
<erp>0.2</erp>
<quickStep>true</quickStep>
@@ -66,7 +66,6 @@
</rendering:ogre>
-
<model:physical name="gplane">
<xyz>0 0 0</xyz>
<rpy>0 0 0</rpy>
@@ -112,9 +111,9 @@
- <!-- The Slide-->
+ <!-- The Slide
<model:physical name="slide1_model">
- <static>true</static>
+ <static>false</static>
<xyz> 0.0 0.0 0.00</xyz>
<rpy> 0.0 0.0 0.00</rpy>
<body:box name="slide1_legs_body">
@@ -126,7 +125,7 @@
<xyz> 0.0 5.0 13</xyz>
<rpy> 45.0 0.0 0.00</rpy>
<size> 50.0 20.0 1.0</size>
- <mass> 1000.0</mass>
+ <mass> 100.0</mass>
<visual>
<size>50.0 20.0 1.0</size>
<material>PR2/Red</material>
@@ -134,13 +133,24 @@
</visual>
</geom:box>
</body:box>
+ <joint:hinge name="slide_fixed_joint">
+ <body1>slide1_legs_body</body1>
+ <body2>world</body2>
+ <anchor>slide1_legs_body</anchor>
+ <lowStop>0</lowStop>
+ <highStop>0</highStop>
+ <axis>1 0 0</axis>
+ </joint:hinge>
+
</model:physical>
+ -->
+
<!-- boxes -->
<model:physical name="box_01_model">
- <xyz> 2.0 8.0 17.42</xyz>
- <rpy> 45.0 0.0 0.0</rpy>
+ <xyz> 2.0 8.0 0.5</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
<body:box name="box_01_body">
<massMatrix>true</massMatrix>
<mass>1.0</mass>
@@ -171,8 +181,8 @@
</model:physical>
<model:physical name="box_02_model">
- <xyz> 4.0 8.0 17.42</xyz>
- <rpy> 45.0 0.0 0.0</rpy>
+ <xyz> 4.0 8.0 0.5</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
<body:box name="box_02_body">
<massMatrix>true</massMatrix>
<mass>1.0</mass>
@@ -203,8 +213,8 @@
</model:physical>
<model:physical name="box_03_model">
- <xyz> 6.0 8.0 17.42</xyz>
- <rpy> 45.0 0.0 0.0</rpy>
+ <xyz> 6.0 8.0 0.5</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
<body:box name="box_03_body">
<massMatrix>true</massMatrix>
<mass>1.0</mass>
@@ -235,8 +245,8 @@
</model:physical>
<model:physical name="box_04_model">
- <xyz> 8.0 8.0 17.42</xyz>
- <rpy> 45.0 0.0 0.0</rpy>
+ <xyz> 8.0 8.0 0.5</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
<body:box name="box_04_body">
<massMatrix>true</massMatrix>
<mass>1.0</mass>
@@ -267,8 +277,8 @@
</model:physical>
<model:physical name="box_05_model">
- <xyz> 10.0 8.0 17.42</xyz>
- <rpy> 45.0 0.0 0.0</rpy>
+ <xyz> 10.0 8.0 0.5</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
<body:box name="box_05_body">
<massMatrix>true</massMatrix>
<mass>1.0</mass>
@@ -299,8 +309,8 @@
</model:physical>
<model:physical name="box_06_model">
- <xyz> 12.0 8.0 17.42</xyz>
- <rpy> 45.0 0.0 0.0</rpy>
+ <xyz> 12.0 8.0 0.5</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
<body:box name="box_06_body">
<massMatrix>true</massMatrix>
<mass>1.0</mass>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jfa...@us...> - 2009-09-04 21:09:20
|
Revision: 23872
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23872&view=rev
Author: jfaustwg
Date: 2009-09-04 21:09:13 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Delete unused files
Removed Paths:
-------------
pkg/trunk/stacks/pr2_gui/pr2_dashboard2/src/pr2_dashboard/hardware_panel.py
pkg/trunk/stacks/pr2_gui/pr2_dashboard2/src/pr2_dashboard/motor.py
Deleted: pkg/trunk/stacks/pr2_gui/pr2_dashboard2/src/pr2_dashboard/hardware_panel.py
===================================================================
--- pkg/trunk/stacks/pr2_gui/pr2_dashboard2/src/pr2_dashboard/hardware_panel.py 2009-09-04 21:09:09 UTC (rev 23871)
+++ pkg/trunk/stacks/pr2_gui/pr2_dashboard2/src/pr2_dashboard/hardware_panel.py 2009-09-04 21:09:13 UTC (rev 23872)
@@ -1,67 +0,0 @@
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2008, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# * Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# * Redistributions in binary form must reproduce the above
-# copyright notice, this list of conditions and the following
-# disclaimer in the documentation and/or other materials provided
-# with the distribution.
-# * Neither the name of 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.
-
-import roslib
-roslib.load_manifest('pr2_dashboard')
-
-import wx
-import wx.aui
-from wx import xrc
-import motor
-import ocean_battery_driver
-from ocean_battery_driver.ibps_panel import *
-import pr2_power_board
-from pr2_power_board.pr2_power_board_panel import *
-
-
-PKG='pr2_dashboard'
-
-class HardwarePanel(wx.Panel):
- def __init__(self, parent):
- wx.Panel.__init__(self, parent)
-
- self._notebook = wx.aui.AuiNotebook(self, wx.ID_ANY, wx.DefaultPosition, wx.DefaultSize,
- wx.aui.AUI_NB_TAB_SPLIT | wx.aui.AUI_NB_TAB_MOVE | wx.aui.AUI_NB_TOP | wx.aui.AUI_NB_SCROLL_BUTTONS)
-
- sizer = wx.BoxSizer(wx.VERTICAL)
- sizer.Add(self._notebook, 1, wx.EXPAND)
- self.SetSizer(sizer)
-
- self._motor_panel = motor.MotorPanel(self)
- self._battery_panel = BatteryPanel(self)
- self._powerboard_panel = PowerBoardPanel(self)
- self._notebook.AddPage(self._powerboard_panel, "Power Board", True)
- self._notebook.AddPage(self._motor_panel, "Motors")
- self._notebook.AddPage(self._battery_panel, "Battery")
-
-
-
Deleted: pkg/trunk/stacks/pr2_gui/pr2_dashboard2/src/pr2_dashboard/motor.py
===================================================================
--- pkg/trunk/stacks/pr2_gui/pr2_dashboard2/src/pr2_dashboard/motor.py 2009-09-04 21:09:09 UTC (rev 23871)
+++ pkg/trunk/stacks/pr2_gui/pr2_dashboard2/src/pr2_dashboard/motor.py 2009-09-04 21:09:13 UTC (rev 23872)
@@ -1,76 +0,0 @@
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2008, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# * Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# * Redistributions in binary form must reproduce the above
-# copyright notice, this list of conditions and the following
-# disclaimer in the documentation and/or other materials provided
-# with the distribution.
-# * Neither the name of 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.
-
-import roslib
-roslib.load_manifest('pr2_dashboard')
-
-import wx
-from wx import xrc
-import rospy
-import std_srvs.srv
-
-PKG='pr2_dashboard'
-
-class MotorPanel(wx.Panel):
- def __init__(self, parent):
- wx.Panel.__init__(self, parent)
-
- xrc_path = roslib.packages.get_pkg_dir(PKG) + '/xrc/motor_panel.xrc'
-
- self._xrc = xrc.XmlResource(xrc_path)
- self._real_panel = self._xrc.LoadPanel(self, 'MotorPanel')
- sizer = wx.BoxSizer(wx.VERTICAL)
- sizer.Add(self._real_panel, 1, wx.EXPAND)
- self.SetSizer(sizer)
-
- self._reset_motors = xrc.XRCCTRL(self._real_panel, "reset_motors_button")
- self._halt_motors = xrc.XRCCTRL(self._real_panel, "halt_motors_button")
-
- self._reset_motors.Bind(wx.EVT_BUTTON, self.on_reset_motors)
- self._halt_motors.Bind(wx.EVT_BUTTON, self.on_halt_motors)
-
- def on_reset_motors(self, event):
- reset = rospy.ServiceProxy("reset_motors", std_srvs.srv.Empty)
-
- try:
- reset()
- except rospy.ServiceException:
- rospy.logerr('Failed to reset the motors: service call failed')
-
- def on_halt_motors(self, event):
- halt = rospy.ServiceProxy("halt_motors", std_srvs.srv.Empty)
-
- try:
- halt()
- except rospy.ServiceException:
- rospy.logerr('Failed to halt the motors: service call failed')
-
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-09-04 21:09:17
|
Revision: 23871
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23871&view=rev
Author: isucan
Date: 2009-09-04 21:09:09 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
update link to wiki
Modified Paths:
--------------
pkg/trunk/motion_planning/robot_self_filter/manifest.xml
Modified: pkg/trunk/motion_planning/robot_self_filter/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/robot_self_filter/manifest.xml 2009-09-04 20:54:44 UTC (rev 23870)
+++ pkg/trunk/motion_planning/robot_self_filter/manifest.xml 2009-09-04 21:09:09 UTC (rev 23871)
@@ -7,7 +7,7 @@
<author>Ioan Sucan</author>
<license>BSD</license>
<review status="unreviewed" notes=""/>
- <url>http://pr.willowgarage.com/wiki/new_robot_self_filter</url>
+ <url>http://pr.willowgarage.com/wiki/robot_self_filter</url>
<depend package="roscpp"/>
<depend package="tf"/>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2009-09-04 20:54:51
|
Revision: 23870
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23870&view=rev
Author: hsujohnhsu
Date: 2009-09-04 20:54:44 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
remove debug comment
Modified Paths:
--------------
pkg/trunk/stacks/simulator_gazebo/gazebo/gazebo_new_patch.diff
Modified: pkg/trunk/stacks/simulator_gazebo/gazebo/gazebo_new_patch.diff
===================================================================
--- pkg/trunk/stacks/simulator_gazebo/gazebo/gazebo_new_patch.diff 2009-09-04 20:42:44 UTC (rev 23869)
+++ pkg/trunk/stacks/simulator_gazebo/gazebo/gazebo_new_patch.diff 2009-09-04 20:54:44 UTC (rev 23870)
@@ -192,7 +192,7 @@
}
}
}
-@@ -614,6 +624,17 @@
+@@ -614,6 +624,16 @@
this->directionVec.z -= this->moveAmount;
break;
@@ -204,13 +204,12 @@
+ case XK_Alt_L:
+ case XK_Alt_R:
+ this->altKeyPressed = true;
-+ std::cout << "pressing alt" << std::endl;
+ break;
+
default:
break;
}
-@@ -641,7 +662,20 @@
+@@ -641,7 +661,20 @@
case ']':
CameraManager::Instance()->DecActiveCamera();
break;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2009-09-04 20:42:52
|
Revision: 23869
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23869&view=rev
Author: hsujohnhsu
Date: 2009-09-04 20:42:44 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
debugging
Modified Paths:
--------------
pkg/trunk/stacks/simulator_gazebo/gazebo/gazebo_new_patch.diff
Modified: pkg/trunk/stacks/simulator_gazebo/gazebo/gazebo_new_patch.diff
===================================================================
--- pkg/trunk/stacks/simulator_gazebo/gazebo/gazebo_new_patch.diff 2009-09-04 20:39:24 UTC (rev 23868)
+++ pkg/trunk/stacks/simulator_gazebo/gazebo/gazebo_new_patch.diff 2009-09-04 20:42:44 UTC (rev 23869)
@@ -61,6 +61,56 @@
endif (RUBY_LIBRARY AND RUBY_INCLUDE_PATH)
IF(RUBY_FOUND)
+Index: server/Global.hh
+===================================================================
+--- server/Global.hh (revision 8232)
++++ server/Global.hh (working copy)
+@@ -80,6 +80,6 @@
+
+ #define ROUND(x) ( (int)( floor((x)+0.5) ) )
+
+-//#define TIMING
++#undef TIMING
+
+ #endif
+Index: server/Simulator.cc
+===================================================================
+--- server/Simulator.cc (revision 8232)
++++ server/Simulator.cc (working copy)
+@@ -645,6 +645,11 @@
+ world->Update();
+ }
+
++#ifdef TIMING
++ double tmpT2 = Simulator::Instance()->GetWallTime();
++ std::cout << " World::Update() DT(" << tmpT2-tmpT1 << ")" << std::endl;
++#endif
++
+ currTime = this->GetRealTime();
+
+ // Set a default sleep time
+@@ -678,6 +683,10 @@
+ // Process all incoming messages from simiface
+ world->UpdateSimulationIface();
+
++#ifdef TIMING
++ double tmpT3 = Simulator::Instance()->GetWallTime();
++ std::cout << " World::UpdatSimulationIface() DT(" << tmpT3-tmpT2 << ")" << std::endl;
++#endif
+ if (this->timeout > 0 && this->GetRealTime() > this->timeout)
+ {
+ this->userQuit = true;
+@@ -691,8 +700,8 @@
+ }
+
+ #ifdef TIMING
+- double tmpT2 = this->GetWallTime();
+- std::cout << " Simulator::PhysicsLoop() DT(" << tmpT2-tmpT1
++ double tmpT4 = this->GetWallTime();
++ std::cout << " Simulator::PhysicsLoop() DT(" << tmpT4-tmpT1
+ << ")" << std::endl;
+ #endif
+ }
Index: server/rendering/OgreHeightmap.cc
===================================================================
--- server/rendering/OgreHeightmap.cc (revision 8232)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2009-09-04 20:39:36
|
Revision: 23868
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23868&view=rev
Author: hsujohnhsu
Date: 2009-09-04 20:39:24 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
debugging
Modified Paths:
--------------
pkg/trunk/stacks/physics/opende/test_patch.diff
Modified: pkg/trunk/stacks/physics/opende/test_patch.diff
===================================================================
--- pkg/trunk/stacks/physics/opende/test_patch.diff 2009-09-04 20:38:15 UTC (rev 23867)
+++ pkg/trunk/stacks/physics/opende/test_patch.diff 2009-09-04 20:39:24 UTC (rev 23868)
@@ -1,6 +1,6 @@
Index: ode/src/quickstep.cpp
===================================================================
---- ode/src/quickstep.cpp (revision 1684)
+--- ode/src/quickstep.cpp (revision 1690)
+++ ode/src/quickstep.cpp (working copy)
@@ -63,6 +63,7 @@
@@ -635,7 +635,7 @@
// solve the LCP problem and get lambda and invM*constraint_force
Index: ode/src/util.h
===================================================================
---- ode/src/util.h (revision 1684)
+--- ode/src/util.h (revision 1690)
+++ ode/src/util.h (working copy)
@@ -23,6 +23,7 @@
#ifndef _ODE_UTIL_H_
@@ -647,7 +647,7 @@
Index: ode/src/util.cpp
===================================================================
---- ode/src/util.cpp (revision 1684)
+--- ode/src/util.cpp (revision 1690)
+++ ode/src/util.cpp (working copy)
@@ -24,6 +24,8 @@
#include "objects.h"
@@ -662,21 +662,24 @@
dxBody *const *bodystart = body;
dxJoint *const *jointstart = joint;
-+ std::cout << "number of islands: " << islandcount << std::endl;
++ //std::cout << "number of islands: " << islandcount << std::endl;
+ boost::thread* island_threads[islandcount];
+
+ int thread_count = 0;
int const *const sizesend = islandsizes + islandcount * sizeelements;
for (int const *sizescurr = islandsizes; sizescurr != sizesend; sizescurr += sizeelements) {
int bcount = sizescurr[0];
-@@ -541,12 +547,20 @@
+@@ -541,12 +547,26 @@
BEGIN_STATE_SAVE(context, stepperstate) {
// now do something with body and joint lists
-- stepper (context,world,bodystart,bcount,jointstart,jcount,stepsize);
-+ //stepper (context,world,bodystart,bcount,jointstart,jcount,stepsize);
++#undef BTTEST
++#if BTTEST
+ std::cout << "spawning island: " << thread_count << std::endl;
+ island_threads[thread_count] = new boost::thread( boost::bind( stepper, context,world,bodystart,bcount,jointstart,jcount,stepsize) );
++#else
+ stepper (context,world,bodystart,bcount,jointstart,jcount,stepsize);
++#endif
} END_STATE_SAVE(context, stepperstate);
bodystart += bcount;
@@ -684,10 +687,12 @@
+
+ thread_count++;
}
++#if BTTEST
+ for (int j = 0 ; j < thread_count ; j++)
+ island_threads[j]->join();
+ for (int j = 0 ; j < thread_count ; j++)
+ delete island_threads[j];
++#endif
context->CleanupContext();
dIASSERT(context->IsStructureValid());
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2009-09-04 20:38:23
|
Revision: 23867
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23867&view=rev
Author: hsujohnhsu
Date: 2009-09-04 20:38:15 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
startup plugin executive as well
Added Paths:
-----------
pkg/trunk/demos/plug_in_gazebo/launch/pr2_plug_in_test.launch
Added: pkg/trunk/demos/plug_in_gazebo/launch/pr2_plug_in_test.launch
===================================================================
--- pkg/trunk/demos/plug_in_gazebo/launch/pr2_plug_in_test.launch (rev 0)
+++ pkg/trunk/demos/plug_in_gazebo/launch/pr2_plug_in_test.launch 2009-09-04 20:38:15 UTC (rev 23867)
@@ -0,0 +1,10 @@
+<launch>
+ <include file="$(find plug_in_gazebo)/launch/pr2_plug_outlet.launch"/>
+ <include file="$(find milestone2_actions)/milestone2.launch" />
+ <node pkg="plugs_core" type="test_executive" output="screen"/>
+ <!--<node pkg="rosrecord" type="rosrecord" args=" -f door_demos_test.bag " />-->
+
+ <param name="/base_shadow_filter/notifier_tolerance" value="0.09" type="double" />
+ <param name="/tilt_shadow_filter/notifier_tolerance" value="0.09" type="double" />
+</launch>
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <goo...@us...> - 2009-09-04 20:33:37
|
Revision: 23866
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23866&view=rev
Author: goodfellow
Date: 2009-09-04 20:33:31 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Modifications to make it work on pre
Modified Paths:
--------------
pkg/trunk/sandbox/person_data/calibration_components/person_calibrate.launch
pkg/trunk/sandbox/person_data/common/checkrobot.py
pkg/trunk/sandbox/person_data/data_collector_components/base_odom.xml
pkg/trunk/sandbox/person_data/data_collector_components/person_data.launch
pkg/trunk/sandbox/person_data/data_collector_components/truly_passive.launch
pkg/trunk/sandbox/person_data/scripts/collect_data.sh
Added Paths:
-----------
pkg/trunk/sandbox/person_data/NOTES
pkg/trunk/sandbox/person_data/config/machine1bagdir.txt
pkg/trunk/sandbox/person_data/config/machine2bagdir.txt
pkg/trunk/sandbox/person_data/real_make.sh
Added: pkg/trunk/sandbox/person_data/NOTES
===================================================================
--- pkg/trunk/sandbox/person_data/NOTES (rev 0)
+++ pkg/trunk/sandbox/person_data/NOTES 2009-09-04 20:33:31 UTC (rev 23866)
@@ -0,0 +1 @@
+Currently, there is no /bags directory on pre. Eric said to just put everything in the home directory on pre2.
Modified: pkg/trunk/sandbox/person_data/calibration_components/person_calibrate.launch
===================================================================
--- pkg/trunk/sandbox/person_data/calibration_components/person_calibrate.launch 2009-09-04 20:32:16 UTC (rev 23865)
+++ pkg/trunk/sandbox/person_data/calibration_components/person_calibrate.launch 2009-09-04 20:33:31 UTC (rev 23866)
@@ -1,7 +1,7 @@
<launch>
<node pkg="person_data" type="joylistener" output="screen"/>
<node pkg ="person_data" type="headhack" output="screen" />
-<node pkg ="pr2_default_controllers" type="tuckarm.py" args="r" output="screen" />
+<node pkg ="pr2_experimental_controllers" type="tuckarm.py" args="r" output="screen" />
<!-- for some reason putting joylistener after the other launch files broke it,
and putting headhack after them makes roslaunch not find it! -->
<!-- node pkg="pr2_default_controllers" type="tuckarm.py" args="r" -->
Modified: pkg/trunk/sandbox/person_data/common/checkrobot.py
===================================================================
--- pkg/trunk/sandbox/person_data/common/checkrobot.py 2009-09-04 20:32:16 UTC (rev 23865)
+++ pkg/trunk/sandbox/person_data/common/checkrobot.py 2009-09-04 20:33:31 UTC (rev 23866)
@@ -9,9 +9,9 @@
print "Your ROBOT variable is not set"
quit(-1)
-if sys.argv[1] != "prf" and sys.argv[1] != "prg":
- for i in range(0,1000):
- print "Your ROBOT variable is not set"
- quit(-1)
+#if sys.argv[1] != "prf" and sys.argv[1] != "prg":
+# for i in range(0,1000):
+## print "Your ROBOT variable is not a recognized robot"
+# quit(-1)
quit(0)
Added: pkg/trunk/sandbox/person_data/config/machine1bagdir.txt
===================================================================
--- pkg/trunk/sandbox/person_data/config/machine1bagdir.txt (rev 0)
+++ pkg/trunk/sandbox/person_data/config/machine1bagdir.txt 2009-09-04 20:33:31 UTC (rev 23866)
@@ -0,0 +1 @@
+/pr/2/`whoami`/bags
Added: pkg/trunk/sandbox/person_data/config/machine2bagdir.txt
===================================================================
--- pkg/trunk/sandbox/person_data/config/machine2bagdir.txt (rev 0)
+++ pkg/trunk/sandbox/person_data/config/machine2bagdir.txt 2009-09-04 20:33:31 UTC (rev 23866)
@@ -0,0 +1 @@
+/pr/2/`whoami`/bags
Modified: pkg/trunk/sandbox/person_data/data_collector_components/base_odom.xml
===================================================================
--- pkg/trunk/sandbox/person_data/data_collector_components/base_odom.xml 2009-09-04 20:32:16 UTC (rev 23865)
+++ pkg/trunk/sandbox/person_data/data_collector_components/base_odom.xml 2009-09-04 20:33:31 UTC (rev 23866)
@@ -9,14 +9,15 @@
<node pkg="backup_safetysound" type="backingup.py" machine="four" />
<!-- The robot pose EKF is launched with the base controller-->
-<node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf">
+<!-- commented out because also present in truly_passive.launch
+node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf">
<param name="freq" value="30.0"/>
<param name="sensor_timeout" value="1.0"/>
<param name="publish_tf" value="true"/>
<param name="odom_used" value="true"/>
<param name="imu_used" value="true"/>
<param name="vo_used" value="false"/>
-</node>
+</node -->
</launch>
Modified: pkg/trunk/sandbox/person_data/data_collector_components/person_data.launch
===================================================================
--- pkg/trunk/sandbox/person_data/data_collector_components/person_data.launch 2009-09-04 20:32:16 UTC (rev 23865)
+++ pkg/trunk/sandbox/person_data/data_collector_components/person_data.launch 2009-09-04 20:33:31 UTC (rev 23866)
@@ -1,7 +1,7 @@
<launch>
<node pkg="person_data" type="joylistener" output="screen"/>
<node pkg ="person_data" type="headhack" output="screen" />
-<node pkg ="pr2_default_controllers" type="tuckarm.py" args="r" output="screen" />
+<node pkg ="pr2_experimental_controllers" type="tuckarm.py" args="r" output="screen" />
<include file="$(find person_data)/data_collector_components/2dnav_pr2.launch" />
Modified: pkg/trunk/sandbox/person_data/data_collector_components/truly_passive.launch
===================================================================
--- pkg/trunk/sandbox/person_data/data_collector_components/truly_passive.launch 2009-09-04 20:32:16 UTC (rev 23865)
+++ pkg/trunk/sandbox/person_data/data_collector_components/truly_passive.launch 2009-09-04 20:33:31 UTC (rev 23866)
@@ -22,6 +22,7 @@
<param name="odom_used" value="true"/>
<param name="imu_used" value="true"/>
<param name="vo_used" value="false"/>
+ <param name="publish_tf" value="true"/>
</node>
<!-- node pkg="tf" machine="two" type="change_notifier"-->
Added: pkg/trunk/sandbox/person_data/real_make.sh
===================================================================
--- pkg/trunk/sandbox/person_data/real_make.sh (rev 0)
+++ pkg/trunk/sandbox/person_data/real_make.sh 2009-09-04 20:33:31 UTC (rev 23866)
@@ -0,0 +1,10 @@
+#Run this to actually make the realtime dependencies
+function rosmake-deps { \
+ #argument is name of launch file \
+ rosmake `roslaunch-deps $1`; \
+}
+
+
+rosmake-deps *.launch */*.launch
+rosmake-deps config/controllers.xml
+rosmake-deps config/perception.xml
Modified: pkg/trunk/sandbox/person_data/scripts/collect_data.sh
===================================================================
--- pkg/trunk/sandbox/person_data/scripts/collect_data.sh 2009-09-04 20:32:16 UTC (rev 23865)
+++ pkg/trunk/sandbox/person_data/scripts/collect_data.sh 2009-09-04 20:33:31 UTC (rev 23866)
@@ -1,10 +1,10 @@
#!/bin/bash
python `rospack find person_data`/common/checkrobot.py ${ROBOT} || exit
+export bagconfig=`rospack find person_data`/config/machine2bagdir.txt
+ssh ${ROBOT}2 mkdir -p `cat ${bagconfig}`
-ssh ${ROBOT}2 mkdir -p /bags/person_data
+#ssh ${ROBOT}3 mkdir -p /bags/person_data
-ssh ${ROBOT}3 mkdir -p /bags/person_data
+#ssh ${ROBOT}4 mkdir -p /bags/person_data
-ssh ${ROBOT}4 mkdir -p /bags/person_data
-
roslaunch `rospack find person_data`/data_collector_components/person_data.launch
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mc...@us...> - 2009-09-04 20:32:23
|
Revision: 23865
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23865&view=rev
Author: mcgann
Date: 2009-09-04 20:32:16 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Missing dependency
Modified Paths:
--------------
pkg/trunk/stacks/pr2_simulator/pr2_ogre/manifest.xml
Modified: pkg/trunk/stacks/pr2_simulator/pr2_ogre/manifest.xml
===================================================================
--- pkg/trunk/stacks/pr2_simulator/pr2_ogre/manifest.xml 2009-09-04 20:30:21 UTC (rev 23864)
+++ pkg/trunk/stacks/pr2_simulator/pr2_ogre/manifest.xml 2009-09-04 20:32:16 UTC (rev 23865)
@@ -13,7 +13,9 @@
<depend package="convex_decomposition"/>
<depend package="ivcon"/>
<depend package="ogre_tools"/>
+ <depend package="pr2_defs"/>
+
<url>http://pr.willowgarage.com/wiki/RobotDescriptionFormat</url>
</package>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <pmi...@us...> - 2009-09-04 20:30:29
|
Revision: 23864
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23864&view=rev
Author: pmihelich
Date: 2009-09-04 20:30:21 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
image_transport: Can now override transports used by ImagePublisher and their topics. Added transform utility for republishing an image topic in alternate form.
Modified Paths:
--------------
pkg/trunk/stacks/image_common/image_transport/CMakeLists.txt
pkg/trunk/stacks/image_common/image_transport/manifest.xml
pkg/trunk/stacks/image_common/image_transport/src/image_publisher.cpp
Added Paths:
-----------
pkg/trunk/stacks/image_common/image_transport/src/transform.cpp
Removed Paths:
-------------
pkg/trunk/stacks/image_common/image_transport/src/encoder.cpp
Modified: pkg/trunk/stacks/image_common/image_transport/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/image_common/image_transport/CMakeLists.txt 2009-09-04 20:28:41 UTC (rev 23863)
+++ pkg/trunk/stacks/image_common/image_transport/CMakeLists.txt 2009-09-04 20:30:21 UTC (rev 23864)
@@ -18,8 +18,8 @@
rosbuild_add_library(${PROJECT_NAME} src/image_publisher.cpp src/image_subscriber.cpp src/raw_publisher.cpp src/raw_subscriber.cpp src/manifest.cpp)
-rosbuild_add_executable(encoder src/encoder.cpp)
-target_link_libraries(encoder ${PROJECT_NAME})
+rosbuild_add_executable(transform src/transform.cpp)
+target_link_libraries(transform ${PROJECT_NAME})
#rosbuild_add_executable(test_publisher src/test_publisher.cpp)
#target_link_libraries(test_publisher ${PROJECT_NAME})
Modified: pkg/trunk/stacks/image_common/image_transport/manifest.xml
===================================================================
--- pkg/trunk/stacks/image_common/image_transport/manifest.xml 2009-09-04 20:28:41 UTC (rev 23863)
+++ pkg/trunk/stacks/image_common/image_transport/manifest.xml 2009-09-04 20:30:21 UTC (rev 23864)
@@ -1,7 +1,9 @@
<package>
<description brief="image_transport">
- image_transport
+ image_transport provides specialized publisher and subscriber classes for transporting images.
+ These classes use a plugin architecture to provide specialized transport options, such as
+ through a video codec.
</description>
<author>Patrick Mihelich</author>
Deleted: pkg/trunk/stacks/image_common/image_transport/src/encoder.cpp
===================================================================
--- pkg/trunk/stacks/image_common/image_transport/src/encoder.cpp 2009-09-04 20:28:41 UTC (rev 23863)
+++ pkg/trunk/stacks/image_common/image_transport/src/encoder.cpp 2009-09-04 20:30:21 UTC (rev 23864)
@@ -1,16 +0,0 @@
-#include "image_transport/image_publisher.h"
-
-int main(int argc, char** argv)
-{
- ros::init(argc, argv, "encoder", ros::init_options::AnonymousName);
- ros::NodeHandle nh;
- {
- // @todo: need to suppress default publisher
- std::string topic = nh.resolveName("image");
- image_transport::ImagePublisher image_pub;
- image_pub.advertise(nh, topic, 1);
-
- ros::spin();
- }
- return 0;
-}
Modified: pkg/trunk/stacks/image_common/image_transport/src/image_publisher.cpp
===================================================================
--- pkg/trunk/stacks/image_common/image_transport/src/image_publisher.cpp 2009-09-04 20:28:41 UTC (rev 23863)
+++ pkg/trunk/stacks/image_common/image_transport/src/image_publisher.cpp 2009-09-04 20:30:21 UTC (rev 23864)
@@ -37,6 +37,7 @@
#include <pluginlib/class_loader.h>
#include <boost/ptr_container/ptr_vector.hpp>
#include <boost/foreach.hpp>
+#include <boost/algorithm/string/erase.hpp>
namespace image_transport {
@@ -57,7 +58,8 @@
: impl_(new Impl)
{
// Default behavior: load all plugins and use default topic names.
- BOOST_FOREACH(const std::string& lookup_name, impl_->loader.getDeclaredClasses()) {
+ BOOST_FOREACH(std::string lookup_name, impl_->loader.getDeclaredClasses()) {
+ boost::erase_last(lookup_name, "_pub");
impl_->topic_map[lookup_name] = "";
}
}
@@ -77,9 +79,10 @@
impl_->topic = nh.resolveName(topic);
BOOST_FOREACH(const TransportTopicMap::value_type& value, impl_->topic_map) {
- //ROS_INFO("Loading %s", value.first.c_str());
+ std::string lookup_name = value.first + "_pub";
+ //ROS_INFO("Loading %s", lookup_name.c_str());
try {
- PublisherPlugin* pub = impl_->loader.createClassInstance(value.first);
+ PublisherPlugin* pub = impl_->loader.createClassInstance(lookup_name);
impl_->publishers.push_back(pub);
std::string sub_topic = value.second;
if (sub_topic.empty())
@@ -89,7 +92,7 @@
}
catch (const std::runtime_error& e) {
ROS_WARN("Failed to load plugin %s, error string: %s",
- value.first.c_str(), e.what());
+ lookup_name.c_str(), e.what());
}
}
}
Added: pkg/trunk/stacks/image_common/image_transport/src/transform.cpp
===================================================================
--- pkg/trunk/stacks/image_common/image_transport/src/transform.cpp (rev 0)
+++ pkg/trunk/stacks/image_common/image_transport/src/transform.cpp 2009-09-04 20:30:21 UTC (rev 23864)
@@ -0,0 +1,34 @@
+#include "image_transport/image_subscriber.h"
+#include "image_transport/image_publisher.h"
+#include <ros/names.h>
+#include <boost/foreach.hpp>
+
+using namespace image_transport;
+
+int main(int argc, char** argv)
+{
+ ros::init(argc, argv, "image_transformer", ros::init_options::AnonymousName);
+ if (argc < 2) {
+ printf("Usage: %s raw in:=/camera/image_compressed out:=/camera/image_decompressed", argv[0]);
+ return 0;
+ }
+ ros::NodeHandle nh;
+ std::string out_topic = nh.resolveName("out");
+ std::string in_topic = nh.resolveName("in");
+
+ ImagePublisher image_pub;
+ ImagePublisher::TransportTopicMap& topic_map = image_pub.getTopicMap();
+ topic_map.clear();
+ topic_map[ argv[1] ] = out_topic;
+ image_pub.advertise(nh, out_topic, 1);
+
+ ImageSubscriber image_sub;
+ // Use ImagePublisher::publish as the subscriber callback
+ typedef void (ImagePublisher::*PublishMemFn)(const sensor_msgs::ImageConstPtr&) const;
+ PublishMemFn pub_mem_fn = &ImagePublisher::publish;
+ image_sub.subscribe(nh, in_topic, 1, boost::bind(pub_mem_fn, &image_pub, _1));
+
+ ros::spin();
+
+ return 0;
+}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <wa...@us...> - 2009-09-04 20:28:49
|
Revision: 23863
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23863&view=rev
Author: wattsk
Date: 2009-09-04 20:28:41 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Changes to PRG launch file, works with prosilica and new servers
Modified Paths:
--------------
pkg/trunk/stacks/pr2/pr2_alpha/prg.launch
pkg/trunk/stacks/pr2/pr2_alpha/teleop_ps3.launch
Modified: pkg/trunk/stacks/pr2/pr2_alpha/prg.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/prg.launch 2009-09-04 20:22:44 UTC (rev 23862)
+++ pkg/trunk/stacks/pr2/pr2_alpha/prg.launch 2009-09-04 20:28:41 UTC (rev 23863)
@@ -1,5 +1,4 @@
<launch>
-
<include file="$(find pr2_alpha)/prg.machine" />
<include file="$(find pr2_alpha)/prg_ethercat_reset.launch" />
@@ -21,7 +20,7 @@
</node>
<!-- Battery Monitor -->
-<!-- <node machine="two" pkg="ocean_battery_driver" type="ocean_server" respawn="true">
+ <node machine="two" name="ocean_driver" pkg="ocean_battery_driver" type="ocean_server" respawn="true">
<param name="number_of_ports" type="int" value="4" />
<param name="port0" type="string" value="/dev/ttyUSB0" />
<param name="port1" type="string" value="/dev/ttyUSB1" />
@@ -29,22 +28,20 @@
<param name="port3" type="string" value="/dev/ttyUSB3" />
<param name="debug_level" type="int" value="0" />
</node>
--->
<node pkg="power_monitor" type="power_monitor" respawn="true"/>
<!-- Base Laser -->
<node machine="two" pkg="hokuyo_node" type="hokuyo_node" name="base_hokuyo_node" args="scan:=base_scan">
- <param name="port" type="string" value="/dev/ttyACM0" />
+ <param name="port" type="string" value="/dev/ttyACM1" />
<param name="frameid" type="string" value="base_laser" />
<param name="min_ang_degrees" type="double" value="-130.0" />
<param name="max_ang_degrees" type="double" value="130.0" />
</node>
-
<!-- Tilt Laser -->
- <node machine="realtime" pkg="hokuyo_node" type="hokuyo_node" name="tilt_hokuyo_node" args="scan:=tilt_scan">
+ <node machine="two" pkg="hokuyo_node" type="hokuyo_node" name="tilt_hokuyo_node" args="scan:=tilt_scan">
<param name="port" type="string" value="/dev/ttyACM0" />
<param name="frameid" type="string" value="laser_tilt_link" />
<param name="min_ang_degrees" type="double" value="-70.0" />
@@ -63,12 +60,12 @@
<node machine="realtime" pkg="imu_node" type="imu_node" output="screen"/>
<!-- Prosilica camera setup -->
- <!--group ns="prosilica">
+ <group ns="prosilica">
<include file="$(find prosilica_camera)/cam_settings.xml"/>
<param name="acquisition_mode" type="str" value="Triggered"/>
- <param name="ip_address" type="str" value="10.68.7.20"/>
+ <param name="ip_address" type="str" value="10.68.0.20"/>
</group>
- <node machine="two" name="prosilica" pkg="prosilica_camera" type="prosilica_node" output="screen" respawn="true"/-->
+ <node machine="two" name="prosilica" pkg="prosilica_camera" type="prosilica_node" output="screen" respawn="true"/>
<!-- Watts: Need to get driver working for stereo on servers -->
<!-- Double stereo setup -->
@@ -122,7 +119,8 @@
-->
<!-- Runtime Diagnostics Logging -->
- <node pkg="rosrecord" type="rosrecord" args="-f /hwlog/prg_runtime_automatic /diagnostics" />
+ <node name="runtime_logger" machine="realtime" pkg="rosrecord"
+ type="rosrecord" args="-f /hwlog/prg_runtime_automatic /diagnostics" />
<!-- Joint Calibration Monitor -->
<!--
Modified: pkg/trunk/stacks/pr2/pr2_alpha/teleop_ps3.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/teleop_ps3.launch 2009-09-04 20:22:44 UTC (rev 23862)
+++ pkg/trunk/stacks/pr2/pr2_alpha/teleop_ps3.launch 2009-09-04 20:28:41 UTC (rev 23863)
@@ -1,6 +1,8 @@
<launch>
- <include file="$(find pr2_alpha)/pre.machine" />
+ <machine name="two_root" address="c2" user="root" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="two" address="c2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+
<!-- Start up pairing thing -->
<node machine="two_root" pkg="ps3joy" output="screen"
type="ps3joy.py" name="ps3_connector" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <rob...@us...> - 2009-09-04 20:22:52
|
Revision: 23862
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23862&view=rev
Author: rob_wheeler
Date: 2009-09-04 20:22:44 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Add functionality to the map toolbar buttons.
Modified Paths:
--------------
pkg/trunk/sandbox/web/navigation_application/src/navigation_application/jslib/map_viewer.js
Added Paths:
-----------
pkg/trunk/sandbox/web/navigation_application/src/navigation_application/images/pose_disable.png
pkg/trunk/sandbox/web/navigation_application/src/navigation_application/images/pose_enable.png
Added: pkg/trunk/sandbox/web/navigation_application/src/navigation_application/images/pose_disable.png
===================================================================
(Binary files differ)
Property changes on: pkg/trunk/sandbox/web/navigation_application/src/navigation_application/images/pose_disable.png
___________________________________________________________________
Added: svn:mime-type
+ application/octet-stream
Added: pkg/trunk/sandbox/web/navigation_application/src/navigation_application/images/pose_enable.png
===================================================================
(Binary files differ)
Property changes on: pkg/trunk/sandbox/web/navigation_application/src/navigation_application/images/pose_enable.png
___________________________________________________________________
Added: svn:mime-type
+ application/octet-stream
Modified: pkg/trunk/sandbox/web/navigation_application/src/navigation_application/jslib/map_viewer.js
===================================================================
--- pkg/trunk/sandbox/web/navigation_application/src/navigation_application/jslib/map_viewer.js 2009-09-04 20:19:06 UTC (rev 23861)
+++ pkg/trunk/sandbox/web/navigation_application/src/navigation_application/jslib/map_viewer.js 2009-09-04 20:22:44 UTC (rev 23862)
@@ -41,7 +41,6 @@
},
});
-
var MapViewer = Class.create({
initialize: function(domobj) {
this.viewer = domobj;
@@ -60,9 +59,32 @@
],
addButton: function(b) {
- this.buttonbar.insert('<img title="'+b.desc+'" style="margin:1;border:1px solid" src="' + window.location.pathname + '/images/'+b.name+'_disable.png"><br>');
+ this.buttonbar.insert('<img id="' + b.name + '_button" title="'+b.desc+'" style="margin:1;border:1px solid" src="' + window.location.pathname + '/images/'+b.name+'_disable.png"><br>');
+ $(b.name + '_button').observe('click', this.handleClick.bind(this));
+ $(b.name + '_button').observe('mousedown', function(e) {e.stop()});
},
+ mode : {'PAN' : 0, 'GOAL' : 1, 'POSE': 2},
+
+ handleClick : function(e) {
+ var button = e.element();
+ if (button.id == "zoomin_button") {
+ this.zoom(-0.25, this.dim.width/2, this.dim.height/2);
+ } else if (button.id == "zoomout_button") {
+ this.zoom(0.25, this.dim.width/2, this.dim.height/2);
+ } else if (button.id == "pan_button") {
+ this.currentMode = this.mode.PAN;
+ button.src = window.location.pathname + '/images/pan_enable.png'
+ } else if (button.id == "goal_button") {
+ this.currentMode = this.mode.GOAL;
+ } else if (button.id == "pose_button") {
+ this.currentMode = this.mode.POSE;
+ } else if (button.id == "pin_button") {
+ this.follow = !this.follow;
+ }
+ return false;
+ },
+
init: function() {
// Overlay a canvas the same size as this div
this.canvas = new Element('canvas', {'id': 'map_canvas', 'width': this.viewer.getWidth(), 'height': this.viewer.getHeight(), 'style': 'z-index:1;position:absolute'});
@@ -102,10 +124,10 @@
Event.observe(document, 'mouseup', this.handleMouseUp.bind(this));
Event.observe(document, 'mousemove', this.handleMouseMove.bind(this));
Event.observe(document, 'keypress', this.handleKeyPress.bind(this));
- this.panning = false;
- this.settingGoal = false;
- this.settingPose = false;
+ this.currentMode = this.mode.PAN;
+ this.follow = false;
+
this.robot_img = new Image();
this.robot_img.src = window.location.pathname + '/images/pr2_small.png';
},
@@ -120,29 +142,22 @@
},
handleMouseDown : function(e) {
- this.mark = [Event.pointerX(e), Event.pointerY(e)];
if (Event.isLeftClick(e)) {
- this.panning = true;
- } else if (Event.isMiddleClick(e)) {
- if (e.ctrlKey)
- this.settingPose = true;
- else
- this.settingGoal = true;
+ this.mark = [Event.pointerX(e), Event.pointerY(e)];
}
},
handleMouseUp : function(e) {
if (Event.isLeftClick(e)) {
- this.panning = false;
- } else if (Event.isMiddleClick(e)) {
- if (this.settingGoal || this.settingPose) {
+ if (this.currentMode == this.mode.GOAL ||
+ this.currentMode == this.mode.POSE) {
var dx = Event.pointerX(e) - this.mark[0];
var dy = Event.pointerY(e) - this.mark[1];
var angle = Math.atan2(-dy, dx);
var off = this.viewer.cumulativeOffset();
var pos = this.pixelToMap([this.mark[0]-off.left, this.mark[1]-off.top]);
var url = 'http://' + window.location.hostname + ':8080';
- url += this.settingGoal ? '/map/set_goal' : '/map/set_pose';
+ url += this.currentMode == this.mode.GOAL ? '/map/set_goal' : '/map/set_pose';
url += '?x=' + pos.x;
url += '&y=' + pos.y;
url += '&angle=' + angle;
@@ -152,23 +167,27 @@
delete this.robot_est;
delete this.plan;
}
+ delete this.mark;
}
},
handleMouseMove : function(e) {
- if (this.panning) {
- var old_mark = this.mark;
- this.mark = [Event.pointerX(e), Event.pointerY(e)];
- this.panMap(this.mark[0] - old_mark[0],
- this.mark[1] - old_mark[1]);
- } else if (this.settingGoal || this.settingPose) {
- var off = this.viewer.cumulativeOffset();
- var pos = this.pixelToMap([this.mark[0]-off.left, this.mark[1]-off.top]);
- var dx = Event.pointerX(e) - this.mark[0];
- var dy = Event.pointerY(e) - this.mark[1];
- var angle = Math.atan2(dy, dx);
- this.robot_est = {'x': pos.x, 'y': pos.y, 'angle': angle};
- this.updateCanvas();
+ if (this.mark) {
+ if (this.currentMode == this.mode.PAN) {
+ var old_mark = this.mark;
+ this.mark = [Event.pointerX(e), Event.pointerY(e)];
+ this.panMap(this.mark[0] - old_mark[0],
+ this.mark[1] - old_mark[1]);
+ } else if (this.currentMode == this.mode.GOAL ||
+ this.currentMode == this.mode.POSE) {
+ var off = this.viewer.cumulativeOffset();
+ var pos = this.pixelToMap([this.mark[0]-off.left, this.mark[1]-off.top]);
+ var dx = Event.pointerX(e) - this.mark[0];
+ var dy = Event.pointerY(e) - this.mark[1];
+ var angle = Math.atan2(dy, dx);
+ this.robot_est = {'x': pos.x, 'y': pos.y, 'angle': angle};
+ this.updateCanvas();
+ }
}
},
@@ -341,7 +360,8 @@
var coords = this.mapToPixel(msg.pose.position);
coords[0] -= this.panner.left;
coords[1] -= this.panner.top;
- //this.panMap(this.dim.width/2-coords[0], this.dim.height/2-coords[1], false);
+ if (this.follow)
+ this.panMap(this.dim.width/2-coords[0], this.dim.height/2-coords[1], false);
this.robot = {'x': msg.pose.position.x,
'y': msg.pose.position.y,
'angle': angle};
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <wa...@us...> - 2009-09-04 20:19:13
|
Revision: 23861
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23861&view=rev
Author: wattsk
Date: 2009-09-04 20:19:06 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Changed torso command topic
Modified Paths:
--------------
pkg/trunk/pr2/teleop/teleop_pr2/teleop_pr2.cpp
Modified: pkg/trunk/pr2/teleop/teleop_pr2/teleop_pr2.cpp
===================================================================
--- pkg/trunk/pr2/teleop/teleop_pr2/teleop_pr2.cpp 2009-09-04 20:00:56 UTC (rev 23860)
+++ pkg/trunk/pr2/teleop/teleop_pr2/teleop_pr2.cpp 2009-09-04 20:19:06 UTC (rev 23861)
@@ -41,7 +41,7 @@
#include "std_msgs/Float64.h"
-#define TORSO_TOPIC "torso_lift_velocity_controller/set_command"
+#define TORSO_TOPIC "torso_lift_velocity_controller/command"
#define HEAD_TOPIC "head_controller/command"
using namespace std;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bla...@us...> - 2009-09-04 20:01:03
|
Revision: 23860
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23860&view=rev
Author: blaisegassend
Date: 2009-09-04 20:00:56 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Moved launch files from camera_launch_files
Added Paths:
-----------
pkg/trunk/deprecated/dcam/videre.launch
pkg/trunk/deprecated/dcam/videre_with_projector.launch
Copied: pkg/trunk/deprecated/dcam/videre.launch (from rev 23346, pkg/trunk/stacks/camera_drivers/camera_launch_files/videre.launch)
===================================================================
--- pkg/trunk/deprecated/dcam/videre.launch (rev 0)
+++ pkg/trunk/deprecated/dcam/videre.launch 2009-09-04 20:00:56 UTC (rev 23860)
@@ -0,0 +1,22 @@
+<launch>
+ <group ns="stereo">
+ <node pkg="dcam" type="stereodcam" respawn="false" name="stereodcam">
+ <param name="videre_mode" type="str" value="rectified"/>
+ <param name="exposure" type="int" value="450"/>
+ <param name="exposure_auto" type="bool" value="false"/>
+ <param name="brightness" type="int" value="50"/>
+ <param name="brightness_auto" type="bool" value="false"/>
+ <param name="gain" type="int" value="10"/>
+ <param name="gain_auto" type="bool" value="false"/>
+ </node>
+
+ <node pkg="stereo_image_proc" type="stereoproc" respawn="false" name="stereoproc">
+ <param name="do_colorize" type="bool" value="True"/>
+ <param name="do_rectify" type="bool" value="True"/>
+ <param name="do_stereo" type="bool" value="True"/>
+ <param name="do_calc_points" type="bool" value="True"/>
+ </node>
+ </group>
+
+</launch>
+
Copied: pkg/trunk/deprecated/dcam/videre_with_projector.launch (from rev 23346, pkg/trunk/stacks/camera_drivers/camera_launch_files/videre_with_projector.launch)
===================================================================
--- pkg/trunk/deprecated/dcam/videre_with_projector.launch (rev 0)
+++ pkg/trunk/deprecated/dcam/videre_with_projector.launch 2009-09-04 20:00:56 UTC (rev 23860)
@@ -0,0 +1,27 @@
+<launch>
+ <group ns="stereo">
+ <node pkg="dcam" type="stereodcam" respawn="false">
+ <param name="videre_mode" type="str" value="none"/>
+ <param name="exposure" type="int" value="6"/>
+ <param name="exposure_auto" type="bool" value="false"/>
+ <param name="brightness" type="int" value="50"/>
+ <param name="brightness_auto" type="bool" value="true"/>
+ <param name="gain" type="int" value="10"/>
+ <param name="gain_auto" type="bool" value="true"/>
+ </node>
+ <node pkg="stereo_image_proc" type="stereoproc" respawn="false">
+ <param name="do_colorize" type="bool" value="false"/>
+ <param name="do_rectify" type="bool" value="True"/>
+ <param name="do_stereo" type="bool" value="True"/>
+ <param name="do_calc_points" type="bool" value="True"/>
+ <param name="do_keep_coords" type="bool" value="True"/>
+
+ <param name="num_disp" type="int" value="128"/>
+ <param name="texture_thresh" type="int" value="4"/>
+ <param name="unique_thresh" type="int" value="25"/>
+ <param name="corr_size" type="int" value="11"/>
+ </node>
+
+ </group>
+</launch>
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bla...@us...> - 2009-09-04 20:00:31
|
Revision: 23859
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23859&view=rev
Author: blaisegassend
Date: 2009-09-04 20:00:26 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Added camera_focus as a qualification dependency.
Modified Paths:
--------------
pkg/trunk/pr2/qualification/manifest.xml
Modified: pkg/trunk/pr2/qualification/manifest.xml
===================================================================
--- pkg/trunk/pr2/qualification/manifest.xml 2009-09-04 19:59:22 UTC (rev 23858)
+++ pkg/trunk/pr2/qualification/manifest.xml 2009-09-04 20:00:26 UTC (rev 23859)
@@ -5,6 +5,7 @@
<license>BSD</license>
<review status="unreviewed" notes=""/>
<depend package="rospy" />
+ <depend package="camera_focus" />
<depend package="std_msgs" />
<depend package="diagnostic_msgs" />
<depend package="hokuyo_node" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bla...@us...> - 2009-09-04 19:59:31
|
Revision: 23858
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23858&view=rev
Author: blaisegassend
Date: 2009-09-04 19:59:22 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Added an error message if bluez is not installed.
Modified Paths:
--------------
pkg/trunk/stacks/joystick_drivers/ps3joy/ps3joy.py
Modified: pkg/trunk/stacks/joystick_drivers/ps3joy/ps3joy.py
===================================================================
--- pkg/trunk/stacks/joystick_drivers/ps3joy/ps3joy.py 2009-09-04 19:56:44 UTC (rev 23857)
+++ pkg/trunk/stacks/joystick_drivers/ps3joy/ps3joy.py 2009-09-04 19:59:22 UTC (rev 23858)
@@ -199,7 +199,7 @@
quit(1)
os.system("/etc/init.d/bluetooth stop > /dev/null 2>&1")
while os.system("hciconfig hci0 > /dev/null 2>&1") != 0:
- print >> sys.stderr, "No bluetooth dongle found. Will retry in 5 seconds."
+ print >> sys.stderr, "No bluetooth dongle found or bluez rosdep not installed. Will retry in 5 seconds."
time.sleep(5)
os.system("hciconfig hci0 up > /dev/null 2>&1")
os.system("hciconfig hci0 pscan > /dev/null 2>&1")
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bla...@us...> - 2009-09-04 19:56:51
|
Revision: 23857
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23857&view=rev
Author: blaisegassend
Date: 2009-09-04 19:56:44 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Added bluez as sysdep and made error message clearer.
Modified Paths:
--------------
pkg/trunk/stacks/joystick_drivers/ps3joy/manifest.xml
pkg/trunk/stacks/joystick_drivers/ps3joy/ps3joy.py
Modified: pkg/trunk/stacks/joystick_drivers/ps3joy/manifest.xml
===================================================================
--- pkg/trunk/stacks/joystick_drivers/ps3joy/manifest.xml 2009-09-04 19:54:50 UTC (rev 23856)
+++ pkg/trunk/stacks/joystick_drivers/ps3joy/manifest.xml 2009-09-04 19:56:44 UTC (rev 23857)
@@ -15,6 +15,7 @@
<url>http://www.ros.org/wiki/ps3joy</url>
<rosdep name="libusb"/>
<rosdep name="joystick"/>
+ <rosdep name="bluez"/>
<rosdep name="python-bluez"/>
</package>
Modified: pkg/trunk/stacks/joystick_drivers/ps3joy/ps3joy.py
===================================================================
--- pkg/trunk/stacks/joystick_drivers/ps3joy/ps3joy.py 2009-09-04 19:54:50 UTC (rev 23856)
+++ pkg/trunk/stacks/joystick_drivers/ps3joy/ps3joy.py 2009-09-04 19:56:44 UTC (rev 23857)
@@ -199,7 +199,7 @@
quit(1)
os.system("/etc/init.d/bluetooth stop > /dev/null 2>&1")
while os.system("hciconfig hci0 > /dev/null 2>&1") != 0:
- print >> sys.stderr, "No bluetooth device found. Will retry in 5 seconds."
+ print >> sys.stderr, "No bluetooth dongle found. Will retry in 5 seconds."
time.sleep(5)
os.system("hciconfig hci0 up > /dev/null 2>&1")
os.system("hciconfig hci0 pscan > /dev/null 2>&1")
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <goo...@us...> - 2009-09-04 19:55:01
|
Revision: 23856
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23856&view=rev
Author: goodfellow
Date: 2009-09-04 19:54:50 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Updated script to use new version of JointState
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py 2009-09-04 19:47:26 UTC (rev 23855)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py 2009-09-04 19:54:50 UTC (rev 23856)
@@ -39,21 +39,16 @@
import rospy
from geometry_msgs.msg import PointStamped, Point
-from pr2_mechanism_msgs.msg import JointStates, JointState
+from sensor_msgs.msg import JointState
def point_head_client(pan, tilt):
- head_angles = rospy.Publisher('head_controller/command', JointStates)
+ head_angles = rospy.Publisher('head_controller/command', JointState)
rospy.init_node('head_commander', anonymous=True)
sleep(1)
- ps = JointState()
- ps.name = 'head_pan_joint'
- ps.position = pan
- ts = JointState()
- ts.name ='head_tilt_joint'
- ts.position = tilt
- js = JointStates()
- js.joints = [ps, ts]
+ js = JointState()
+ js.name = ['head_pan_joint', 'head_tilt_joint'];
+ js.position = [pan,tilt];
head_angles.publish(js)
sleep(1)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|