40 #include <gmock/gmock.h>
41 #include <gtest/gtest.h>
42 #include <rclcpp/rclcpp.hpp>
53 rclcpp::init(0,
nullptr);
54 node_ = std::make_shared<rclcpp::Node>(
"test_check_start_state_bounds_adapter",
"");
58 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
59 planning_scene_ = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
62 plugin_loader_ = std::make_unique<pluginlib::ClassLoader<planning_interface::PlanningRequestAdapter>>(
63 "moveit_core",
"planning_interface::PlanningRequestAdapter");
64 adapter_ =
plugin_loader_->createUniqueInstance(
"default_planning_request_adapters/CheckStartStateBounds");
73 std::shared_ptr<rclcpp::Node>
node_;
75 std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlanningRequestAdapter>>
plugin_loader_;
76 pluginlib::UniquePtr<planning_interface::PlanningRequestAdapter>
adapter_;
82 request.group_name =
"right_arm";
83 request.start_state.joint_state.name = {
84 "r_shoulder_pan_joint",
"r_shoulder_lift_joint",
"r_upper_arm_roll_joint",
"r_forearm_roll_joint",
85 "r_elbow_flex_joint",
"r_wrist_flex_joint",
"r_wrist_roll_joint",
87 request.start_state.joint_state.position = {
88 0.0, 0.0, 0.0, 0.0, -0.5, -0.5, 0.0,
91 const auto result = adapter_->adapt(planning_scene_, request);
92 EXPECT_EQ(result.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
93 EXPECT_EQ(result.message,
"");
99 request.group_name =
"right_arm";
100 request.start_state.joint_state.name = {
101 "r_shoulder_pan_joint",
"r_shoulder_lift_joint",
"r_upper_arm_roll_joint",
"r_forearm_roll_joint",
102 "r_elbow_flex_joint",
"r_wrist_flex_joint",
"r_wrist_roll_joint",
104 request.start_state.joint_state.position = {
106 0.0, 0.0, 0.0, -0.5, -0.5, 0.0,
109 const auto result = adapter_->adapt(planning_scene_, request);
110 EXPECT_EQ(result.val, moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID);
111 EXPECT_EQ(result.message,
"Start state out of bounds.");
117 request.group_name =
"right_arm";
118 request.start_state.joint_state.name = {
119 "r_shoulder_pan_joint",
"r_shoulder_lift_joint",
"r_upper_arm_roll_joint",
"r_forearm_roll_joint",
120 "r_elbow_flex_joint",
"r_wrist_flex_joint",
"r_wrist_roll_joint",
122 request.start_state.joint_state.position = {
123 0.0, 0.0, 0.0, 100.0,
127 const auto result = adapter_->adapt(planning_scene_, request);
128 EXPECT_EQ(result.val, moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID);
129 EXPECT_EQ(result.message,
"Start state out of bounds.");
135 request.group_name =
"right_arm";
136 request.start_state.joint_state.name = {
137 "r_shoulder_pan_joint",
"r_shoulder_lift_joint",
"r_upper_arm_roll_joint",
"r_forearm_roll_joint",
138 "r_elbow_flex_joint",
"r_wrist_flex_joint",
"r_wrist_roll_joint",
140 request.start_state.joint_state.position = {
141 0.0, 0.0, 0.0, 100.0,
146 node_->set_parameter(rclcpp::Parameter(
"fix_start_state",
true));
148 const auto result = adapter_->adapt(planning_scene_, request);
149 EXPECT_EQ(result.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
150 EXPECT_EQ(result.message,
"Normalized start state.");
153 const auto& joint_names = request.start_state.joint_state.name;
154 const size_t joint_idx =
155 std::find(joint_names.begin(), joint_names.end(),
"r_forearm_roll_joint") - joint_names.begin();
156 EXPECT_NEAR(request.start_state.joint_state.position[joint_idx], -0.530965, 1.0e-4);
159 int main(
int argc,
char** argv)
161 ::testing::InitGoogleTest(&argc, argv);
162 return RUN_ALL_TESTS();
std::unique_ptr< pluginlib::ClassLoader< planning_interface::PlanningRequestAdapter > > plugin_loader_
std::shared_ptr< rclcpp::Node > node_
pluginlib::UniquePtr< planning_interface::PlanningRequestAdapter > adapter_
std::shared_ptr< planning_scene::PlanningScene > planning_scene_
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
int main(int argc, char **argv)
TEST_F(TestCheckStartStateBounds, TestWithinBounds)