35#include <boost/core/demangle.hpp>
36#include <gtest/gtest.h>
62template <
typename T,
int N>
69template <
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!";
111 cartesian_limits::Params cartesian_limit;
112 cartesian_limit.max_trans_vel = 1.0 * M_PI;
113 cartesian_limit.max_trans_acc = 1.0 * M_PI;
114 cartesian_limit.max_trans_dec = 1.0 * M_PI;
115 cartesian_limit.max_rot_vel = 1.0 * M_PI;
125 auto scene = std::make_shared<planning_scene::PlanningScene>(
robot_model_);
129 scene->setCurrentState(current_state);
146 std::string(context_name).erase(0, std::string(
"pilz_industrial_motion_planner::PlanningContext").length());
148 req.max_velocity_scaling_factor = 0.01;
149 req.max_acceleration_scaling_factor = 0.01;
157 std::vector<double>{ 4.430233957464225e-12, 0.007881892504574495, -1.8157263253868452,
158 1.1801525390026025e-11, 1.8236082178909834,
159 8.591793942969161e-12 });
160 Eigen::Isometry3d start_pose(Eigen::Isometry3d::Identity());
161 start_pose.translation() = Eigen::Vector3d(0.3, 0, 0.65);
166 Eigen::Isometry3d goal_pose(Eigen::Isometry3d::Identity());
167 goal_pose.translation() = Eigen::Vector3d(0, 0.3, 0.65);
168 Eigen::Matrix3d goal_rotation;
169 goal_rotation = Eigen::AngleAxisd(0 * M_PI, Eigen::Vector3d::UnitZ());
170 goal_pose.linear() = goal_rotation;
176 req.path_constraints.name =
"center";
177 moveit_msgs::msg::PositionConstraint center_point;
179 geometry_msgs::msg::Pose center_position;
180 center_position.position.x = 0.0;
181 center_position.position.y = 0.0;
182 center_position.position.z = 0.65;
183 center_point.constraint_region.primitive_poses.push_back(center_position);
184 req.path_constraints.position_constraints.push_back(center_point);
193 std::unique_ptr<robot_model_loader::RobotModelLoader>
rm_loader_;
210 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 this->planning_context_->solve(res);
229 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, res.
error_code.val)
233 this->planning_context_->solve(res_detailed);
235 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, res.
error_code.val)
247 this->planning_context_->setMotionPlanRequest(req);
248 this->planning_context_->solve(res);
250 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, res.
error_code.val)
262 this->planning_context_->setMotionPlanRequest(req);
264 bool result_termination = this->planning_context_->terminate();
267 this->planning_context_->solve(res);
269 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED, res.
error_code.val)
278 EXPECT_NO_THROW(this->planning_context_->clear()) <<
testutils::demangle(
typeid(TypeParam).name());
283 rclcpp::init(argc, argv);
284 testing::InitGoogleTest(&argc, argv);
285 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...
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
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...
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(cartesian_limits::Params &cartesian_limit)
Set cartesian limits.
void setJointLimits(JointLimitsContainer &joint_limits)
Set joint limits.
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
std::string demangle(const char *name)
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.
moveit_msgs::msg::MoveItErrorCodes error_code
Response to a planning query.
moveit::core::MoveItErrorCode error_code
#define TYPED_TEST_SUITE(...)
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")
::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