Added new coursework, cleaned up structure

This commit is contained in:
2017-11-29 10:11:54 -08:00
parent b300c76103
commit 808a0f1724
345 changed files with 126653 additions and 0 deletions

View File

@@ -0,0 +1,11 @@
<launch>
<param name="/use_sim_time" value="true"/>
<node pkg="rosbag" type="play" name="rosplay"
args="-d 5 -r 1 --clock --hz 10 $(find gmapping)/test/hallway_slow_2011-03-04-21-41-33.bag"/>
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<remap from="scan" to="base_laser1_scan"/>
</node>
<!--test time-limit="180" test-name="basic_localization_stage" pkg="gmapping"
type="test_map.py" args="90.0"/-->
<test time-limit="180" test-name="map_data_different_beamcount_test" pkg="gmapping" type="gmapping-rtest" args="90.0 0.05 4000 4000 0.002 0.005"/>
</launch>

View File

@@ -0,0 +1,11 @@
<launch>
<param name="/use_sim_time" value="true"/>
<node pkg="rosbag" type="play" name="rosplay"
args="-d 5 -r 1 --clock --hz 10 $(find gmapping)/test/basic_localization_stage_indexed.bag"/>
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<remap from="scan" to="base_scan"/>
</node>
<!--test time-limit="180" test-name="basic_localization_stage" pkg="gmapping"
type="test_map.py" args="90.0"/-->
<test time-limit="180" test-name="map_data_test" pkg="gmapping" type="gmapping-rtest" args="90.0 0.05 4000 4000 0.005 0.010"/>
</launch>

View File

@@ -0,0 +1,8 @@
<launch>
<node pkg="gmapping" type="slam_gmapping_replay" name="slam_gmapping_replay" output="screen"
args="--bag_filename $(find gmapping)/test/basic_localization_stage_indexed.bag --scan_topic /base_scan"/>
<!--test time-limit="30" test-name="basic_localization_stage" pkg="gmapping"
type="test_map.py" args="90.0"/-->
<!-- TODO: Fix the rtest to work with replay, for now it's not working -->
<test time-limit="250" test-name="map_data_test_replay" pkg="gmapping" type="gmapping-rtest" args="200.0 0.05 4000 4000 0.005 0.010"/>
</launch>

View File

@@ -0,0 +1,5 @@
<launch>
<node pkg="gmapping" type="slam_gmapping_replay" name="slam_gmapping_replay" output="screen"
args="--bag_filename $(find gmapping)/test/test_replay_crash.bag --scan_topic /scan"/>
<test time-limit="20" test-name="map_data_test_replay" pkg="gmapping" type="gmapping-rtest" args="10.0 0.05 4000 4000 0.0001 0.010"/>
</launch>

View File

@@ -0,0 +1,5 @@
<launch>
<node pkg="gmapping" type="slam_gmapping_replay" name="slam_gmapping_replay" output="screen"
args="--bag_filename $(find gmapping)/test/test_turtlebot.bag --scan_topic /scan"/>
<test time-limit="120" test-name="test_symmetry" pkg="gmapping" type="gmapping-rtest" args="90.0 0.05 4000 4000 0.0005 0.010"/>
</launch>

View File

@@ -0,0 +1,5 @@
<launch>
<node pkg="gmapping" type="slam_gmapping_replay" name="slam_gmapping_replay" output="screen"
args="--bag_filename $(find gmapping)/test/test_upside_down.bag --scan_topic /laserscan/fix/raw _base_frame:=base_floor"/>
<test time-limit="190" test-name="test_symmetry" pkg="gmapping" type="gmapping-rtest" args="180.0 0.05 4000 4000 0.002 0.010"/>
</launch>

View File

@@ -0,0 +1,180 @@
/*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
/* Author: Brian Gerkey */
#include <gtest/gtest.h>
#include <ros/service.h>
#include <ros/ros.h>
#include <nav_msgs/GetMap.h>
#include <nav_msgs/OccupancyGrid.h>
#include <nav_msgs/MapMetaData.h>
ros::NodeHandle* g_n=NULL;
double g_res, g_width, g_height, g_min_free_ratio, g_max_free_ratio;
class MapClientTest : public testing::Test
{
public:
MapClientTest()
{
got_map_ = false;
got_map_metadata_ = false;
}
~MapClientTest()
{
}
bool got_map_;
boost::shared_ptr<nav_msgs::OccupancyGrid const> map_;
void mapCallback(const boost::shared_ptr<nav_msgs::OccupancyGrid const>& map)
{
map_ = map;
got_map_ = true;
}
bool got_map_metadata_;
boost::shared_ptr<nav_msgs::MapMetaData const> map_metadata_;
void mapMetaDataCallback(const boost::shared_ptr<nav_msgs::MapMetaData const>& map_metadata)
{
map_metadata_ = map_metadata;
got_map_metadata_ = true;
}
void checkMapMetaData(const nav_msgs::MapMetaData& map_metadata)
{
EXPECT_FLOAT_EQ(map_metadata.resolution, g_res);
EXPECT_FLOAT_EQ(map_metadata.width, g_width);
EXPECT_FLOAT_EQ(map_metadata.height, g_height);
}
void checkMapData(const nav_msgs::OccupancyGrid& map)
{
unsigned int i;
unsigned int free_cnt = 0;
for(i=0; i < map.info.width * map.info.height; i++)
{
if(map.data[i] == 0)
free_cnt++;
}
double free_ratio = free_cnt / (double)(i);
ROS_INFO("Min / ratio / Max free ratio: %f / %f / %f", g_min_free_ratio, free_ratio, g_max_free_ratio);
EXPECT_GE(free_ratio, g_min_free_ratio);
EXPECT_LE(free_ratio, g_max_free_ratio);
}
};
/* Try to retrieve the map via service, and compare to ground truth */
TEST_F(MapClientTest, call_service)
{
nav_msgs::GetMap::Request req;
nav_msgs::GetMap::Response resp;
ASSERT_TRUE(ros::service::waitForService("dynamic_map", 5000));
ASSERT_TRUE(ros::service::call("dynamic_map", req, resp));
checkMapMetaData(resp.map.info);
checkMapData(resp.map);
}
/* Try to retrieve the map via topic, and compare to ground truth */
TEST_F(MapClientTest, subscribe_topic)
{
ros::Subscriber sub = g_n->subscribe<nav_msgs::OccupancyGrid>("map", 1, boost::bind(&MapClientTest::mapCallback, this, _1));
// Try a few times, because the server may not be up yet.
int i=20;
while(!got_map_ && i > 0)
{
ros::spinOnce();
ros::WallDuration d(0.25);
d.sleep();
i--;
}
ASSERT_TRUE(got_map_);
checkMapMetaData(map_->info);
checkMapData(*(map_.get()));
}
/* Try to retrieve the metadata via topic, and compare to ground truth */
TEST_F(MapClientTest, subscribe_topic_metadata)
{
ros::Subscriber sub = g_n->subscribe<nav_msgs::MapMetaData>("map_metadata", 1, boost::bind(&MapClientTest::mapMetaDataCallback, this, _1));
// Try a few times, because the server may not be up yet.
int i=20;
while(!got_map_metadata_ && i > 0)
{
ros::spinOnce();
ros::WallDuration d(0.25);
d.sleep();
i--;
}
ASSERT_TRUE(got_map_metadata_);
checkMapMetaData(*(map_metadata_.get()));
}
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
ros::init(argc, argv, "map_client_test");
g_n = new ros::NodeHandle();
// Required args are, in order:
// <delay> <resolution> <width> <height> <min_free_ratio> <max_free_ratio>
ROS_ASSERT(argc == 7);
ros::Duration delay = ros::Duration(atof(argv[1]));
g_res = atof(argv[2]);
g_width = atof(argv[3]);
g_height = atof(argv[4]);
g_min_free_ratio = atof(argv[5]);
g_max_free_ratio = atof(argv[6]);
while(ros::Time::now().toSec() == 0.0)
{
ROS_INFO("Waiting for initial time publication");
ros::Duration(0.25).sleep();
ros::spinOnce();
}
ros::Time start_time = ros::Time::now();
while((ros::Time::now() - start_time) < delay)
{
ROS_INFO("Waiting for delay expiration (%.3f - %.3f) < %.3f",
ros::Time::now().toSec(),
start_time.toSec(),
delay.toSec());
ros::Duration(0.25).sleep();
ros::spinOnce();
}
int result = RUN_ALL_TESTS();
delete g_n;
return result;
}

View File

@@ -0,0 +1,104 @@
#!/usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of the Willow Garage nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
import PIL.Image
import unittest
import subprocess
import sys
import roslib
import os
roslib.load_manifest('gmapping')
import rostest
class TestGmapping(unittest.TestCase):
# Test that 2 map files are approximately the same
def cmp_maps(self, f0, f1):
im0 = PIL.Image.open(f0+'.pgm')
im1 = PIL.Image.open(f1+'.pgm')
size = 100,100
im0.thumbnail(size,PIL.Image.ANTIALIAS)
im1.thumbnail(size,PIL.Image.ANTIALIAS)
# get raw data for comparison
im0d = im0.getdata()
im1d = im1.getdata()
# assert len(i0)==len(i1)
self.assertTrue(len(im0d) == len(im1d))
#compare pixel by pixel for thumbnails
error_count = 0
error_total = 0
pixel_tol = 0
total_error_tol = 0.1
for i in range(len(im0d)):
(p0) = im0d[i]
(p1) = im1d[i]
if abs(p0-p1) > pixel_tol:
error_count = error_count + 1
error_total = error_total + abs(p0-p1)
error_avg = float(error_total)/float(len(im0d))
print '%d / %d = %.6f (%.6f)'%(error_total,len(im0d),error_avg,total_error_tol)
self.assertTrue(error_avg <= total_error_tol)
def test_basic_localization_stage(self):
if sys.argv > 1:
target_time = float(sys.argv[1])
import time
import rospy
rospy.init_node('test', anonymous=True)
while(rospy.rostime.get_time() == 0.0):
print 'Waiting for initial time publication'
time.sleep(0.1)
start_time = rospy.rostime.get_time()
while (rospy.rostime.get_time() - start_time) < target_time:
print 'Waiting for end time %.6f (current: %.6f)'%(target_time,(rospy.rostime.get_time() - start_time))
time.sleep(0.1)
f0 = os.path.join(roslib.packages.get_pkg_dir('gmapping'),'test','basic_localization_stage_groundtruth')
f1 = os.path.join(roslib.packages.get_pkg_dir('gmapping'),'test','basic_localization_stage_generated')
cmd = ['rosrun', 'map_server', 'map_saver', 'map:=dynamic_map', '-f', f1]
self.assertTrue(subprocess.call(cmd) == 0)
self.cmp_maps(f0,f1)
if __name__ == '__main__':
rostest.run('gmapping', 'gmapping_slam', TestGmapping, sys.argv)