Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Namespaces | Functions
kinematics_test_utils.h File Reference
#include <tesseract_common/macros.h>
#include <gtest/gtest.h>
#include <fstream>
#include <yaml-cpp/yaml.h>
#include <tesseract_kinematics/core/forward_kinematics.h>
#include <tesseract_kinematics/core/inverse_kinematics.h>
#include <tesseract_kinematics/core/utils.h>
#include <tesseract_kinematics/core/types.h>
#include <tesseract_kinematics/core/kinematic_group.h>
#include <tesseract_kinematics/core/kinematics_plugin_factory.h>
#include <tesseract_kinematics/core/validate.h>
#include <tesseract_scene_graph/graph.h>
#include <tesseract_state_solver/kdl/kdl_state_solver.h>
#include <tesseract_urdf/urdf_parser.h>
#include <tesseract_common/utils.h>
#include <tesseract_support/tesseract_support_resource_locator.h>
Include dependency graph for kinematics_test_utils.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  tesseract_kinematics
 
namespace  tesseract_kinematics::test_suite
 

Functions

tesseract_scene_graph::SceneGraph::UPtr tesseract_kinematics::test_suite::getSceneGraphIIWA ()
 
tesseract_scene_graph::SceneGraph::UPtr tesseract_kinematics::test_suite::getSceneGraphABBExternalPositioner ()
 
tesseract_scene_graph::SceneGraph::UPtr tesseract_kinematics::test_suite::getSceneGraphABBOnPositioner ()
 
tesseract_scene_graph::SceneGraph::UPtr tesseract_kinematics::test_suite::getSceneGraphABB ()
 
tesseract_scene_graph::SceneGraph::UPtr tesseract_kinematics::test_suite::getSceneGraphIIWA7 ()
 
tesseract_scene_graph::SceneGraph::UPtr tesseract_kinematics::test_suite::getSceneGraphUR (const tesseract_kinematics::URParameters &params, double shoulder_offset, double elbow_offset)
 
tesseract_common::KinematicLimits tesseract_kinematics::test_suite::getTargetLimits (const tesseract_scene_graph::SceneGraph &scene_graph, const std::vector< std::string > &joint_names)
 
void tesseract_kinematics::test_suite::runJacobianTest (tesseract_kinematics::ForwardKinematics &kin, const Eigen::VectorXd &jvals, const std::string &link_name, const Eigen::Vector3d &link_point, const Eigen::Isometry3d &change_base)
 Run a kinematic jacobian test. More...
 
void tesseract_kinematics::test_suite::runJacobianTest (tesseract_kinematics::KinematicGroup &kin_group, const Eigen::VectorXd &jvals, const std::string &link_name, const Eigen::Vector3d &link_point)
 Run a kinematic jacobian test. More...
 
void tesseract_kinematics::test_suite::runKinJointLimitsTest (const tesseract_common::KinematicLimits &limits, const tesseract_common::KinematicLimits &target_limits)
 Run kinematic limits test. More...
 
void tesseract_kinematics::test_suite::runKinSetJointLimitsTest (tesseract_kinematics::KinematicGroup &kin_group)
 Run kinematics setJointLimits function test. More...
 
void tesseract_kinematics::test_suite::runStringVectorEqualTest (const std::vector< std::string > &names, const std::vector< std::string > &target_names)
 Check if two vectors of strings are equal but ignore order. More...
 
void tesseract_kinematics::test_suite::runInvKinTest (const tesseract_kinematics::InverseKinematics &inv_kin, const tesseract_kinematics::ForwardKinematics &fwd_kin, const Eigen::Isometry3d &target_pose, const std::string &tip_link_name, const Eigen::VectorXd &seed)
 Run inverse kinematics test comparing the inverse solution to the forward solution. More...
 
void tesseract_kinematics::test_suite::runInvKinTest (const tesseract_kinematics::KinematicGroup &kin_group, const Eigen::Isometry3d &target_pose, const std::string &working_frame, const std::string &tip_link_name, const Eigen::VectorXd &seed)
 Run inverse kinematics test comparing the inverse solution to the forward solution. More...
 
void tesseract_kinematics::test_suite::runFwdKinIIWATest (tesseract_kinematics::ForwardKinematics &kin)
 
void tesseract_kinematics::test_suite::runJacobianIIWATest (tesseract_kinematics::ForwardKinematics &kin, bool is_kin_tree=false)
 
void tesseract_kinematics::test_suite::runKinGroupJacobianIIWATest (tesseract_kinematics::KinematicGroup &kin_group)
 
void tesseract_kinematics::test_suite::runActiveLinkNamesIIWATest (const tesseract_kinematics::KinematicGroup &kin_group)
 
void tesseract_kinematics::test_suite::runActiveLinkNamesABBTest (const tesseract_kinematics::KinematicGroup &kin_group)
 
void tesseract_kinematics::test_suite::runActiveLinkNamesURTest (const tesseract_kinematics::KinematicGroup &kin_group)
 
void tesseract_kinematics::test_suite::runKinGroupJacobianABBOnPositionerTest (tesseract_kinematics::KinematicGroup &kin_group)
 
void tesseract_kinematics::test_suite::runActiveLinkNamesABBOnPositionerTest (const tesseract_kinematics::KinematicGroup &kin_group)
 
void tesseract_kinematics::test_suite::runKinGroupJacobianABBExternalPositionerTest (tesseract_kinematics::KinematicGroup &kin_group)
 
void tesseract_kinematics::test_suite::runActiveLinkNamesABBExternalPositionerTest (const tesseract_kinematics::KinematicGroup &kin_group)
 
void tesseract_kinematics::test_suite::runInvKinIIWATest (const tesseract_kinematics::KinematicsPluginFactory &factory, const std::string &inv_factory_name, const std::string &fwd_factory_name)