74 hp_action_client_ = rclcpp_action::create_client<moveit_msgs::action::HybridPlanner>(
node_,
"run_hybrid_planning");
78 "global_trajectory", rclcpp::SystemDefaultsQoS(),
79 [](
const moveit_msgs::msg::MotionPlanResponse::SharedPtr ) {});
81 RCLCPP_INFO(
node_->get_logger(),
"Initialize Planning Scene Monitor");
85 "planning_scene_monitor");
88 RCLCPP_ERROR(
node_->get_logger(),
"The planning scene was not retrieved!");
89 std::exit(EXIT_FAILURE);
102 RCLCPP_ERROR(
node_->get_logger(),
"Timeout when waiting for /joint_states updates. Is the robot running?");
103 std::exit(EXIT_FAILURE);
108 RCLCPP_ERROR(
node_->get_logger(),
"Hybrid planning action server not available after waiting");
109 std::exit(EXIT_FAILURE);
113 const std::string planning_group =
"panda_arm";
118 const auto robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
122 robot_state->setToDefaultValues(joint_model_group,
"ready");
123 robot_state->update();
127 locked_planning_scene->setCurrentState(*robot_state);
132 std::vector<double> joint_values = { 0.0, 0.0, 0.0, 0.0, 0.0, 1.571, 0.785 };
138 const moveit_msgs::msg::MotionPlanRequest goal_motion_request(
139 [robot_state, planning_group, goal_state, joint_model_group]() {
140 moveit_msgs::msg::MotionPlanRequest goal_motion_request;
142 goal_motion_request.group_name = planning_group;
143 goal_motion_request.num_planning_attempts = 10;
144 goal_motion_request.max_velocity_scaling_factor = 0.1;
145 goal_motion_request.max_acceleration_scaling_factor = 0.1;
146 goal_motion_request.allowed_planning_time = 2.0;
147 goal_motion_request.planner_id =
"ompl";
148 goal_motion_request.pipeline_id =
"ompl";
149 goal_motion_request.goal_constraints.resize(1);
150 goal_motion_request.goal_constraints[0] =
152 return goal_motion_request;
156 moveit_msgs::msg::MotionSequenceItem sequence_item;
157 sequence_item.req = goal_motion_request;
158 sequence_item.blend_radius = 0.0;
160 moveit_msgs::msg::MotionSequenceRequest sequence_request;
161 sequence_request.items.push_back(sequence_item);
167 send_goal_options_ = rclcpp_action::Client<moveit_msgs::action::HybridPlanner>::SendGoalOptions();
169 [
this](
const rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanner>::WrappedResult& result) {
172 case rclcpp_action::ResultCode::SUCCEEDED:
174 RCLCPP_INFO(
node_->get_logger(),
"Hybrid planning goal succeeded");
176 case rclcpp_action::ResultCode::ABORTED:
178 RCLCPP_ERROR(
node_->get_logger(),
"Hybrid planning goal was aborted");
180 case rclcpp_action::ResultCode::CANCELED:
181 RCLCPP_ERROR(
node_->get_logger(),
"Hybrid planning goal was canceled");
184 RCLCPP_ERROR(
node_->get_logger(),
"Unknown hybrid planning result code");
191 [
this](rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanner>::SharedPtr ,
192 const std::shared_ptr<const moveit_msgs::action::HybridPlanner::Feedback> feedback) {
193 RCLCPP_INFO(
node_->get_logger(),
"%s", feedback->feedback.c_str());