Functions | Variables
test_maps.cpp File Reference
#include <gtest/gtest.h>
#include <ros/ros.h>
#include <exotica_core/exotica_core.h>
#include <exotica_core/tools/test_helpers.h>
Include dependency graph for test_maps.cpp:

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 
UnconstrainedEndPoseProblemPtr setup_problem (Initializer &map, const std::string &collision_scene="", const std::vector< Initializer > &links=std::vector< Initializer >())
 
UnconstrainedTimeIndexedProblemPtr setup_time_indexed_problem (Initializer &map)
 
 TEST (ExoticaTaskMaps, testEffPositionXY)
 
 TEST (ExoticaTaskMaps, testEffPosition)
 
 TEST (ExoticaTaskMaps, testEffOrientation)
 
 TEST (ExoticaTaskMaps, testEffAxisAlignment)
 
 TEST (ExoticaTaskMaps, testEffFrame)
 
 TEST (ExoticaTaskMaps, testEffVelocity)
 
 TEST (ExoticaTaskMaps, testDistance)
 
 TEST (ExoticaTaskMaps, testDistanceToLine2D)
 
 TEST (ExoticaTaskMaps, testJointLimit)
 
 TEST (ExoticaTaskMaps, testJointTorqueMinimizationProxy)
 
 TEST (ExoticaTaskMaps, testSphereCollision)
 
 TEST (ExoticaTaskMaps, testJointPose)
 
 TEST (ExoticaTaskMaps, testCoM)
 
 TEST (ExoticaTaskMaps, testContinuousJointPose)
 
 TEST (ExoticaTaskMaps, testIMesh)
 
 TEST (ExoticaTaskMaps, testPoint2Line)
 
 TEST (ExoticaTaskMaps, testPoint2Plane)
 
 TEST (ExoticaTaskMaps, testCollisionDistance)
 
 TEST (ExoticaTaskMaps, testSmoothCollisionDistance)
 
 TEST (ExoticaTaskMaps, testQuasiStatic)
 
 TEST (ExoticaTaskMaps, testJointSmoothingBackwardDifference)
 
 TEST (ExoticaTaskMaps, testAvoidLookAtSphere)
 
 TEST (ExoticaTaskMaps, testLookAt)
 
 TEST (ExoticaTaskMaps, testManipulability)
 
bool test_hessian (UnconstrainedEndPoseProblemPtr problem, const double eps=1e-5)
 
bool test_jacobian (UnconstrainedEndPoseProblemPtr problem, const double eps=1e-5)
 
template<class T >
bool test_jacobian_time_indexed (std::shared_ptr< T > problem, TimeIndexedTask &task, int t, const double eps=1e-5)
 
bool test_random (UnconstrainedEndPoseProblemPtr problem)
 
bool test_random (UnconstrainedTimeIndexedProblemPtr problem)
 
bool test_values (Eigen::MatrixXdRefConst Xref, Eigen::MatrixXdRefConst Yref, Eigen::MatrixXdRefConst Jref, UnconstrainedEndPoseProblemPtr problem, const double eps=1e-5)
 

Variables

constexpr int num_trials_ = 100
 
constexpr bool print_debug_information_ = false
 
static const std::string srdf_string_ = "<robot name=\"test_robot\"><group name=\"arm\"><chain base_link=\"base\" tip_link=\"endeff\" /></group><virtual_joint name=\"world_joint\" type=\"fixed\" parent_frame=\"world_frame\" child_link=\"base\" /><group_state name=\"zero\" group=\"arm\"><joint name=\"joint1\" value=\"0\" /><joint name=\"joint2\" value=\"0.3\" /><joint name=\"joint3\" value=\"0.55\" /></group_state><disable_collisions link1=\"base\" link2=\"link1\" reason=\"Adjacent\" /><disable_collisions link1=\"endeff\" link2=\"link3\" reason=\"Adjacent\" /><disable_collisions link1=\"link1\" link2=\"link2\" reason=\"Adjacent\" /><disable_collisions link1=\"link2\" link2=\"link3\" reason=\"Adjacent\" /></robot>"
 
static const std::string urdf_string_ = "<robot name=\"test_robot\"><link name=\"base\"><visual><geometry><cylinder length=\"0.3\" radius=\"0.2\"/></geometry><origin xyz=\"0 0 0.15\"/></visual><collision><geometry><cylinder length=\"0.3\" radius=\"0.2\"/></geometry><origin xyz=\"0 0 0.15\"/></collision></link><link name=\"link1\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.15\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.075\"/></visual><collision><geometry><cylinder length=\"0.15\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.075\"/></collision></link><link name=\"link2\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.35\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.175\"/></visual><collision><geometry><cylinder length=\"0.35\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.175\"/></collision></link><link name=\"link3\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.45\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.225\"/></visual><collision><geometry><cylinder length=\"0.45\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.225\"/></collision></link><link name=\"endeff\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.05\" radius=\"0.1\"/></geometry><origin xyz=\"0 0 -0.025\"/></visual><collision><geometry><cylinder length=\"0.05\" radius=\"0.1\"/></geometry><origin xyz=\"0 0 -0.025\"/></collision></link><joint name=\"joint1\" type=\"revolute\"><parent link=\"base\"/><child link=\"link1\"/><origin xyz=\"0 0 0.3\" rpy=\"0 0 0\" /><axis xyz=\"0 0 1\" /><limit effort=\"200\" velocity=\"1.0\" lower=\"-0.4\" upper=\"0.4\"/><safety_controller k_position=\"30\" k_velocity=\"30\" soft_lower_limit=\"-0.4\" soft_upper_limit=\"0.4\"/></joint><joint name=\"joint2\" type=\"revolute\"><parent link=\"link1\"/><child link=\"link2\"/><origin xyz=\"0 0 0.15\" rpy=\"0 0 0\" /><axis xyz=\"0 1 0\" /><limit effort=\"200\" velocity=\"1.0\" lower=\"-0.4\" upper=\"0.4\"/><safety_controller k_position=\"30\" k_velocity=\"30\" soft_lower_limit=\"-0.4\" soft_upper_limit=\"0.4\"/></joint><joint name=\"joint3\" type=\"revolute\"><parent link=\"link2\"/><child link=\"link3\"/><origin xyz=\"0 0 0.35\" rpy=\"0 0 0\" /><axis xyz=\"0 1 0\" /><limit effort=\"200\" velocity=\"1.0\" lower=\"-0.4\" upper=\"0.4\"/><safety_controller k_position=\"30\" k_velocity=\"30\" soft_lower_limit=\"-0.4\" soft_upper_limit=\"0.4\"/></joint><joint name=\"joint4\" type=\"fixed\"><parent link=\"link3\"/><child link=\"endeff\"/><origin xyz=\"0 0 0.45\" rpy=\"0 0 0\" /></joint></robot>"
 

Function Documentation

int main ( int  argc,
char **  argv 
)

Definition at line 1336 of file test_maps.cpp.

UnconstrainedEndPoseProblemPtr setup_problem ( Initializer map,
const std::string &  collision_scene = "",
const std::vector< Initializer > &  links = std::vector<Initializer>() 
)

Definition at line 239 of file test_maps.cpp.

UnconstrainedTimeIndexedProblemPtr setup_time_indexed_problem ( Initializer map)

Definition at line 278 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testEffPositionXY   
)

Definition at line 309 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testEffPosition   
)

Definition at line 327 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testEffOrientation   
)

Definition at line 358 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testEffAxisAlignment   
)

Definition at line 386 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testEffFrame   
)

Definition at line 405 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testEffVelocity   
)

Definition at line 448 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testDistance   
)

Definition at line 476 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testDistanceToLine2D   
)

Definition at line 511 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testJointLimit   
)

Definition at line 545 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testJointTorqueMinimizationProxy   
)

Definition at line 563 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testSphereCollision   
)

Definition at line 644 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testJointPose   
)

Definition at line 681 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testCoM   
)

Definition at line 787 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testContinuousJointPose   
)

Definition at line 936 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testIMesh   
)

Definition at line 953 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testPoint2Line   
)

Definition at line 1036 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testPoint2Plane   
)

Definition at line 1061 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testCollisionDistance   
)

Definition at line 1093 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testSmoothCollisionDistance   
)

Definition at line 1113 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testQuasiStatic   
)

Definition at line 1139 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testJointSmoothingBackwardDifference   
)

Definition at line 1209 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testAvoidLookAtSphere   
)

Definition at line 1260 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testLookAt   
)

Definition at line 1288 of file test_maps.cpp.

TEST ( ExoticaTaskMaps  ,
testManipulability   
)

Definition at line 1313 of file test_maps.cpp.

bool test_hessian ( UnconstrainedEndPoseProblemPtr  problem,
const double  eps = 1e-5 
)

Definition at line 156 of file test_maps.cpp.

bool test_jacobian ( UnconstrainedEndPoseProblemPtr  problem,
const double  eps = 1e-5 
)

Definition at line 115 of file test_maps.cpp.

template<class T >
bool test_jacobian_time_indexed ( std::shared_ptr< T >  problem,
TimeIndexedTask task,
int  t,
const double  eps = 1e-5 
)

Definition at line 204 of file test_maps.cpp.

bool test_random ( UnconstrainedEndPoseProblemPtr  problem)

Definition at line 49 of file test_maps.cpp.

bool test_random ( UnconstrainedTimeIndexedProblemPtr  problem)

Definition at line 68 of file test_maps.cpp.

bool test_values ( Eigen::MatrixXdRefConst  Xref,
Eigen::MatrixXdRefConst  Yref,
Eigen::MatrixXdRefConst  Jref,
UnconstrainedEndPoseProblemPtr  problem,
const double  eps = 1e-5 
)

Definition at line 81 of file test_maps.cpp.

Variable Documentation

constexpr int num_trials_ = 100

Definition at line 47 of file test_maps.cpp.

constexpr bool print_debug_information_ = false

Definition at line 46 of file test_maps.cpp.

const std::string srdf_string_ = "<robot name=\"test_robot\"><group name=\"arm\"><chain base_link=\"base\" tip_link=\"endeff\" /></group><virtual_joint name=\"world_joint\" type=\"fixed\" parent_frame=\"world_frame\" child_link=\"base\" /><group_state name=\"zero\" group=\"arm\"><joint name=\"joint1\" value=\"0\" /><joint name=\"joint2\" value=\"0.3\" /><joint name=\"joint3\" value=\"0.55\" /></group_state><disable_collisions link1=\"base\" link2=\"link1\" reason=\"Adjacent\" /><disable_collisions link1=\"endeff\" link2=\"link3\" reason=\"Adjacent\" /><disable_collisions link1=\"link1\" link2=\"link2\" reason=\"Adjacent\" /><disable_collisions link1=\"link2\" link2=\"link3\" reason=\"Adjacent\" /></robot>"
static

Definition at line 44 of file test_maps.cpp.

const std::string urdf_string_ = "<robot name=\"test_robot\"><link name=\"base\"><visual><geometry><cylinder length=\"0.3\" radius=\"0.2\"/></geometry><origin xyz=\"0 0 0.15\"/></visual><collision><geometry><cylinder length=\"0.3\" radius=\"0.2\"/></geometry><origin xyz=\"0 0 0.15\"/></collision></link><link name=\"link1\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.15\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.075\"/></visual><collision><geometry><cylinder length=\"0.15\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.075\"/></collision></link><link name=\"link2\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.35\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.175\"/></visual><collision><geometry><cylinder length=\"0.35\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.175\"/></collision></link><link name=\"link3\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.45\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.225\"/></visual><collision><geometry><cylinder length=\"0.45\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.225\"/></collision></link><link name=\"endeff\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.05\" radius=\"0.1\"/></geometry><origin xyz=\"0 0 -0.025\"/></visual><collision><geometry><cylinder length=\"0.05\" radius=\"0.1\"/></geometry><origin xyz=\"0 0 -0.025\"/></collision></link><joint name=\"joint1\" type=\"revolute\"><parent link=\"base\"/><child link=\"link1\"/><origin xyz=\"0 0 0.3\" rpy=\"0 0 0\" /><axis xyz=\"0 0 1\" /><limit effort=\"200\" velocity=\"1.0\" lower=\"-0.4\" upper=\"0.4\"/><safety_controller k_position=\"30\" k_velocity=\"30\" soft_lower_limit=\"-0.4\" soft_upper_limit=\"0.4\"/></joint><joint name=\"joint2\" type=\"revolute\"><parent link=\"link1\"/><child link=\"link2\"/><origin xyz=\"0 0 0.15\" rpy=\"0 0 0\" /><axis xyz=\"0 1 0\" /><limit effort=\"200\" velocity=\"1.0\" lower=\"-0.4\" upper=\"0.4\"/><safety_controller k_position=\"30\" k_velocity=\"30\" soft_lower_limit=\"-0.4\" soft_upper_limit=\"0.4\"/></joint><joint name=\"joint3\" type=\"revolute\"><parent link=\"link2\"/><child link=\"link3\"/><origin xyz=\"0 0 0.35\" rpy=\"0 0 0\" /><axis xyz=\"0 1 0\" /><limit effort=\"200\" velocity=\"1.0\" lower=\"-0.4\" upper=\"0.4\"/><safety_controller k_position=\"30\" k_velocity=\"30\" soft_lower_limit=\"-0.4\" soft_upper_limit=\"0.4\"/></joint><joint name=\"joint4\" type=\"fixed\"><parent link=\"link3\"/><child link=\"endeff\"/><origin xyz=\"0 0 0.45\" rpy=\"0 0 0\" /></joint></robot>"
static

Definition at line 43 of file test_maps.cpp.



exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:36:09