Skip to content

Commit

Permalink
Merge pull request #202 from Jmeyer1292/test/descartes_tests
Browse files Browse the repository at this point in the history
descartes_tests package
  • Loading branch information
Jonathan Meyer authored Nov 25, 2017
2 parents 429a226 + 2cbd771 commit 3067b21
Show file tree
Hide file tree
Showing 30 changed files with 213 additions and 129 deletions.
3 changes: 0 additions & 3 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,7 @@ compiler:
notifications:
email:
on_failure: always

env:
global:
- BEFORE_SCRIPT='catkin config -w $CATKIN_WORKSPACE --no-install'
matrix:
- USE_DEB=true
ROS_DISTRO="kinetic"
Expand Down
1 change: 0 additions & 1 deletion descartes/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
<run_depend>descartes_planner</run_depend>
<run_depend>descartes_trajectory</run_depend>
<run_depend>descartes_utilities</run_depend>

<export>
<metapackage/>
</export>
Expand Down
16 changes: 0 additions & 16 deletions descartes_moveit/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,22 +59,6 @@ target_link_libraries(descartes_moveit
${catkin_LIBRARIES}
)


#############
## Testing ##
#############

if(CATKIN_ENABLE_TESTING)
find_package(rostest)
set(UTEST_SRC_FILES test/utest.cpp
test/moveit_state_adapter_test.cpp)

add_rostest_gtest(${PROJECT_NAME}_utest test/launch/utest.launch ${UTEST_SRC_FILES})
target_compile_definitions(${PROJECT_NAME}_utest PUBLIC GTEST_USE_OWN_TR1_TUPLE=0)
target_link_libraries(${PROJECT_NAME}_utest descartes_moveit ${catkin_LIBRARIES} ${Boost_LIBRARIES})
endif()


#############
## Install ##
#############
Expand Down
18 changes: 0 additions & 18 deletions descartes_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@ endif()
catkin_package(
INCLUDE_DIRS
include
test
LIBRARIES
descartes_planner
CATKIN_DEPENDS
Expand Down Expand Up @@ -72,20 +71,3 @@ install(
install(
DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})


#############
## Testing ##
#############
if(CATKIN_ENABLE_TESTING)

set(UTEST_PLANNER_SRC_FILES
test/utest.cpp
test/dense_planner.cpp
test/sparse_planner.cpp
test/planning_graph_tests.cpp
test/utils/trajectory_maker.cpp)
catkin_add_gtest(${PROJECT_NAME}_planner_utest ${UTEST_PLANNER_SRC_FILES})
target_link_libraries(${PROJECT_NAME}_planner_utest descartes_planner)

endif()
82 changes: 82 additions & 0 deletions descartes_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
cmake_minimum_required(VERSION 2.8.3)
project(descartes_tests)

add_compile_options(-std=c++11)

find_package(catkin REQUIRED COMPONENTS
descartes_moveit
descartes_planner
descartes_trajectory
)

catkin_package(
INCLUDE_DIRS
include
LIBRARIES
${PROJECT_NAME}
CATKIN_DEPENDS
descartes_moveit
descartes_planner
descartes_trajectory
)

include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_library(${PROJECT_NAME}
src/cartesian_robot.cpp
)

add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

target_link_libraries(${PROJECT_NAME}
${catkin_LIBRARIES}
)

install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h"
)

if(CATKIN_ENABLE_TESTING)
# Trajectory Unit Tests
catkin_add_gtest(${PROJECT_NAME}_trajectory_utest
test/trajectory/utest.cpp
test/trajectory/axial_symmetric_pt.cpp
test/trajectory/cart_trajectory_pt.cpp
test/trajectory/joint_trajectory_pt.cpp
test/trajectory/cartesian_robot_test.cpp
)
target_compile_definitions(${PROJECT_NAME}_trajectory_utest PUBLIC GTEST_USE_OWN_TR1_TUPLE=0)
target_link_libraries(${PROJECT_NAME}_trajectory_utest ${PROJECT_NAME})

# Planner unit tests
catkin_add_gtest(${PROJECT_NAME}_planner_utest
test/planner/utest.cpp
test/planner/dense_planner.cpp
test/planner/sparse_planner.cpp
test/planner/planning_graph_tests.cpp
test/planner/utils/trajectory_maker.cpp
)
target_compile_definitions(${PROJECT_NAME}_planner_utest PUBLIC GTEST_USE_OWN_TR1_TUPLE=0)
target_link_libraries(${PROJECT_NAME}_planner_utest ${PROJECT_NAME})

# Moveit adapter unit tests
find_package(rostest)
add_rostest_gtest(${PROJECT_NAME}_moveit_utest
test/moveit/launch/utest.launch
test/moveit/utest.cpp
test/moveit/moveit_state_adapter_test.cpp
)
target_compile_definitions(${PROJECT_NAME}_moveit_utest PUBLIC GTEST_USE_OWN_TR1_TUPLE=0)
target_link_libraries(${PROJECT_NAME}_moveit_utest ${PROJECT_NAME})

endif()
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include "descartes_core/robot_model.h"

namespace descartes_trajectory_test
namespace descartes_tests
{
/**@brief Cartesian Robot used for test purposes. This is a simple robot with simple kinematics. Each
* joint corresponds to a cartesian direction (i.e. x, y, R, P, Y) (don't ask me how this is built, it
Expand Down
22 changes: 22 additions & 0 deletions descartes_tests/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0"?>
<package>
<name>descartes_tests</name>
<version>0.1.0</version>
<description>
A package dedicated to unit tests for the Descartes cartesian path
planning library.
</description>

<maintainer email="[email protected]">Jonathan Meyer</maintainer>
<license>Apache 2.0</license>

<test_depend>gtest</test_depend>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>descartes_moveit</build_depend>
<build_depend>descartes_planner</build_depend>
<build_depend>descartes_trajectory</build_depend>
<run_depend>descartes_moveit</run_depend>
<run_depend>descartes_planner</run_depend>
<run_depend>descartes_trajectory</run_depend>

</package>
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,13 @@
* limitations under the License.
*/

#include "descartes_trajectory_test/cartesian_robot.h"
#include "descartes_tests/cartesian_robot.h"
#include "descartes_core/pretty_print.hpp"
#include "eigen_conversions/eigen_kdl.h"
#include "ros/console.h"
#include "ros/assert.h"

namespace descartes_trajectory_test
namespace descartes_tests
{
const static int DOF = 6;

Expand Down Expand Up @@ -160,4 +160,4 @@ bool CartesianRobot::isValid(const Eigen::Affine3d &pose) const
}


} // descartes_trajectory_test
}
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- URDF file (including path) -->
<arg name="urdf_file" default="$(find descartes_moveit)/test/resources/kuka_kr210/kr210l150.urdf"/>
<arg name="urdf_file" default="$(find descartes_tests)/test/moveit/resources/kuka_kr210/kr210l150.urdf"/>

<!-- Launch test node -->
<arg name="run_test_node" default="true"/>
Expand All @@ -15,16 +15,16 @@
<param name="$(arg robot_description)" textfile="$(arg urdf_file)"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find descartes_moveit)/test/resources/kuka_kr210/kuka_kr210.srdf" />
<param name="$(arg robot_description)_semantic" textfile="$(find descartes_tests)/test/moveit/resources/kuka_kr210/kuka_kr210.srdf" />

<!-- Load updated joint limits (override information from URDF) -->
<group ns="$(arg robot_description)_planning">
<rosparam command="load" file="$(find descartes_moveit)/test/resources/kuka_kr210/joint_limits.yaml"/>
<rosparam command="load" file="$(find descartes_tests)/test/moveit/resources/kuka_kr210/joint_limits.yaml"/>
</group>

<!-- Load default settings for kinematics; these settings are overridden by settings in a node's namespace -->
<group ns="$(arg robot_description)_kinematics">
<rosparam command="load" file="$(find descartes_moveit)/test/resources/kuka_kr210/kinematics.yaml"/>
<rosparam command="load" file="$(find descartes_tests)/test/moveit/resources/kuka_kr210/kinematics.yaml"/>
</group>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,13 @@



<include file="$(find descartes_moveit)/test/launch/moveit_state_adapter.launch">
<include file="$(find descartes_tests)/test/moveit/launch/moveit_state_adapter.launch">
<arg name="robot_description" value="$(arg robot_description)"/>
<arg name="urdf_file" value="$(find descartes_moveit)/test/resources/kuka_kr210/kr210l150.urdf"/>
<arg name="urdf_file" value="$(find descartes_tests)/test/moveit/resources/kuka_kr210/kr210l150.urdf"/>
<arg name="run_test_node" value="$(arg run_test_node)"/>
</include>

<!-- Test Node -->
<test test-name="utest" pkg="descartes_moveit" type="descartes_moveit_utest" if="$(arg run_test_node)"/>
<test test-name="utest" pkg="descartes_tests" type="descartes_tests_moveit_utest" if="$(arg run_test_node)"/>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -17,17 +17,17 @@
*/

#include "descartes_moveit/moveit_state_adapter.h"
#include <descartes_trajectory_test/robot_model_test.hpp>
#include "moveit/robot_model_loader/robot_model_loader.h"
#include <gtest/gtest.h>
#include "../trajectory/robot_model_test.hpp"

using namespace descartes_moveit;
using namespace descartes_trajectory;
using namespace descartes_core;

using testing::Types;

namespace descartes_trajectory_test
namespace descartes_tests
{
// This variable must be global in order for the test to pass.
// Destructing the robot model results in a boost mutex exception:
Expand Down Expand Up @@ -56,7 +56,7 @@ RobotModelPtr CreateRobotModel<descartes_moveit::MoveitStateAdapter>()
}

template <class T>
class MoveitRobotModelTest : public descartes_trajectory_test::RobotModelTest<T>
class MoveitRobotModelTest : public descartes_tests::RobotModelTest<T>
{
};

Expand Down
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <ros/console.h>
#include <descartes_core/path_planner_base.h>
#include <descartes_trajectory_test/cartesian_robot.h>
#include <descartes_tests/cartesian_robot.h>

#include "utils/trajectory_maker.h"

Expand All @@ -20,7 +20,7 @@ class PathPlannerTest : public testing::Test
}

PathPlannerTest()
: velocity_limits_(6, 1.0), robot_(new descartes_trajectory_test::CartesianRobot(5.0, 0.001, velocity_limits_))
: velocity_limits_(6, 1.0), robot_(new descartes_tests::CartesianRobot(5.0, 0.001, velocity_limits_))
{
ros::Time::init();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

#include <descartes_planner/planning_graph.h>
#include <descartes_trajectory/joint_trajectory_pt.h>
#include <descartes_trajectory_test/cartesian_robot.h>
#include <descartes_tests/cartesian_robot.h>
#include <boost/make_shared.hpp>

#include <gtest/gtest.h>
Expand All @@ -28,7 +28,7 @@ static boost::shared_ptr<descartes_core::RobotModel> makeTestRobot()
const auto max_joint_vel = 1.0;
const auto dof = 6;
return boost::shared_ptr<descartes_core::RobotModel>(
new descartes_trajectory_test::CartesianRobot(5.0, 0.001, std::vector<double>(dof, max_joint_vel))
new descartes_tests::CartesianRobot(5.0, 0.001, std::vector<double>(dof, max_joint_vel))
);
}

Expand Down
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,11 @@

#include "descartes_trajectory/axial_symmetric_pt.h"
#include "descartes_core/utils.h"
#include "descartes_trajectory_test/cartesian_robot.h"
#include "descartes_tests/cartesian_robot.h"
#include <gtest/gtest.h>

using namespace descartes_trajectory;
using namespace descartes_trajectory_test;
using namespace descartes_tests;

// Does it have a default constructor
TEST(AxialSymPt, construction)
Expand Down
Loading

0 comments on commit 3067b21

Please sign in to comment.