#include <move_relative.h>

Public Member Functions | |
| void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
| MoveRelative (const std::string &name="move relative", const solvers::PlannerInterfacePtr &planner=solvers::PlannerInterfacePtr()) | |
| void | setDirection (const geometry_msgs::TwistStamped &twist) |
| perform twist motion on specified link More... | |
| void | setDirection (const geometry_msgs::Vector3Stamped &direction) |
| translate link along given direction More... | |
| void | setDirection (const std::map< std::string, double > &joint_deltas) |
| move specified joint variables by given amount More... | |
| void | setGroup (const std::string &group) |
| void | setIKFrame (const Eigen::Isometry3d &pose, const std::string &link) |
| void | setIKFrame (const geometry_msgs::PoseStamped &pose) |
| setters for IK frame More... | |
| void | setIKFrame (const std::string &link) |
| template<typename T > | |
| void | setIKFrame (const T &p, const std::string &link) |
| void | setMaxDistance (double distance) |
| void | setMinDistance (double distance) |
| set minimum / maximum distance to move More... | |
| void | setMinMaxDistance (double min_distance, double max_distance) |
| void | setPathConstraints (moveit_msgs::Constraints path_constraints) |
Public Member Functions inherited from moveit::task_constructor::PropagatingEitherWay | |
| virtual void | computeBackward (const InterfaceState &to) |
| virtual void | computeForward (const InterfaceState &from) |
| PropagatingEitherWay (const std::string &name="propagating either way") | |
| void | restrictDirection (Direction dir) |
Public Member Functions inherited from moveit::task_constructor::Stage | |
| SolutionCallbackList::const_iterator | addSolutionCallback (SolutionCallback &&cb) |
| add function to be called for every newly found solution or failure More... | |
| virtual bool | explainFailure (std::ostream &) const |
| const std::list< SolutionBaseConstPtr > & | failures () const |
| std::set< std::string > | forwardedProperties () const |
| void | forwardProperties (const InterfaceState &source, InterfaceState &dest) |
| forwarding of properties between interface states More... | |
| double | getTotalComputeTime () const |
| Introspection * | introspection () const |
| uint32_t | introspectionId () const |
| const std::string & | markerNS () |
| marker namespace of solution markers More... | |
| const std::string & | name () const |
| size_t | numFailures () const |
| const ContainerBase * | parent () const |
| PropertyMap & | properties () |
| Get the stage's property map. More... | |
| const PropertyMap & | properties () const |
| void | removeSolutionCallback (SolutionCallbackList::const_iterator which) |
| remove function callback More... | |
| void | reportPropertyError (const Property::error &e) |
| Analyze source of error and report accordingly. More... | |
| virtual void | reset () |
| reset stage, clearing all solutions, interfaces, inherited properties. More... | |
| void | setCostTerm (const CostTermConstPtr &term) |
| template<typename T , typename = std::enable_if_t<std::is_constructible<LambdaCostTerm, T>::value>> | |
| void | setCostTerm (T term) |
| void | setForwardedProperties (const std::set< std::string > &names) |
| void | setMarkerNS (const std::string &marker_ns) |
| void | setName (const std::string &name) |
| void | setProperty (const std::string &name, const boost::any &value) |
| Set a previously declared property to a new value. More... | |
| void | setProperty (const std::string &name, const char *value) |
| overload: const char* values are stored as std::string More... | |
| void | setTimeout (double timeout) |
| void | setTrajectoryExecutionInfo (TrajectoryExecutionInfo trajectory_execution_info) |
| Set and get info to use when executing the stage's trajectory. More... | |
| void | silentFailure () |
| Call to increase number of failures w/o storing a (failure) trajectory. More... | |
| const ordered< SolutionBaseConstPtr > & | solutions () const |
| bool | storeFailures () const |
| Should we generate failure solutions? Note: Always report a failure! More... | |
| double | timeout () const |
| timeout of stage per computation More... | |
| TrajectoryExecutionInfo | trajectoryExecutionInfo () const |
| virtual | ~Stage () |
Protected Member Functions | |
| bool | compute (const InterfaceState &state, planning_scene::PlanningScenePtr &scene, SubTrajectory &trajectory, Interface::Direction dir) override |
Protected Member Functions inherited from moveit::task_constructor::PropagatingEitherWay | |
| PropagatingEitherWay (PropagatingEitherWayPrivate *impl) | |
| template<Interface::Direction dir> | |
| void | send (const InterfaceState &start, InterfaceState &&end, SubTrajectory &&trajectory) |
| void | sendBackward (InterfaceState &&from, const InterfaceState &to, SubTrajectory &&trajectory) |
| void | sendForward (const InterfaceState &from, InterfaceState &&to, SubTrajectory &&trajectory) |
Protected Member Functions inherited from moveit::task_constructor::ComputeBase | |
| ComputeBase (ComputeBasePrivate *impl) | |
| ComputeBase can only be instantiated by derived classes in stage.cpp. More... | |
Protected Member Functions inherited from moveit::task_constructor::Stage | |
| Stage (const Stage &)=delete | |
| Stage cannot be copied. More... | |
| Stage (StagePrivate *impl) | |
| Stage can only be instantiated through derived classes. More... | |
Protected Attributes | |
| solvers::PlannerInterfacePtr | planner_ |
Protected Attributes inherited from moveit::task_constructor::Stage | |
| StagePrivate * | pimpl_ |
Additional Inherited Members | |
Public Types inherited from moveit::task_constructor::PropagatingEitherWay | |
| enum | Direction : uint8_t { AUTO = 0x00, FORWARD = 0x01, BACKWARD = 0x02 } |
Public Types inherited from moveit::task_constructor::Stage | |
| using | pointer = std::unique_ptr< Stage > |
| enum | PropertyInitializerSource : uint8_t { DEFAULT = 0, MANUAL = 1, PARENT = 2, INTERFACE = 4 } |
| using | SolutionCallback = std::function< void(const SolutionBase &)> |
| using | SolutionCallbackList = std::list< SolutionCallback > |
Perform a Cartesian motion relative to some link
Definition at line 57 of file move_relative.h.
| moveit::task_constructor::stages::MoveRelative::MoveRelative | ( | const std::string & | name = "move relative", |
| const solvers::PlannerInterfacePtr & | planner = solvers::PlannerInterfacePtr() |
||
| ) |
Definition at line 146 of file move_relative.cpp.
|
overrideprotectedvirtual |
Reimplemented from moveit::task_constructor::PropagatingEitherWay.
Definition at line 261 of file move_relative.cpp.
|
overridevirtual |
initialize stage once before planning
When called, properties configured for initialization from parent are already defined. Push interfaces are not yet defined!
Reimplemented from moveit::task_constructor::Stage.
Definition at line 173 of file move_relative.cpp.
|
inline |
perform twist motion on specified link
Definition at line 90 of file move_relative.h.
|
inline |
translate link along given direction
Definition at line 92 of file move_relative.h.
|
inline |
move specified joint variables by given amount
Definition at line 94 of file move_relative.h.
|
inline |
Definition at line 65 of file move_relative.h.
| void moveit::task_constructor::stages::MoveRelative::setIKFrame | ( | const Eigen::Isometry3d & | pose, |
| const std::string & | link | ||
| ) |
Definition at line 166 of file move_relative.cpp.
|
inline |
setters for IK frame
Definition at line 67 of file move_relative.h.
|
inline |
Definition at line 75 of file move_relative.h.
|
inline |
Definition at line 70 of file move_relative.h.
|
inline |
Definition at line 79 of file move_relative.h.
|
inline |
set minimum / maximum distance to move
Definition at line 78 of file move_relative.h.
|
inline |
Definition at line 80 of file move_relative.h.
|
inline |
Definition at line 85 of file move_relative.h.
|
protected |
Definition at line 102 of file move_relative.h.