|
| 1 | +#include "models.h" |
| 2 | + |
| 3 | +#include <moveit/task_constructor/task.h> |
| 4 | +#include <moveit/task_constructor/stages/move_relative.h> |
| 5 | +#include <moveit/task_constructor/stages/fixed_state.h> |
| 6 | +#include <moveit/task_constructor/solvers/cartesian_path.h> |
| 7 | +#include <moveit/task_constructor/moveit_compat.h> |
| 8 | + |
| 9 | +#include <moveit/planning_scene/planning_scene.h> |
| 10 | + |
| 11 | +#include <geometry_msgs/PoseStamped.h> |
| 12 | +#include <geometry_msgs/TwistStamped.h> |
| 13 | + |
| 14 | +#include <gtest/gtest.h> |
| 15 | + |
| 16 | +using namespace moveit::task_constructor; |
| 17 | +using namespace planning_scene; |
| 18 | +using namespace moveit::core; |
| 19 | + |
| 20 | +constexpr double TAU{ 2 * M_PI }; |
| 21 | +constexpr double EPS{ 1e-6 }; |
| 22 | + |
| 23 | +// provide a basic test fixture that prepares a Task |
| 24 | +struct PandaMoveRelative : public testing::Test |
| 25 | +{ |
| 26 | + Task t; |
| 27 | + stages::MoveRelative* move; |
| 28 | + PlanningScenePtr scene; |
| 29 | + |
| 30 | + const JointModelGroup* group; |
| 31 | + |
| 32 | + PandaMoveRelative() { |
| 33 | + t.setRobotModel(loadModel()); |
| 34 | + |
| 35 | + group = t.getRobotModel()->getJointModelGroup("panda_arm"); |
| 36 | + |
| 37 | + scene = std::make_shared<PlanningScene>(t.getRobotModel()); |
| 38 | + scene->getCurrentStateNonConst().setToDefaultValues(); |
| 39 | + scene->getCurrentStateNonConst().setToDefaultValues(t.getRobotModel()->getJointModelGroup("panda_arm"), "ready"); |
| 40 | + t.add(std::make_unique<stages::FixedState>("start", scene)); |
| 41 | + |
| 42 | + auto move_relative = std::make_unique<stages::MoveRelative>("move", std::make_shared<solvers::CartesianPath>()); |
| 43 | + move_relative->setGroup(group->getName()); |
| 44 | + move = move_relative.get(); |
| 45 | + t.add(std::move(move_relative)); |
| 46 | + } |
| 47 | +}; |
| 48 | + |
| 49 | +moveit_msgs::AttachedCollisionObject createAttachedObject(const std::string& id) { |
| 50 | + moveit_msgs::AttachedCollisionObject aco; |
| 51 | + aco.link_name = "panda_hand"; |
| 52 | + aco.object.header.frame_id = aco.link_name; |
| 53 | + aco.object.operation = aco.object.ADD; |
| 54 | + aco.object.id = id; |
| 55 | + aco.object.primitives.resize(1, [] { |
| 56 | + shape_msgs::SolidPrimitive p; |
| 57 | + p.type = p.SPHERE; |
| 58 | + p.dimensions.resize(1); |
| 59 | + p.dimensions[p.SPHERE_RADIUS] = 0.01; |
| 60 | + return p; |
| 61 | + }()); |
| 62 | + |
| 63 | + geometry_msgs::Pose p; |
| 64 | + p.position.x = 0.1; |
| 65 | + p.orientation.w = 1.0; |
| 66 | +#if MOVEIT_HAS_OBJECT_POSE |
| 67 | + aco.object.pose = p; |
| 68 | +#else |
| 69 | + aco.object.primitive_poses.resize(1, p); |
| 70 | + aco.object.primitive_poses[0] = p; |
| 71 | +#endif |
| 72 | + return aco; |
| 73 | +} |
| 74 | + |
| 75 | +inline auto position(const PlanningSceneConstPtr& scene, const std::string& frame) { |
| 76 | + return scene->getFrameTransform(frame).translation(); |
| 77 | +} |
| 78 | + |
| 79 | +TEST_F(PandaMoveRelative, cartesianRotateEEF) { |
| 80 | + move->setDirection([] { |
| 81 | + geometry_msgs::TwistStamped twist; |
| 82 | + twist.header.frame_id = "world"; |
| 83 | + twist.twist.angular.z = TAU / 8.0; |
| 84 | + return twist; |
| 85 | + }()); |
| 86 | + |
| 87 | + ASSERT_TRUE(t.plan()) << "Failed to plan"; |
| 88 | + |
| 89 | + const auto& tip_name{ group->getOnlyOneEndEffectorTip()->getName() }; |
| 90 | + const auto start_eef_position{ position(scene, tip_name) }; |
| 91 | + const auto end_eef_position{ position(move->solutions().front()->end()->scene(), tip_name) }; |
| 92 | + |
| 93 | + EXPECT_TRUE(start_eef_position.isApprox(end_eef_position, EPS)) |
| 94 | + << "Cartesian rotation unexpectedly changed position of '" << tip_name << "' (must only change orientation)\n" |
| 95 | + << start_eef_position << "\nvs\n" |
| 96 | + << end_eef_position; |
| 97 | +} |
| 98 | + |
| 99 | +TEST_F(PandaMoveRelative, cartesianRotateAttachedIKFrame) { |
| 100 | + const std::string ATTACHED_OBJECT{ "attached_object" }; |
| 101 | + scene->processAttachedCollisionObjectMsg(createAttachedObject(ATTACHED_OBJECT)); |
| 102 | + move->setIKFrame(ATTACHED_OBJECT); |
| 103 | + |
| 104 | + move->setDirection([] { |
| 105 | + geometry_msgs::TwistStamped twist; |
| 106 | + twist.header.frame_id = "world"; |
| 107 | + twist.twist.angular.z = TAU / 8.0; |
| 108 | + return twist; |
| 109 | + }()); |
| 110 | + |
| 111 | + ASSERT_TRUE(t.plan()); |
| 112 | + |
| 113 | + const auto start_eef_position{ position(scene, ATTACHED_OBJECT) }; |
| 114 | + const auto end_eef_position{ position(move->solutions().front()->end()->scene(), ATTACHED_OBJECT) }; |
| 115 | + |
| 116 | + EXPECT_TRUE(start_eef_position.isApprox(end_eef_position, EPS)) |
| 117 | + << "Cartesian rotation unexpectedly changed position of ik frame (must only change orientation)\n" |
| 118 | + << start_eef_position << "\nvs\n" |
| 119 | + << end_eef_position; |
| 120 | +} |
| 121 | + |
| 122 | +int main(int argc, char** argv) { |
| 123 | + testing::InitGoogleTest(&argc, argv); |
| 124 | + ros::init(argc, argv, "move_relative_test"); |
| 125 | + ros::AsyncSpinner spinner(1); |
| 126 | + spinner.start(); |
| 127 | + |
| 128 | + return RUN_ALL_TESTS(); |
| 129 | +} |
0 commit comments