39 #include <gtest/gtest.h>
43 #include <rclcpp/rclcpp.hpp>
44 #include <rclcpp_action/rclcpp_action.hpp>
45 #include <tf2_ros/buffer.hpp>
47 #include <moveit_msgs/action/hybrid_planner.hpp>
48 #include <moveit_msgs/msg/display_robot_state.hpp>
49 #include <moveit_msgs/msg/motion_plan_response.hpp>
53 using namespace std::chrono_literals;
60 action_successful_ =
false;
61 action_aborted_ =
false;
62 action_complete_ =
false;
64 executor_.add_node(node_);
66 hp_action_client_ = rclcpp_action::create_client<moveit_msgs::action::HybridPlanner>(node_,
"run_hybrid_planning");
69 global_solution_subscriber_ = node_->create_subscription<moveit_msgs::msg::MotionPlanResponse>(
70 "global_trajectory", rclcpp::SystemDefaultsQoS(),
71 [](
const moveit_msgs::msg::MotionPlanResponse::SharedPtr ) {});
73 RCLCPP_INFO(node_->get_logger(),
"Initialize Planning Scene Monitor");
74 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
76 planning_scene_monitor_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node_,
"robot_description",
77 "planning_scene_monitor");
78 if (!planning_scene_monitor_->getPlanningScene())
80 RCLCPP_ERROR(node_->get_logger(),
"The planning scene was not retrieved!");
81 std::exit(EXIT_FAILURE);
85 planning_scene_monitor_->startStateMonitor();
86 planning_scene_monitor_->setPlanningScenePublishingFrequency(100);
89 planning_scene_monitor_->startSceneMonitor();
92 if (!planning_scene_monitor_->waitForCurrentRobotState(node_->now(), 5))
94 RCLCPP_ERROR(node_->get_logger(),
"Timeout when waiting for /joint_states updates. Is the robot running?");
95 std::exit(EXIT_FAILURE);
98 if (!hp_action_client_->wait_for_action_server(20s))
100 RCLCPP_ERROR(node_->get_logger(),
"Hybrid planning action server not available after waiting");
101 std::exit(EXIT_FAILURE);
105 const std::string planning_group =
"panda_arm";
110 const auto robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
114 robot_state->setToDefaultValues(joint_model_group,
"ready");
115 robot_state->update();
119 locked_planning_scene->setCurrentState(*robot_state);
124 std::vector<double> joint_values = { 0.0, 0.0, 0.0, 0.0, 0.0, 1.571, 0.785 };
131 [robot_state, planning_group, goal_state, joint_model_group]() {
134 goal_motion_request.group_name = planning_group;
135 goal_motion_request.num_planning_attempts = 10;
136 goal_motion_request.max_velocity_scaling_factor = 0.1;
137 goal_motion_request.max_acceleration_scaling_factor = 0.1;
138 goal_motion_request.allowed_planning_time = 2.0;
139 goal_motion_request.planner_id =
"ompl";
140 goal_motion_request.pipeline_id =
"ompl";
141 goal_motion_request.goal_constraints.resize(1);
142 goal_motion_request.goal_constraints[0] =
144 return goal_motion_request;
148 moveit_msgs::msg::MotionSequenceItem sequence_item;
149 sequence_item.req = goal_motion_request;
150 sequence_item.blend_radius = 0.0;
152 moveit_msgs::msg::MotionSequenceRequest sequence_request;
153 sequence_request.items.push_back(sequence_item);
155 goal_action_request_ = moveit_msgs::action::HybridPlanner::Goal();
156 goal_action_request_.planning_group = planning_group;
157 goal_action_request_.motion_sequence = sequence_request;
159 send_goal_options_ = rclcpp_action::Client<moveit_msgs::action::HybridPlanner>::SendGoalOptions();
160 send_goal_options_.result_callback =
161 [
this](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanner>::WrappedResult& result) {
164 case rclcpp_action::ResultCode::SUCCEEDED:
165 action_successful_ =
true;
166 RCLCPP_INFO(node_->get_logger(),
"Hybrid planning goal succeeded");
168 case rclcpp_action::ResultCode::ABORTED:
169 action_aborted_ =
true;
170 RCLCPP_ERROR(node_->get_logger(),
"Hybrid planning goal was aborted");
172 case rclcpp_action::ResultCode::CANCELED:
173 RCLCPP_ERROR(node_->get_logger(),
"Hybrid planning goal was canceled");
176 RCLCPP_ERROR(node_->get_logger(),
"Unknown hybrid planning result code");
179 action_complete_ =
true;
182 send_goal_options_.feedback_callback =
183 [
this](rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanner>::SharedPtr ,
184 const std::shared_ptr<const moveit_msgs::action::HybridPlanner::Feedback> feedback) {
185 RCLCPP_INFO(node_->get_logger(),
"%s", feedback->feedback.c_str());
209 std::thread run_thread([
this]() {
211 auto goal_handle_future = hp_action_client_->async_send_goal(goal_action_request_, send_goal_options_);
214 rclcpp::Rate rate(10);
215 while (!action_complete_)
217 executor_.spin_once();
221 ASSERT_TRUE(action_successful_);
248 int main(
int argc,
char** argv)
250 rclcpp::init(argc, argv);
251 ::testing::InitGoogleTest(&argc, argv);
253 int ret = RUN_ALL_TESTS();
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...
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
rclcpp_action::Client< moveit_msgs::action::HybridPlanner >::SendGoalOptions send_goal_options_
std::atomic_bool action_aborted_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
rclcpp::Subscription< moveit_msgs::msg::MotionPlanResponse >::SharedPtr global_solution_subscriber_
rclcpp::executors::MultiThreadedExecutor executor_
moveit_msgs::action::HybridPlanner::Goal goal_action_request_
std::atomic_bool action_complete_
rclcpp_action::Client< moveit_msgs::action::HybridPlanner >::SharedPtr hp_action_client_
rclcpp::Node::SharedPtr node_
std::atomic_bool action_successful_
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
@ UPDATE_SCENE
The entire scene was updated.
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.
TEST_F(HybridPlanningFixture, ActionCompletion)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
int main(int argc, char **argv)