40 #include <boost/algorithm/string/join.hpp>
42 #include <dynamic_reconfigure/server.h>
43 #include <moveit_ros_planning/SenseForPlanDynamicReconfigureConfig.h>
47 using namespace moveit_ros_planning;
49 class PlanWithSensing::DynamicReconfigureImpl
52 DynamicReconfigureImpl(PlanWithSensing* owner)
53 : owner_(owner), dynamic_reconfigure_server_(
ros::NodeHandle(
"~/sense_for_plan"))
55 dynamic_reconfigure_server_.setCallback(
56 [
this](
const auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
60 void dynamicReconfigureCallback(
const SenseForPlanDynamicReconfigureConfig& config, uint32_t )
62 owner_->setMaxSafePathCost(config.max_safe_path_cost);
63 owner_->setMaxCostSources(config.max_cost_sources);
64 owner_->setMaxLookAttempts(config.max_look_attempts);
65 owner_->setDiscardOverlappingCostSources(config.discard_overlapping_cost_sources);
68 PlanWithSensing* owner_;
69 dynamic_reconfigure::Server<SenseForPlanDynamicReconfigureConfig> dynamic_reconfigure_server_;
74 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution)
75 : node_handle_(
"~"), trajectory_execution_manager_(trajectory_execution)
91 sensor_manager_loader_ = std::make_unique<pluginlib::ClassLoader<moveit_sensor_manager::MoveItSensorManager>>(
92 "moveit_core",
"moveit_sensor_manager::MoveItSensorManager");
96 ROS_ERROR_STREAM(
"Exception while creating sensor manager plugin loader: " << ex.what());
108 ROS_ERROR_STREAM(
"Exception while loading sensor manager '" << manager <<
"': " << ex.what());
113 std::vector<std::string> sensors;
115 ROS_INFO_STREAM(
"PlanWithSensing is aware of the following sensors: " << boost::algorithm::join(sensors,
", "));
125 delete reconfigure_impl_;
130 if (flag && !display_cost_sources_)
132 cost_sources_publisher_ =
133 node_handle_.advertise<visualization_msgs::MarkerArray>(
"display_cost_sources", 100,
true);
134 else if (!flag && display_cost_sources_)
135 cost_sources_publisher_.shutdown();
136 display_cost_sources_ = flag;
141 unsigned int max_look_attempts,
double max_safe_path_cost)
143 if (max_safe_path_cost <= std::numeric_limits<double>::epsilon())
144 max_safe_path_cost = default_max_safe_path_cost_;
146 if (max_look_attempts == 0)
147 max_look_attempts = default_max_look_attempts_;
149 double previous_cost = 0.0;
150 unsigned int look_attempts = 0;
154 bool just_looked_around =
false;
159 bool look_around_failed =
false;
165 bool solved = motion_planner(plan);
166 if (!solved || plan.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
170 std::set<collision_detection::CostSource> cost_sources;
178 std::set<collision_detection::CostSource> cost_sources_i;
181 discard_overlapping_cost_sources_);
182 cost_sources.insert(cost_sources_i.begin(), cost_sources_i.end());
183 if (cost_sources.size() > max_cost_sources_)
185 std::set<collision_detection::CostSource> other;
186 other.swap(cost_sources);
188 for (std::set<collision_detection::CostSource>::iterator it = other.begin(); j < max_cost_sources_; ++it, ++j)
189 cost_sources.insert(*it);
195 if (display_cost_sources_)
197 visualization_msgs::MarkerArray arr;
199 cost_sources_publisher_.publish(arr);
203 ROS_DEBUG(
"The total cost of the trajectory is %lf.", cost);
204 if (previous_cost > 0.0)
205 ROS_DEBUG(
"The change in the trajectory cost is %lf after the perception step.", cost - previous_cost);
206 if (cost > max_safe_path_cost && look_attempts < max_look_attempts)
209 ROS_INFO(
"The cost of the trajectory is %lf, which is above the maximum safe cost of %lf. Attempt %u (of at most "
210 "%u) at looking around.",
211 cost, max_safe_path_cost, look_attempts, max_look_attempts);
213 bool looked_at_result = lookAt(cost_sources, plan.
planning_scene_->getPlanningFrame());
214 if (looked_at_result)
215 ROS_INFO(
"Sensor was successfully actuated. Attempting to recompute a motion plan.");
218 if (look_around_failed)
219 ROS_WARN(
"Looking around seems to keep failing. Giving up.");
221 ROS_WARN(
"Looking around seems to have failed. Attempting to recompute a motion plan anyway.");
223 if (looked_at_result || !look_around_failed)
225 previous_cost = cost;
226 just_looked_around =
true;
228 look_around_failed = !looked_at_result;
230 if (just_looked_around)
234 if (cost > max_safe_path_cost)
236 plan.
error_code_.val = moveit_msgs::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA;
247 const std::string& frame_id)
249 if (!sensor_manager_)
251 ROS_WARN(
"It seems looking around would be useful, but no MoveIt Sensor Manager is loaded. Did you set "
252 "~moveit_sensor_manager ?");
256 if (before_look_callback_)
257 before_look_callback_();
259 std::vector<std::string> names;
260 sensor_manager_->getSensorsList(names);
261 geometry_msgs::PointStamped
point;
262 for (
const std::string&
name : names)
266 point.header.frame_id = frame_id;
268 moveit_msgs::RobotTrajectory sensor_trajectory;
269 if (sensor_manager_->pointSensorTo(
name,
point, sensor_trajectory))
272 return trajectory_execution_manager_->push(sensor_trajectory) &&
273 trajectory_execution_manager_->executeAndWait();