66 hp_action_client_ = rclcpp_action::create_client<moveit_msgs::action::HybridPlanner>(
node_,
"run_hybrid_planning");
70 "global_trajectory", rclcpp::SystemDefaultsQoS(),
71 [](
const moveit_msgs::msg::MotionPlanResponse::SharedPtr ) {});
73 RCLCPP_INFO(
node_->get_logger(),
"Initialize Planning Scene Monitor");
77 "planning_scene_monitor");
80 RCLCPP_ERROR(
node_->get_logger(),
"The planning scene was not retrieved!");
81 std::exit(EXIT_FAILURE);
94 RCLCPP_ERROR(
node_->get_logger(),
"Timeout when waiting for /joint_states updates. Is the robot running?");
95 std::exit(EXIT_FAILURE);
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 };
130 const moveit_msgs::msg::MotionPlanRequest goal_motion_request(
131 [robot_state, planning_group, goal_state, joint_model_group]() {
132 moveit_msgs::msg::MotionPlanRequest goal_motion_request;
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);
159 send_goal_options_ = rclcpp_action::Client<moveit_msgs::action::HybridPlanner>::SendGoalOptions();
161 [
this](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanner>::WrappedResult& result) {
164 case rclcpp_action::ResultCode::SUCCEEDED:
166 RCLCPP_INFO(
node_->get_logger(),
"Hybrid planning goal succeeded");
168 case rclcpp_action::ResultCode::ABORTED:
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");
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());