103 if (long_callback_thread_.joinable())
105 long_callback_thread_.join();
126 return node_->get_node_base_interface();
133 std::shared_ptr<rclcpp::Node> node_;
136 std::shared_ptr<local_planner_parameters::Params> config_;
139 std::atomic<LocalPlannerState> state_;
142 rclcpp::TimerBase::SharedPtr timer_;
145 std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::LocalPlanner>> local_planning_goal_handle_;
148 std::shared_ptr<moveit_msgs::action::LocalPlanner::Feedback> local_planner_feedback_;
151 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
154 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
155 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
158 rclcpp::Subscription<moveit_msgs::msg::MotionPlanResponse>::SharedPtr global_solution_subscriber_;
161 rclcpp_action::Server<moveit_msgs::action::LocalPlanner>::SharedPtr local_planning_request_server_;
164 rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr local_trajectory_publisher_;
165 rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr local_solution_publisher_;
168 std::unique_ptr<pluginlib::ClassLoader<LocalConstraintSolverInterface>> local_constraint_solver_plugin_loader_;
171 std::shared_ptr<LocalConstraintSolverInterface> local_constraint_solver_instance_;
174 std::unique_ptr<pluginlib::ClassLoader<TrajectoryOperatorInterface>> trajectory_operator_loader_;
177 std::shared_ptr<TrajectoryOperatorInterface> trajectory_operator_instance_;
180 std::thread long_callback_thread_;
183 rclcpp::CallbackGroup::SharedPtr cb_group_;