50#include <gtest/gtest.h>
58#include <moveit_msgs/msg/constraints.hpp>
61#include <ompl/util/Exception.h>
62#include <ompl/base/spaces/RealVectorStateSpace.h>
63#include <ompl/base/spaces/constraint/ProjectedStateSpace.h>
64#include <ompl/base/ConstrainedSpaceInformation.h>
87 shape_msgs::msg::SolidPrimitive box_constraint;
88 box_constraint.type = shape_msgs::msg::SolidPrimitive::BOX;
89 box_constraint.dimensions = { 0.05, 0.4, 0.05 };
91 geometry_msgs::msg::Pose box_pose;
92 box_pose.position.x = 0.9;
93 box_pose.position.y = 0.0;
94 box_pose.position.z = 0.2;
95 box_pose.orientation.w = 1.0;
97 moveit_msgs::msg::PositionConstraint position_constraint;
98 position_constraint.header.frame_id = base_link;
99 position_constraint.link_name = ee_link;
100 position_constraint.constraint_region.primitives.push_back(box_constraint);
101 position_constraint.constraint_region.primitive_poses.push_back(box_pose);
103 return position_constraint;
123 const Eigen::Isometry3d
fk(
const Eigen::VectorXd& q,
const std::string& link_name)
const
132 Eigen::VectorXd joint_positions;
134 return joint_positions;
139 const double h = 1e-6;
141 Eigen::MatrixXd jacobian = Eigen::MatrixXd::Zero(3,
num_dofs_);
146 for (std::size_t dim = 0; dim <
num_dofs_; ++dim)
148 Eigen::Vector3d pos =
fk(q, link_name).translation();
149 Eigen::Vector3d pos_plus_h =
fk(q + m_helper.col(dim), link_name).translation();
150 Eigen::Vector3d col = (pos_plus_h - pos) / h;
151 jacobian.col(dim) = col;
158 moveit_msgs::msg::Constraints constraint_msgs;
170 RCLCPP_DEBUG_STREAM(
getLogger(), different_link);
172 moveit_msgs::msg::Constraints constraint_msgs;
185 pos_con_msg.constraint_region.primitives.at(0).dimensions[0] = 0.0005;
188 pos_con_msg.constraint_region.primitives.at(0).dimensions[1] = 1.0;
189 pos_con_msg.constraint_region.primitives.at(0).dimensions[2] = 1.0;
191 moveit_msgs::msg::Constraints constraint_msgs;
192 constraint_msgs.position_constraints.push_back(pos_con_msg);
195 constraint_msgs.name =
"use_equality_constraints";
203 SCOPED_TRACE(
"testJacobian");
205 double total_error = 999.9;
210 auto jac_exact =
constraint_->calcErrorJacobian(q);
214 RCLCPP_DEBUG_STREAM(
getLogger(),
"Analytical jacobian:");
215 RCLCPP_DEBUG_STREAM(
getLogger(), jac_exact);
216 RCLCPP_DEBUG_STREAM(
getLogger(),
"Finite difference jacobian:");
217 RCLCPP_DEBUG_STREAM(
getLogger(), jac_approx);
219 total_error = (jac_exact - jac_approx).lpNorm<1>();
226 SCOPED_TRACE(
"testOMPLProjectedStateSpaceConstruction");
228 auto state_space = std::make_shared<ompl::base::RealVectorStateSpace>(
num_dofs_);
229 ompl::base::RealVectorBounds bounds(
num_dofs_);
235 for (std::size_t i = 0; i <
num_dofs_; ++i)
239 bounds.setHigh(i,
joint_limits[i]->at(0).max_position_);
242 state_space->setBounds(bounds);
244 auto constrained_state_space = std::make_shared<ompl::base::ProjectedStateSpace>(state_space,
constraint_);
248 auto constrained_state_space_info =
249 std::make_shared<ompl::base::ConstrainedSpaceInformation>(constrained_state_space);
258 constrained_state_space->sanityChecks();
260 catch (ompl::Exception& ex)
262 RCLCPP_ERROR(
getLogger(),
"Sanity checks did not pass: %s", ex.what());
268 SCOPED_TRACE(
"testEqualityPositionConstraints");
270 EXPECT_NE(
constraint_,
nullptr) <<
"First call setEqualityPositionConstraints before calling this test.";
281 EXPECT_DOUBLE_EQ(f[1], 0.0);
282 EXPECT_DOUBLE_EQ(f[2], 0.0);
288 for (std::size_t i = 0; i <
num_dofs_; ++i)
291 EXPECT_DOUBLE_EQ(jac(1, i), 0.0);
292 EXPECT_DOUBLE_EQ(jac(2, i), 0.0);
296 EXPECT_NE(f[0], 0.0);
297 EXPECT_NE(jac.row(0).squaredNorm(), 0.0);
317 setPositionConstraints();
318 setPositionConstraintsDifferentLink();
323 setPositionConstraints();
327 setPositionConstraintsDifferentLink();
333 setPositionConstraints();
334 testOMPLProjectedStateSpaceConstruction();
338 setPositionConstraintsDifferentLink();
339 testOMPLProjectedStateSpaceConstruction();
344 setEqualityPositionConstraints();
345 testOMPLProjectedStateSpaceConstruction();
346 testEqualityPositionConstraints();
361 setPositionConstraints();
362 setPositionConstraintsDifferentLink();
367 setPositionConstraints();
371 setPositionConstraintsDifferentLink();
377 setPositionConstraints();
378 testOMPLProjectedStateSpaceConstruction();
382 setPositionConstraintsDifferentLink();
383 testOMPLProjectedStateSpaceConstruction();
388 setEqualityPositionConstraints();
389 testOMPLProjectedStateSpaceConstruction();
390 testEqualityPositionConstraints();
406 setPositionConstraints();
407 setPositionConstraintsDifferentLink();
412 setPositionConstraints();
416 setPositionConstraintsDifferentLink();
422 setPositionConstraints();
423 testOMPLProjectedStateSpaceConstruction();
426 setPositionConstraintsDifferentLink();
427 testOMPLProjectedStateSpaceConstruction();
432 setEqualityPositionConstraints();
433 testOMPLProjectedStateSpaceConstruction();
434 testEqualityPositionConstraints();
442 testing::InitGoogleTest(&argc, argv);
443 return RUN_ALL_TESTS();
PR2LeftArmConstraintTest()
TestOMPLConstraints(const std::string &robot_name, const std::string &group_name)
std::shared_ptr< ompl_interface::BaseConstraint > constraint_
void setPositionConstraints()
Eigen::VectorXd getRandomState()
void testOMPLProjectedStateSpaceConstruction()
const Eigen::Isometry3d fk(const Eigen::VectorXd &q, const std::string &link_name) const
Robot forward kinematics.
Eigen::MatrixXd numericalJacobianPosition(const Eigen::VectorXd &q, const std::string &link_name) const
void testEqualityPositionConstraints()
void setEqualityPositionConstraints()
void setPositionConstraintsDifferentLink()
Test position constraints a link that is not the end-effector.
const JointBoundsVector & getActiveJointModelsBounds() const
Get the bounds for all the active joints.
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
Robot independent test class setup.
moveit::core::RobotStatePtr robot_state_
Eigen::VectorXd getDeterministicState() const
Create a joint position vector with values 0.1, 0.2, 0.3, ... where the length depends on the number ...
moveit::core::RobotModelPtr robot_model_
std::string ee_link_name_
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
std::string base_link_name_
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
constexpr int NUM_RANDOM_TESTS
Number of times to run a test that uses randomly generated input.
TEST_F(PandaConstraintTest, InitPositionConstraint)
int main(int argc, char **argv)
constexpr unsigned int DIFFERENT_LINK_OFFSET
Select a robot link at (num_dofs - different_link_offset) to test another link than the end-effector.
rclcpp::Logger getLogger()
constexpr double JAC_ERROR_TOLERANCE
Allowed error when comparing Jacobian matrix error.
moveit_msgs::msg::PositionConstraint createPositionConstraint(std::string &base_link, std::string &ee_link)
Helper function to create a specific position constraint.