ompl_planner_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Dave Coleman */
36 
43 
44 #include <dynamic_reconfigure/server.h>
45 #include "moveit_planners_ompl/OMPLDynamicReconfigureConfig.h"
46 
47 #include <moveit_msgs/DisplayRobotState.h>
48 #include <moveit_msgs/DisplayTrajectory.h>
49 
50 #include <ompl/util/Console.h>
51 
52 #include <thread>
53 #include <memory>
54 
55 namespace ompl_interface
56 {
57 using namespace moveit_planners_ompl;
58 
59 constexpr char LOGNAME[] = "ompl_planner_manager";
60 
61 #define OMPL_ROS_LOG(ros_log_level) \
62  { \
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()); \
67  }
68 
69 class OMPLPlannerManager : public planning_interface::PlannerManager
70 {
71 public:
72  OMPLPlannerManager() : planning_interface::PlannerManager(), nh_("~")
73  {
74  class OutputHandler : public ompl::msg::OutputHandler
75  {
76  public:
77  void log(const std::string& text, ompl::msg::LogLevel level, const char* filename, int line) override
78  {
79  switch (level)
80  {
81  case ompl::msg::LOG_DEV2:
82  case ompl::msg::LOG_DEV1:
83  case ompl::msg::LOG_DEBUG:
85  break;
86  case ompl::msg::LOG_INFO:
88  break;
89  case ompl::msg::LOG_WARN:
91  break;
92  case ompl::msg::LOG_ERROR:
94  break;
95  case ompl::msg::LOG_NONE:
96  default:
97  /* ignore */
98  break;
99  }
100  }
101  };
102 
103  output_handler_ = std::make_shared<OutputHandler>();
104  ompl::msg::useOutputHandler(output_handler_.get());
105  }
106 
107  bool initialize(const moveit::core::RobotModelConstPtr& model, const std::string& ns) override
108  {
109  if (!ns.empty())
110  nh_ = ros::NodeHandle(ns);
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();
118  return true;
119  }
120 
121  bool canServiceRequest(const moveit_msgs::MotionPlanRequest& req) const override
122  {
123  return req.trajectory_constraints.constraints.empty();
124  }
125 
126  std::string getDescription() const override
127  {
128  return "OMPL";
129  }
130 
131  void getPlanningAlgorithms(std::vector<std::string>& algs) const override
132  {
133  const planning_interface::PlannerConfigurationMap& pconfig = ompl_interface_->getPlannerConfigurations();
134  algs.clear();
135  algs.reserve(pconfig.size());
136  for (const std::pair<const std::string, planning_interface::PlannerConfigurationSettings>& config : pconfig)
137  algs.push_back(config.first);
138  }
139 
140  void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap& pconfig) override
141  {
142  // this call can add a few more configs than we pass in (adds defaults)
143  ompl_interface_->setPlannerConfigurations(pconfig);
144  // so we read the configs instead of just setting pconfig
145  PlannerManager::setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
146  }
147 
148  planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
150  moveit_msgs::MoveItErrorCodes& error_code) const override
151  {
152  return ompl_interface_->getPlanningContext(planning_scene, req, error_code);
153  }
154 
155 private:
156  /*
157  bool r = ompl_interface_->solve(planning_scene, req, res);
158  if (!planner_data_link_name_.empty())
159  displayPlannerData(planning_scene, planner_data_link_name_);
160  return r;
161  */
162 
163  /*
164  bool r = ompl_interface_->solve(planning_scene, req, res);
165  if (!planner_data_link_name_.empty())
166  displayPlannerData(planning_scene, planner_data_link_name_);
167  return r;
168  */
169 
170  /*
171  void displayRandomValidStates()
172  {
173  ompl_interface::ModelBasedPlanningContextPtr pc = ompl_interface_->getLastPlanningContext();
174  if (!pc || !pc->getPlanningScene())
175  {
176  ROS_ERROR("No planning context to sample states for");
177  return;
178  }
179  ROS_INFO_STREAM("Displaying states for context " << pc->getName());
180  const og::SimpleSetup &ss = pc->getOMPLSimpleSetup();
181  ob::ValidStateSamplerPtr vss = ss.getSpaceInformation()->allocValidStateSampler();
182  moveit::core::RobotState robot_state = pc->getPlanningScene()->getCurrentState();
183  ob::ScopedState<> rstate1(ss.getStateSpace());
184  ob::ScopedState<> rstate2(ss.getStateSpace());
185  ros::WallDuration wait(2);
186  unsigned int n = 0;
187  std::vector<ob::State*> sts;
188  if (vss->sample(rstate2.get()))
189  while (display_random_valid_states_)
190  {
191  if (!vss->sampleNear(rstate1.get(), rstate2.get(), 10000000))
192  continue;
193  pc->getOMPLStateSpace()->copyToRobotState(robot_state, rstate1.get());
194  robot_state.getJointStateGroup(pc->getJointModelGroupName())->updateLinkTransforms();
195  moveit_msgs::DisplayRobotState state_msg;
196  moveit::core::robotStateToRobotStateMsg(robot_state, state_msg.state);
197  pub_valid_states_.publish(state_msg);
198  n = (n + 1) % 2;
199  if (n == 0)
200  {
201  robot_trajectory::RobotTrajectory traj(pc->getRobotModel(), pc->getJointModelGroupName());
202  unsigned int g = ss.getSpaceInformation()->getMotionStates(rstate1.get(), rstate2.get(), sts, 10, true, true);
203  ROS_INFO("Generated a motion with %u states", g);
204  for (std::size_t i = 0 ; i < g ; ++i)
205  {
206  pc->getOMPLStateSpace()->copyToRobotState(robot_state, sts[i]);
207  traj.addSuffixWayPoint(robot_state, 0.0);
208  }
209  moveit_msgs::DisplayTrajectory msg;
210  msg.model_id = pc->getRobotModel()->getName();
211  msg.trajectory.resize(1);
212  traj.getRobotTrajectoryMsg(msg.trajectory[0]);
213  moveit::core::robotStateToRobotStateMsg(traj.getFirstWayPoint(), msg.trajectory_start);
214  pub_valid_traj_.publish(msg);
215  }
216  rstate2 = rstate1;
217  wait.sleep();
218  }
219  }
220 
221  void displayPlannerData(const planning_scene::PlanningSceneConstPtr& planning_scene,
222  const std::string &link_name) const
223  {
224  ompl_interface::ModelBasedPlanningContextPtr pc = ompl_interface_->getLastPlanningContext();
225  if (pc)
226  {
227  ompl::base::PlannerData pd(pc->getOMPLSimpleSetup()->getSpaceInformation());
228  pc->getOMPLSimpleSetup()->getPlannerData(pd);
229  moveit::core::RobotState robot_state = planning_scene->getCurrentState();
230  visualization_msgs::MarkerArray arr;
231  std_msgs::ColorRGBA color;
232  color.r = 1.0f;
233  color.g = 0.25f;
234  color.b = 1.0f;
235  color.a = 1.0f;
236  unsigned int nv = pd.numVertices();
237  for (unsigned int i = 0 ; i < nv ; ++i)
238  {
239  pc->getOMPLStateSpace()->copyToRobotState(robot_state, pd.getVertex(i).getState());
240  robot_state.getJointStateGroup(pc->getJointModelGroupName())->updateLinkTransforms();
241  const Eigen::Vector3d &pos = robot_state.getLinkState(link_name)->getGlobalLinkTransform().translation();
242 
243  visualization_msgs::Marker mk;
244  mk.header.stamp = ros::Time::now();
245  mk.header.frame_id = planning_scene->getPlanningFrame();
246  mk.ns = "planner_data";
247  mk.id = i;
248  mk.type = visualization_msgs::Marker::SPHERE;
249  mk.action = visualization_msgs::Marker::ADD;
250  mk.pose.position.x = pos.x();
251  mk.pose.position.y = pos.y();
252  mk.pose.position.z = pos.z();
253  mk.pose.orientation.w = 1.0;
254  mk.scale.x = mk.scale.y = mk.scale.z = 0.025;
255  mk.color = color;
256  mk.lifetime = ros::Duration(30.0);
257  arr.markers.push_back(mk);
258  }
259  pub_markers_.publish(arr);
260  }
261  }
262  */
263 
264  void dynamicReconfigureCallback(OMPLDynamicReconfigureConfig& config, uint32_t /*level*/)
265  {
266  if (config.link_for_exploration_tree.empty() && !planner_data_link_name_.empty())
267  {
268  pub_markers_.shutdown();
269  planner_data_link_name_.clear();
270  ROS_INFO_NAMED(LOGNAME, "Not displaying OMPL exploration data structures.");
271  }
272  else if (!config.link_for_exploration_tree.empty() && planner_data_link_name_.empty())
273  {
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());
277  }
278 
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)
283  {
284  display_random_valid_states_ = false;
285  if (pub_valid_states_thread_)
286  {
287  pub_valid_states_thread_->join();
288  pub_valid_states_thread_.reset();
289  }
290  pub_valid_states_.shutdown();
291  pub_valid_traj_.shutdown();
292  }
293  else if (!display_random_valid_states_ && config.display_random_valid_states)
294  {
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;
298  // pub_valid_states_thread_.reset(new boost::thread([this] { displayRandomValidStates(); }));
299  }
300  }
301 
302  ros::NodeHandle nh_;
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 };
307  ros::Publisher pub_markers_;
308  ros::Publisher pub_valid_states_;
309  ros::Publisher pub_valid_traj_;
310  std::string planner_data_link_name_;
311  std::shared_ptr<ompl::msg::OutputHandler> output_handler_;
312 };
313 
314 } // namespace ompl_interface
315 
initialize
bool initialize(MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit, bool refit_bottomup)
ros::console::levels::Error
Error
ros::Publisher
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
planning_interface.h
ompl_interface.h
planning_interface::PlannerConfigurationMap
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
ros::console::levels::Debug
Debug
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ompl_interface::LOGNAME
constexpr char LOGNAME[]
Definition: constrained_goal_sampler.cpp:78
class_loader.hpp
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
ros::console::levels::Info
Info
OMPL_ROS_LOG
#define OMPL_ROS_LOG(ros_log_level)
Definition: ompl_planner_manager.cpp:93
planning_scene.h
planning_interface
ros::console::levels::Warn
Warn
conversions.h
ompl_interface::OMPLPlannerManager
Definition: ompl_planner_manager.cpp:101
profiler.h
planning_scene
CLASS_LOADER_REGISTER_CLASS
CLASS_LOADER_REGISTER_CLASS(ompl_interface::OMPLPlannerManager, planning_interface::PlannerManager)
planning_interface::PlannerManager
ros::NodeHandle


ompl
Author(s): Ioan Sucan
autogenerated on Fri May 3 2024 02:29:39