plan_with_sensing.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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 */
36 
37 #pragma once
38 
42 
46 
47 #include <memory>
48 
49 namespace plan_execution
50 {
51 MOVEIT_CLASS_FORWARD(PlanWithSensing); // Defines PlanWithSensingPtr, ConstPtr, WeakPtr... etc
52 
53 class PlanWithSensing
54 {
55 public:
56  PlanWithSensing(const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution);
58 
59  const trajectory_execution_manager::TrajectoryExecutionManagerPtr& getTrajectoryExecutionManager() const
60  {
62  }
63 
64  bool computePlan(ExecutableMotionPlan& plan, const ExecutableMotionPlanComputationFn& motion_planner,
65  unsigned int max_look_attempts, double max_safe_path_cost);
66 
67  double getMaxSafePathCost() const
68  {
70  }
71 
72  void setMaxSafePathCost(double max_safe_path_cost)
73  {
74  default_max_safe_path_cost_ = max_safe_path_cost;
75  }
76 
77  void setMaxLookAttempts(unsigned int attempts)
78  {
79  default_max_look_attempts_ = attempts;
80  }
81 
82  unsigned int getMaxLookAttempts() const
83  {
85  }
86 
87  unsigned int getMaxCostSources() const
88  {
89  return max_cost_sources_;
90  }
91 
92  void setMaxCostSources(unsigned int value)
93  {
94  max_cost_sources_ = value;
95  }
96 
98  {
100  }
101 
102  void setDiscardOverlappingCostSources(double value)
103  {
105  }
106 
107  void setBeforeLookCallback(const boost::function<void()>& callback)
108  {
110  }
111 
112  void displayCostSources(bool flag);
113 
114 private:
115  bool lookAt(const std::set<collision_detection::CostSource>& cost_sources, const std::string& frame_id);
116 
118  trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_;
119 
120  std::unique_ptr<pluginlib::ClassLoader<moveit_sensor_manager::MoveItSensorManager> > sensor_manager_loader_;
121  moveit_sensor_manager::MoveItSensorManagerPtr sensor_manager_;
122  unsigned int default_max_look_attempts_;
124 
126  unsigned int max_cost_sources_;
127 
130 
131  boost::function<void()> before_look_callback_;
132 
135 };
136 } // namespace plan_execution
plan_execution::PlanWithSensing::getDiscardOverlappingCostSources
double getDiscardOverlappingCostSources() const
Definition: plan_with_sensing.h:129
plan_execution::PlanWithSensing::sensor_manager_
moveit_sensor_manager::MoveItSensorManagerPtr sensor_manager_
Definition: plan_with_sensing.h:153
sensor_manager.h
ros::Publisher
plan_execution::PlanWithSensing::PlanWithSensing
PlanWithSensing(const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
Definition: plan_with_sensing.cpp:73
plan_execution::PlanWithSensing::reconfigure_impl_
DynamicReconfigureImpl * reconfigure_impl_
Definition: plan_with_sensing.h:165
plan_execution::PlanWithSensing::lookAt
bool lookAt(const std::set< collision_detection::CostSource > &cost_sources, const std::string &frame_id)
Definition: plan_with_sensing.cpp:246
plan_execution::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(PlanExecution)
plan_execution::PlanWithSensing::trajectory_execution_manager_
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
Definition: plan_with_sensing.h:150
plan_execution::PlanWithSensing::getMaxLookAttempts
unsigned int getMaxLookAttempts() const
Definition: plan_with_sensing.h:114
plan_execution::PlanWithSensing::sensor_manager_loader_
std::unique_ptr< pluginlib::ClassLoader< moveit_sensor_manager::MoveItSensorManager > > sensor_manager_loader_
Definition: plan_with_sensing.h:152
plan_execution::PlanWithSensing::setMaxSafePathCost
void setMaxSafePathCost(double max_safe_path_cost)
Definition: plan_with_sensing.h:104
plan_execution::PlanWithSensing::discard_overlapping_cost_sources_
double discard_overlapping_cost_sources_
Definition: plan_with_sensing.h:157
plan_execution::PlanWithSensing::getMaxCostSources
unsigned int getMaxCostSources() const
Definition: plan_with_sensing.h:119
plan_execution::PlanWithSensing::cost_sources_publisher_
ros::Publisher cost_sources_publisher_
Definition: plan_with_sensing.h:161
plan_execution::PlanWithSensing::default_max_safe_path_cost_
double default_max_safe_path_cost_
Definition: plan_with_sensing.h:155
plan_execution::PlanWithSensing::setMaxLookAttempts
void setMaxLookAttempts(unsigned int attempts)
Definition: plan_with_sensing.h:109
plan_execution::PlanWithSensing::display_cost_sources_
bool display_cost_sources_
Definition: plan_with_sensing.h:160
plan_execution::PlanWithSensing::computePlan
bool computePlan(ExecutableMotionPlan &plan, const ExecutableMotionPlanComputationFn &motion_planner, unsigned int max_look_attempts, double max_safe_path_cost)
Definition: plan_with_sensing.cpp:139
plan_execution::PlanWithSensing::getMaxSafePathCost
double getMaxSafePathCost() const
Definition: plan_with_sensing.h:99
plan_execution::PlanWithSensing::default_max_look_attempts_
unsigned int default_max_look_attempts_
Definition: plan_with_sensing.h:154
plan_execution::PlanWithSensing::before_look_callback_
boost::function< void()> before_look_callback_
Definition: plan_with_sensing.h:163
plan_execution::PlanWithSensing::displayCostSources
void displayCostSources(bool flag)
Definition: plan_with_sensing.cpp:128
class_loader.hpp
plan_execution::PlanWithSensing::DynamicReconfigureImpl
Definition: plan_with_sensing.cpp:81
plan_execution::PlanWithSensing::~PlanWithSensing
~PlanWithSensing()
Definition: plan_with_sensing.cpp:123
plan_execution
This namespace includes functionality specific to the execution and monitoring of motion plans.
Definition: plan_execution.h:50
trajectory_monitor.h
class_forward.h
trajectory_execution_manager.h
plan_execution::PlanWithSensing::setDiscardOverlappingCostSources
void setDiscardOverlappingCostSources(double value)
Definition: plan_with_sensing.h:134
plan_execution::PlanWithSensing::setBeforeLookCallback
void setBeforeLookCallback(const boost::function< void()> &callback)
Definition: plan_with_sensing.h:139
plan_execution::PlanWithSensing::getTrajectoryExecutionManager
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & getTrajectoryExecutionManager() const
Definition: plan_with_sensing.h:91
plan_execution::PlanWithSensing::max_cost_sources_
unsigned int max_cost_sources_
Definition: plan_with_sensing.h:158
plan_execution::ExecutableMotionPlanComputationFn
boost::function< bool(ExecutableMotionPlan &)> ExecutableMotionPlanComputationFn
The signature of a function that can compute a motion plan.
Definition: plan_representation.h:120
plan_representation.h
ros::NodeHandle
plan_execution::PlanWithSensing::node_handle_
ros::NodeHandle node_handle_
Definition: plan_with_sensing.h:149
plan_execution::PlanWithSensing::setMaxCostSources
void setMaxCostSources(unsigned int value)
Definition: plan_with_sensing.h:124


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:03