35 #include <boost/core/demangle.hpp>
36 #include <gtest/gtest.h>
62 template <
typename T,
int N>
69 template <
typename T,
int N>
92 rclcpp::NodeOptions node_options;
93 node_options.automatically_declare_parameters_from_overrides(
true);
94 node_ = rclcpp::Node::make_shared(
"unittest_planning_context", node_options);
97 rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(
node_);
99 ASSERT_FALSE(
robot_model_ ==
nullptr) <<
"There is no robot model!";
128 scene->setCurrentState(current_state);
145 std::string(context_name).erase(0, std::string(
"pilz_industrial_motion_planner::PlanningContext").length());
147 req.max_velocity_scaling_factor = 0.01;
148 req.max_acceleration_scaling_factor = 0.01;
156 std::vector<double>{ 4.430233957464225e-12, 0.007881892504574495, -1.8157263253868452,
157 1.1801525390026025e-11, 1.8236082178909834,
158 8.591793942969161e-12 });
159 Eigen::Isometry3d start_pose(Eigen::Isometry3d::Identity());
165 Eigen::Isometry3d goal_pose(Eigen::Isometry3d::Identity());
167 Eigen::Matrix3d goal_rotation;
168 goal_rotation = Eigen::AngleAxisd(0 * M_PI, Eigen::Vector3d::UnitZ());
169 goal_pose.linear() = goal_rotation;
172 rstate, this->
robot_model_->getJointModelGroup(this->planning_group_)));
175 req.path_constraints.name =
"center";
176 moveit_msgs::msg::PositionConstraint center_point;
178 geometry_msgs::msg::Pose center_position;
179 center_position.position.x = 0.0;
180 center_position.position.y = 0.0;
181 center_position.position.z = 0.65;
182 center_point.constraint_region.primitive_poses.push_back(center_position);
183 req.path_constraints.position_constraints.push_back(center_point);
192 std::unique_ptr<robot_model_loader::RobotModelLoader>
rm_loader_;
209 bool result = this->planning_context_->solve(res);
212 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN, res.
error_code_.val)
224 this->planning_context_->setMotionPlanRequest(req);
227 bool result = this->planning_context_->solve(res);
230 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, res.
error_code_.val)
234 bool result_detailed = this->planning_context_->solve(res_detailed);
237 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, res.
error_code_.val)
249 this->planning_context_->setMotionPlanRequest(req);
250 bool result = this->planning_context_->solve(res);
253 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, res.
error_code_.val)
265 this->planning_context_->setMotionPlanRequest(req);
267 bool result_termination = this->planning_context_->terminate();
270 bool result = this->planning_context_->solve(res);
273 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED, res.
error_code_.val)
285 int main(
int argc,
char** argv)
287 rclcpp::init(argc, argv);
288 testing::InitGoogleTest(&argc, argv);
289 return RUN_ALL_TESTS();
planning_interface::MotionPlanRequest getValidRequest(const std::string &context_name) const
Generate a valid fully defined request.
moveit::core::RobotModelConstPtr robot_model_
std::string planning_group_
std::unique_ptr< planning_interface::PlanningContext > planning_context_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
rclcpp::Node::SharedPtr node_
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
void setMaxRotationalVelocity(double max_rot_vel)
Set the maximum rotational velocity.
void setMaxTranslationalVelocity(double max_trans_vel)
Set the maximal translational velocity.
void setMaxTranslationalAcceleration(double max_trans_acc)
Set the maximum translational acceleration.
void setMaxTranslationalDeceleration(double max_trans_dec)
Set the maximum translational deceleration.
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
This class combines CartesianLimit and JointLimits into on single class.
void setCartesianLimits(CartesianLimit &cartesian_limit)
Set cartesian limits.
void setJointLimits(JointLimitsContainer &joint_limits)
Set joint limits.
Vec3fX< details::Vec3Data< double > > Vector3d
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
pilz_industrial_motion_planner::JointLimitsContainer createFakeLimits(const std::vector< std::string > &joint_names)
Create limits for tests to avoid the need to get the limits from the node parameter.
std::string demangle(char const *name)
moveit_msgs::msg::MoveItErrorCodes error_code_
moveit_msgs::msg::MoveItErrorCodes error_code_
const std::string PARAM_PLANNING_GROUP_NAME("planning_group")
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextCIRC, 0 > CIRC_NO_GRIPPER
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextPTP, 1 > PTP_WITH_GRIPPER
int main(int argc, char **argv)
TYPED_TEST(PlanningContextTest, NoRequest)
No request is set. Check the output of solve. Using robot model without gripper.
const std::string PARAM_TARGET_LINK_NAME("target_link")
TYPED_TEST_SUITE(PlanningContextTest, PlanningContextTestTypes,)
::testing::Types< PTP_NO_GRIPPER, PTP_WITH_GRIPPER, LIN_NO_GRIPPER, LIN_WITH_GRIPPER, CIRC_NO_GRIPPER, CIRC_WITH_GRIPPER > PlanningContextTestTypes
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextLIN, 0 > LIN_NO_GRIPPER
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextPTP, 0 > PTP_NO_GRIPPER
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextCIRC, 1 > CIRC_WITH_GRIPPER
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextLIN, 1 > LIN_WITH_GRIPPER