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> 58 #define OMPL_ROS_LOG(ros_log_level) \ 60 ROSCONSOLE_DEFINE_LOCATION(true, ros_log_level, ROSCONSOLE_NAME_PREFIX ".ompl"); \ 61 if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \ 62 ::ros::console::print(0, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, \ 63 filename, line, __ROSCONSOLE_FUNCTION__, "%s", text.c_str()); \ 71 class OutputHandler :
public ompl::msg::OutputHandler
74 void log(
const std::string& text, ompl::msg::LogLevel level,
const char*
filename,
int line)
override 78 case ompl::msg::LOG_DEV2:
79 case ompl::msg::LOG_DEV1:
80 case ompl::msg::LOG_DEBUG:
83 case ompl::msg::LOG_INFO:
86 case ompl::msg::LOG_WARN:
89 case ompl::msg::LOG_ERROR:
92 case ompl::msg::LOG_NONE:
100 output_handler_.reset(
new OutputHandler());
101 ompl::msg::useOutputHandler(output_handler_.get());
104 virtual bool initialize(
const robot_model::RobotModelConstPtr& model,
const std::string& ns)
109 std::string ompl_ns = ns.empty() ?
"ompl" : ns +
"/ompl";
110 dynamic_reconfigure_server_.reset(
111 new dynamic_reconfigure::Server<OMPLDynamicReconfigureConfig>(
ros::NodeHandle(nh_, ompl_ns)));
112 dynamic_reconfigure_server_->setCallback(
114 config_settings_ = ompl_interface_->getPlannerConfigurations();
120 return req.trajectory_constraints.constraints.empty();
132 algs.reserve(pconfig.size());
133 for (planning_interface::PlannerConfigurationMap::const_iterator it = pconfig.begin(); it != pconfig.end(); ++it)
134 algs.push_back(it->first);
140 ompl_interface_->setPlannerConfigurations(pconfig);
142 PlannerManager::setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
145 virtual planning_interface::PlanningContextPtr
149 return ompl_interface_->getPlanningContext(planning_scene, req, error_code);
263 if (config.link_for_exploration_tree.empty() && !planner_data_link_name_.empty())
265 pub_markers_.shutdown();
266 planner_data_link_name_.clear();
267 ROS_INFO(
"Not displaying OMPL exploration data structures.");
269 else if (!config.link_for_exploration_tree.empty() && planner_data_link_name_.empty())
271 pub_markers_ = nh_.advertise<visualization_msgs::MarkerArray>(
"ompl_planner_data_marker_array", 5);
272 planner_data_link_name_ = config.link_for_exploration_tree;
273 ROS_INFO(
"Displaying OMPL exploration data structures for %s", planner_data_link_name_.c_str());
276 ompl_interface_->simplifySolutions(config.simplify_solutions);
277 ompl_interface_->getPlanningContextManager().setMaximumSolutionSegmentLength(config.maximum_waypoint_distance);
278 ompl_interface_->getPlanningContextManager().setMinimumWaypointCount(config.minimum_waypoint_count);
279 if (display_random_valid_states_ && !config.display_random_valid_states)
281 display_random_valid_states_ =
false;
282 if (pub_valid_states_thread_)
284 pub_valid_states_thread_->join();
285 pub_valid_states_thread_.reset();
287 pub_valid_states_.shutdown();
288 pub_valid_traj_.shutdown();
290 else if (!display_random_valid_states_ && config.display_random_valid_states)
292 pub_valid_states_ = nh_.advertise<moveit_msgs::DisplayRobotState>(
"ompl_planner_valid_states", 5);
293 pub_valid_traj_ = nh_.advertise<moveit_msgs::DisplayTrajectory>(
"ompl_planner_valid_trajectories", 5);
294 display_random_valid_states_ =
true;
std::unique_ptr< boost::thread > pub_valid_states_thread_
ros::Publisher pub_valid_states_
bool display_random_valid_states_
INLINE Rall1d< T, V, S > log(const Rall1d< T, V, S > &arg)
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
#define OMPL_ROS_LOG(ros_log_level)
The MoveIt! interface to OMPL.
virtual void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
std::unique_ptr< OMPLInterface > ompl_interface_
virtual std::string getDescription() const
std::string planner_data_link_name_
virtual bool initialize(const robot_model::RobotModelConstPtr &model, const std::string &ns)
ros::Publisher pub_markers_
std::shared_ptr< ompl::msg::OutputHandler > output_handler_
moveit_msgs::MotionPlanRequest MotionPlanRequest
ros::Publisher pub_valid_traj_
virtual planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const
void dynamicReconfigureCallback(OMPLDynamicReconfigureConfig &config, uint32_t level)
virtual bool canServiceRequest(const moveit_msgs::MotionPlanRequest &req) const
virtual void getPlanningAlgorithms(std::vector< std::string > &algs) const
std::unique_ptr< dynamic_reconfigure::Server< OMPLDynamicReconfigureConfig > > dynamic_reconfigure_server_
CLASS_LOADER_REGISTER_CLASS(ompl_interface::OMPLPlannerManager, planning_interface::PlannerManager)