95 if (long_callback_thread_.joinable())
97 long_callback_thread_.join();
118 return node_->get_node_base_interface();
125 std::shared_ptr<rclcpp::Node> node_;
128 std::shared_ptr<local_planner_parameters::Params> config_;
131 std::atomic<LocalPlannerState> state_;
134 rclcpp::TimerBase::SharedPtr timer_;
137 std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::LocalPlanner>> local_planning_goal_handle_;
140 std::shared_ptr<moveit_msgs::action::LocalPlanner::Feedback> local_planner_feedback_;
143 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
146 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
147 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
150 rclcpp::Subscription<moveit_msgs::msg::MotionPlanResponse>::SharedPtr global_solution_subscriber_;
153 rclcpp_action::Server<moveit_msgs::action::LocalPlanner>::SharedPtr local_planning_request_server_;
156 rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr local_trajectory_publisher_;
157 rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr local_solution_publisher_;
160 std::unique_ptr<pluginlib::ClassLoader<LocalConstraintSolverInterface>> local_constraint_solver_plugin_loader_;
163 std::shared_ptr<LocalConstraintSolverInterface> local_constraint_solver_instance_;
166 std::unique_ptr<pluginlib::ClassLoader<TrajectoryOperatorInterface>> trajectory_operator_loader_;
169 std::shared_ptr<TrajectoryOperatorInterface> trajectory_operator_instance_;
172 std::thread long_callback_thread_;
175 rclcpp::CallbackGroup::SharedPtr cb_group_;