Test Fixtures. More...
#include <gtest/gtest.h>
#include <ros/ros.h>
#include "constrained_ik/constrained_ik.h"
#include "constrained_ik/constraints/goal_pose.h"
#include "constrained_ik/constraints/goal_position.h"
#include "constrained_ik/constraints/goal_orientation.h"
#include "constrained_ik/constraints/avoid_obstacles.h"
#include "constrained_ik/constrained_ik_utils.h"
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/robot_model/joint_model_group.h>
#include <moveit/collision_plugin_loader/collision_plugin_loader.h>
#include <boost/random/uniform_int_distribution.hpp>
Go to the source code of this file.
Classes | |
class | BasicIKTest |
Constrained_IK Test Fixtures Consolidate variable-definitions and init functions for use by multiple tests. More... | |
Functions | |
int | main (int argc, char **argv) |
This executes all tests for the Constraine_IK Class and its constraints. | |
TEST (constrained_ik, nullspaceprojection) | |
This test the Constrained_IK null space project calculation. | |
TEST_F (BasicIKTest, inputValidation) | |
This tests the Constrained_IK init functions. | |
TEST_F (BasicIKTest, calcInvKinInputValidation) | |
This performs input validation test for the Constrained_IK calcInvKin function. | |
TEST_F (BasicIKTest, knownPoses) | |
This tests the Constrained_IK calcInvKin function against known poses using only primary constraint. | |
TEST_F (BasicIKTest, NullMotion) | |
This tests the Constrained_IK calcInvKin function null space motion. | |
TEST_F (BasicIKTest, NullMotionPose) | |
This tests the Constrained_IK calcInvKin function null space motion convergence for known poses. | |
TEST_F (BasicIKTest, obstacleAvoidanceAuxiliaryConstraint) | |
This test the AvoidObstacles constraint The solver is setup with a primary GoalPosition constraint and a axuiliary AvoidObstacles constraint. I then seeds the solver with it current pose with a goal position as the current position and the axuiliary constraint should move the robot in joint space away from its current joint positions while maintaining the starting position of the tcp. | |
TEST_F (BasicIKTest, consistancy) | |
This test checks the consistancy of the axisAngle calculations from a quaternion value Namely does it always return an angle in +/-pi range? (The answer should be yes) | |
Variables | |
const std::string | GROUP_NAME = "manipulator" |
const std::string | ROBOT_DESCRIPTION_PARAM = "robot_description" |
Test Fixtures.
Consolidate variable-definitions and init functions for use by multiple tests.
Definition in file test_constrained_ik.cpp.
const std::string GROUP_NAME = "manipulator" |
Default group name for tests
Definition at line 49 of file test_constrained_ik.cpp.
const std::string ROBOT_DESCRIPTION_PARAM = "robot_description" |
Default ROS parameter for robot description
Definition at line 50 of file test_constrained_ik.cpp.