|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include "load_test_robot.h"#include <memory>#include <string>#include <iostream>#include <gtest/gtest.h>#include <Eigen/Dense>#include <moveit/robot_model/robot_model.h>#include <moveit/robot_state/robot_state.h>#include <moveit/robot_state/conversions.h>#include <moveit/utils/robot_model_test_utils.h>#include <moveit/ompl_interface/detail/ompl_constraints.h>#include <moveit_msgs/msg/constraints.hpp>#include <ompl/util/Exception.h>#include <ompl/base/spaces/RealVectorStateSpace.h>#include <ompl/base/spaces/constraint/ProjectedStateSpace.h>#include <ompl/base/ConstrainedSpaceInformation.h>
Go to the source code of this file.
Classes | |
| class | TestOMPLConstraints |
| class | PandaConstraintTest |
| class | FanucConstraintTest |
| class | PR2LeftArmConstraintTest |
Functions | |
| moveit_msgs::msg::PositionConstraint | createPositionConstraint (std::string &base_link, std::string &ee_link) |
| Helper function to create a specific position constraint. More... | |
| TEST_F (PandaConstraintTest, InitPositionConstraint) | |
| TEST_F (PandaConstraintTest, PositionConstraintJacobian) | |
| TEST_F (PandaConstraintTest, PositionConstraintOMPLCheck) | |
| TEST_F (PandaConstraintTest, EqualityPositionConstraints) | |
| TEST_F (FanucConstraintTest, InitPositionConstraint) | |
| TEST_F (FanucConstraintTest, PositionConstraintJacobian) | |
| TEST_F (FanucConstraintTest, PositionConstraintOMPLCheck) | |
| TEST_F (FanucConstraintTest, EqualityPositionConstraints) | |
| TEST_F (PR2LeftArmConstraintTest, InitPositionConstraint) | |
| TEST_F (PR2LeftArmConstraintTest, PositionConstraintJacobian) | |
| TEST_F (PR2LeftArmConstraintTest, PositionConstraintOMPLCheck) | |
| TEST_F (PR2LeftArmConstraintTest, EqualityPositionConstraints) | |
| int | main (int argc, char **argv) |
Variables | |
| constexpr int | NUM_RANDOM_TESTS = 10 |
| Number of times to run a test that uses randomly generated input. More... | |
| constexpr unsigned int | DIFFERENT_LINK_OFFSET = 2 |
| Select a robot link at (num_dofs - different_link_offset) to test another link than the end-effector. More... | |
| constexpr double | JAC_ERROR_TOLERANCE = 1e-4 |
| Allowed error when comparing Jacobian matrix error. More... | |
| moveit_msgs::msg::PositionConstraint createPositionConstraint | ( | std::string & | base_link, |
| std::string & | ee_link | ||
| ) |
Helper function to create a specific position constraint.
Definition at line 81 of file test_ompl_constraints.cpp.

| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 436 of file test_ompl_constraints.cpp.
| TEST_F | ( | FanucConstraintTest | , |
| EqualityPositionConstraints | |||
| ) |
Definition at line 382 of file test_ompl_constraints.cpp.
| TEST_F | ( | FanucConstraintTest | , |
| InitPositionConstraint | |||
| ) |
Definition at line 355 of file test_ompl_constraints.cpp.
| TEST_F | ( | FanucConstraintTest | , |
| PositionConstraintJacobian | |||
| ) |
Definition at line 361 of file test_ompl_constraints.cpp.
| TEST_F | ( | FanucConstraintTest | , |
| PositionConstraintOMPLCheck | |||
| ) |
Definition at line 371 of file test_ompl_constraints.cpp.
| TEST_F | ( | PandaConstraintTest | , |
| EqualityPositionConstraints | |||
| ) |
Definition at line 338 of file test_ompl_constraints.cpp.
| TEST_F | ( | PandaConstraintTest | , |
| InitPositionConstraint | |||
| ) |
Definition at line 311 of file test_ompl_constraints.cpp.
| TEST_F | ( | PandaConstraintTest | , |
| PositionConstraintJacobian | |||
| ) |
Definition at line 317 of file test_ompl_constraints.cpp.
| TEST_F | ( | PandaConstraintTest | , |
| PositionConstraintOMPLCheck | |||
| ) |
Definition at line 327 of file test_ompl_constraints.cpp.
| TEST_F | ( | PR2LeftArmConstraintTest | , |
| EqualityPositionConstraints | |||
| ) |
Definition at line 426 of file test_ompl_constraints.cpp.
| TEST_F | ( | PR2LeftArmConstraintTest | , |
| InitPositionConstraint | |||
| ) |
Definition at line 400 of file test_ompl_constraints.cpp.
| TEST_F | ( | PR2LeftArmConstraintTest | , |
| PositionConstraintJacobian | |||
| ) |
Definition at line 406 of file test_ompl_constraints.cpp.
| TEST_F | ( | PR2LeftArmConstraintTest | , |
| PositionConstraintOMPLCheck | |||
| ) |
Definition at line 416 of file test_ompl_constraints.cpp.
|
constexpr |
Select a robot link at (num_dofs - different_link_offset) to test another link than the end-effector.
Definition at line 71 of file test_ompl_constraints.cpp.
|
constexpr |
Allowed error when comparing Jacobian matrix error.
High tolerance because of high finite difference error. (And it is the L1-norm over the whole matrix difference.)
Definition at line 78 of file test_ompl_constraints.cpp.
|
constexpr |
Number of times to run a test that uses randomly generated input.
Definition at line 68 of file test_ompl_constraints.cpp.