44 #include <dynamic_reconfigure/server.h>
45 #include "moveit_planners_ompl/OMPLDynamicReconfigureConfig.h"
47 #include <moveit_msgs/DisplayRobotState.h>
48 #include <moveit_msgs/DisplayTrajectory.h>
50 #include <ompl/util/Console.h>
57 using namespace moveit_planners_ompl;
59 constexpr
char LOGNAME[] =
"ompl_planner_manager";
61 #define OMPL_ROS_LOG(ros_log_level) \
63 ROSCONSOLE_DEFINE_LOCATION(true, ros_log_level, ROSCONSOLE_NAME_PREFIX ".ompl"); \
64 if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
65 ::ros::console::print(0, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, \
66 filename, line, __ROSCONSOLE_FUNCTION__, "%s", text.c_str()); \
74 class OutputHandler :
public ompl::msg::OutputHandler
77 void log(
const std::string& text, ompl::msg::LogLevel level,
const char* filename,
int line)
override
81 case ompl::msg::LOG_DEV2:
82 case ompl::msg::LOG_DEV1:
83 case ompl::msg::LOG_DEBUG:
86 case ompl::msg::LOG_INFO:
89 case ompl::msg::LOG_WARN:
92 case ompl::msg::LOG_ERROR:
95 case ompl::msg::LOG_NONE:
103 output_handler_ = std::make_shared<OutputHandler>();
104 ompl::msg::useOutputHandler(output_handler_.get());
107 bool initialize(
const moveit::core::RobotModelConstPtr& model,
const std::string& ns)
override
111 ompl_interface_ = std::make_unique<OMPLInterface>(model, nh_);
112 std::string ompl_ns = ns.empty() ?
"ompl" : ns +
"/ompl";
113 dynamic_reconfigure_server_ =
114 std::make_unique<dynamic_reconfigure::Server<OMPLDynamicReconfigureConfig>>(
ros::NodeHandle(nh_, ompl_ns));
115 dynamic_reconfigure_server_->setCallback(
116 [
this](
auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
117 config_settings_ = ompl_interface_->getPlannerConfigurations();
121 bool canServiceRequest(
const moveit_msgs::MotionPlanRequest& req)
const override
123 return req.trajectory_constraints.constraints.empty();
126 std::string getDescription()
const override
131 void getPlanningAlgorithms(std::vector<std::string>& algs)
const override
135 algs.reserve(pconfig.size());
136 for (
const std::pair<const std::string, planning_interface::PlannerConfigurationSettings>& config : pconfig)
137 algs.push_back(config.first);
143 ompl_interface_->setPlannerConfigurations(pconfig);
145 PlannerManager::setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
148 planning_interface::PlanningContextPtr getPlanningContext(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
150 moveit_msgs::MoveItErrorCodes& error_code)
const override
152 return ompl_interface_->getPlanningContext(
planning_scene, req, error_code);
264 void dynamicReconfigureCallback(OMPLDynamicReconfigureConfig& config, uint32_t )
266 if (config.link_for_exploration_tree.empty() && !planner_data_link_name_.empty())
268 pub_markers_.shutdown();
269 planner_data_link_name_.clear();
272 else if (!config.link_for_exploration_tree.empty() && planner_data_link_name_.empty())
274 pub_markers_ = nh_.advertise<visualization_msgs::MarkerArray>(
"ompl_planner_data_marker_array", 5);
275 planner_data_link_name_ = config.link_for_exploration_tree;
276 ROS_INFO_NAMED(
LOGNAME,
"Displaying OMPL exploration data structures for %s", planner_data_link_name_.c_str());
279 ompl_interface_->simplifySolutions(config.simplify_solutions);
280 ompl_interface_->getPlanningContextManager().setMaximumSolutionSegmentLength(config.maximum_waypoint_distance);
281 ompl_interface_->getPlanningContextManager().setMinimumWaypointCount(config.minimum_waypoint_count);
282 if (display_random_valid_states_ && !config.display_random_valid_states)
284 display_random_valid_states_ =
false;
285 if (pub_valid_states_thread_)
287 pub_valid_states_thread_->join();
288 pub_valid_states_thread_.reset();
290 pub_valid_states_.shutdown();
291 pub_valid_traj_.shutdown();
293 else if (!display_random_valid_states_ && config.display_random_valid_states)
295 pub_valid_states_ = nh_.advertise<moveit_msgs::DisplayRobotState>(
"ompl_planner_valid_states", 5);
296 pub_valid_traj_ = nh_.advertise<moveit_msgs::DisplayTrajectory>(
"ompl_planner_valid_trajectories", 5);
297 display_random_valid_states_ =
true;
303 std::unique_ptr<dynamic_reconfigure::Server<OMPLDynamicReconfigureConfig>> dynamic_reconfigure_server_;
304 std::unique_ptr<OMPLInterface> ompl_interface_;
305 std::unique_ptr<std::thread> pub_valid_states_thread_;
306 bool display_random_valid_states_{
false };
310 std::string planner_data_link_name_;
311 std::shared_ptr<ompl::msg::OutputHandler> output_handler_;