moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl Class Reference

Public Member Functions

 MoveGroupInterfaceImpl (const rclcpp::Node::SharedPtr &node, const Options &opt, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, const rclcpp::Duration &wait_for_servers)
 
 ~MoveGroupInterfaceImpl ()
 
const std::shared_ptr< tf2_ros::Buffer > & getTF () const
 
const OptionsgetOptions () const
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
const moveit::core::JointModelGroupgetJointModelGroup () const
 
rclcpp_action::Client< moveit_msgs::action::MoveGroup > & getMoveGroupClient () const
 
bool getInterfaceDescription (moveit_msgs::msg::PlannerInterfaceDescription &desc)
 
bool getInterfaceDescriptions (std::vector< moveit_msgs::msg::PlannerInterfaceDescription > &desc)
 
std::map< std::string, std::string > getPlannerParams (const std::string &planner_id, const std::string &group="")
 
void setPlannerParams (const std::string &planner_id, const std::string &group, const std::map< std::string, std::string > &params, bool replace=false)
 
std::string getDefaultPlanningPipelineId () const
 
void setPlanningPipelineId (const std::string &pipeline_id)
 
const std::string & getPlanningPipelineId () const
 
std::string getDefaultPlannerId (const std::string &group) const
 
void setPlannerId (const std::string &planner_id)
 
const std::string & getPlannerId () const
 
void setNumPlanningAttempts (unsigned int num_planning_attempts)
 
void setMaxVelocityScalingFactor (double value)
 
void setMaxAccelerationScalingFactor (double value)
 
void setMaxScalingFactor (double &variable, const double target_value, const char *factor_name, double fallback_value)
 
moveit::core::RobotStategetTargetRobotState ()
 
const moveit::core::RobotStategetTargetRobotState () const
 
void setStartState (const moveit::core::RobotState &start_state)
 
void setStartStateToCurrentState ()
 
moveit::core::RobotStatePtr getStartState ()
 
bool setJointValueTarget (const geometry_msgs::msg::Pose &eef_pose, const std::string &end_effector_link, const std::string &frame, bool approx)
 
void setEndEffectorLink (const std::string &end_effector)
 
void clearPoseTarget (const std::string &end_effector_link)
 
void clearPoseTargets ()
 
const std::string & getEndEffectorLink () const
 
const std::string & getEndEffector () const
 
bool setPoseTargets (const std::vector< geometry_msgs::msg::PoseStamped > &poses, const std::string &end_effector_link)
 
bool hasPoseTarget (const std::string &end_effector_link) const
 
const geometry_msgs::msg::PoseStamped & getPoseTarget (const std::string &end_effector_link) const
 
const std::vector< geometry_msgs::msg::PoseStamped > & getPoseTargets (const std::string &end_effector_link) const
 
void setPoseReferenceFrame (const std::string &pose_reference_frame)
 
void setSupportSurfaceName (const std::string &support_surface)
 
const std::string & getPoseReferenceFrame () const
 
void setTargetType (ActiveTargetType type)
 
ActiveTargetType getTargetType () const
 
bool startStateMonitor (double wait)
 
bool getCurrentState (moveit::core::RobotStatePtr &current_state, double wait_seconds=1.0)
 
moveit::core::MoveItErrorCode plan (Plan &plan)
 
moveit::core::MoveItErrorCode move (bool wait)
 
moveit::core::MoveItErrorCode execute (const moveit_msgs::msg::RobotTrajectory &trajectory, bool wait, const std::vector< std::string > &controllers=std::vector< std::string >())
 
double computeCartesianPath (const std::vector< geometry_msgs::msg::Pose > &waypoints, double step, double jump_threshold, moveit_msgs::msg::RobotTrajectory &msg, const moveit_msgs::msg::Constraints &path_constraints, bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes &error_code)
 
void stop ()
 
bool attachObject (const std::string &object, const std::string &link, const std::vector< std::string > &touch_links)
 
bool detachObject (const std::string &name)
 
double getGoalPositionTolerance () const
 
double getGoalOrientationTolerance () const
 
double getGoalJointTolerance () const
 
void setGoalJointTolerance (double tolerance)
 
void setGoalPositionTolerance (double tolerance)
 
void setGoalOrientationTolerance (double tolerance)
 
void setPlanningTime (double seconds)
 
double getPlanningTime () const
 
void constructMotionPlanRequest (moveit_msgs::msg::MotionPlanRequest &request) const
 
void constructGoal (moveit_msgs::action::MoveGroup::Goal &goal) const
 
void setPathConstraints (const moveit_msgs::msg::Constraints &constraint)
 
bool setPathConstraints (const std::string &constraint)
 
void clearPathConstraints ()
 
void setTrajectoryConstraints (const moveit_msgs::msg::TrajectoryConstraints &constraint)
 
void clearTrajectoryConstraints ()
 
std::vector< std::string > getKnownConstraints () const
 
moveit_msgs::msg::Constraints getPathConstraints () const
 
moveit_msgs::msg::TrajectoryConstraints getTrajectoryConstraints () const
 
void initializeConstraintsStorage (const std::string &host, unsigned int port)
 
void setWorkspace (double minx, double miny, double minz, double maxx, double maxy, double maxz)
 
rclcpp::Clock::SharedPtr getClock ()
 

Detailed Description

Definition at line 106 of file move_group_interface.cpp.

Constructor & Destructor Documentation

◆ MoveGroupInterfaceImpl()

moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::MoveGroupInterfaceImpl ( const rclcpp::Node::SharedPtr &  node,
const Options opt,
const std::shared_ptr< tf2_ros::Buffer > &  tf_buffer,
const rclcpp::Duration &  wait_for_servers 
)
inline

Definition at line 111 of file move_group_interface.cpp.

Here is the call graph for this function:

◆ ~MoveGroupInterfaceImpl()

moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::~MoveGroupInterfaceImpl ( )
inline

Definition at line 197 of file move_group_interface.cpp.

Member Function Documentation

◆ attachObject()

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::attachObject ( const std::string &  object,
const std::string &  link,
const std::vector< std::string > &  touch_links 
)
inline

Definition at line 913 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ clearPathConstraints()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::clearPathConstraints ( )
inline

Definition at line 1159 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ clearPoseTarget()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::clearPoseTarget ( const std::string &  end_effector_link)
inline

Definition at line 484 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ clearPoseTargets()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::clearPoseTargets ( )
inline

Definition at line 489 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ clearTrajectoryConstraints()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::clearTrajectoryConstraints ( )
inline

Definition at line 1169 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ computeCartesianPath()

double moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::computeCartesianPath ( const std::vector< geometry_msgs::msg::Pose > &  waypoints,
double  step,
double  jump_threshold,
moveit_msgs::msg::RobotTrajectory &  msg,
const moveit_msgs::msg::Constraints &  path_constraints,
bool  avoid_collisions,
moveit_msgs::msg::MoveItErrorCodes &  error_code 
)
inline

Definition at line 854 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ constructGoal()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::constructGoal ( moveit_msgs::action::MoveGroup::Goal &  goal) const
inline

Definition at line 1076 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ constructMotionPlanRequest()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::constructMotionPlanRequest ( moveit_msgs::msg::MotionPlanRequest &  request) const
inline

Definition at line 1014 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ detachObject()

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::detachObject ( const std::string &  name)
inline

Definition at line 943 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ execute()

moveit::core::MoveItErrorCode moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::execute ( const moveit_msgs::msg::RobotTrajectory &  trajectory,
bool  wait,
const std::vector< std::string > &  controllers = std::vector<std::string>() 
)
inline

Definition at line 786 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getClock()

rclcpp::Clock::SharedPtr moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getClock ( )
inline

Definition at line 1234 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getCurrentState()

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getCurrentState ( moveit::core::RobotStatePtr &  current_state,
double  wait_seconds = 1.0 
)
inline

Definition at line 616 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getDefaultPlannerId()

std::string moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getDefaultPlannerId ( const std::string &  group) const
inline

Definition at line 322 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getDefaultPlanningPipelineId()

std::string moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getDefaultPlanningPipelineId ( ) const
inline

Definition at line 299 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getEndEffector()

const std::string& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getEndEffector ( ) const
inline

Definition at line 499 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getEndEffectorLink()

const std::string& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getEndEffectorLink ( ) const
inline

Definition at line 494 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getGoalJointTolerance()

double moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getGoalJointTolerance ( ) const
inline

Definition at line 983 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getGoalOrientationTolerance()

double moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getGoalOrientationTolerance ( ) const
inline

Definition at line 978 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getGoalPositionTolerance()

double moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getGoalPositionTolerance ( ) const
inline

Definition at line 973 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getInterfaceDescription()

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getInterfaceDescription ( moveit_msgs::msg::PlannerInterfaceDescription &  desc)
inline

Definition at line 233 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getInterfaceDescriptions()

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getInterfaceDescriptions ( std::vector< moveit_msgs::msg::PlannerInterfaceDescription > &  desc)
inline

Definition at line 250 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getJointModelGroup()

const moveit::core::JointModelGroup* moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getJointModelGroup ( ) const
inline

Definition at line 223 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getKnownConstraints()

std::vector<std::string> moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getKnownConstraints ( ) const
inline

Definition at line 1174 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getMoveGroupClient()

rclcpp_action::Client<moveit_msgs::action::MoveGroup>& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getMoveGroupClient ( ) const
inline

Definition at line 228 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getOptions()

const Options& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getOptions ( ) const
inline

Definition at line 213 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getPathConstraints()

moveit_msgs::msg::Constraints moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getPathConstraints ( ) const
inline

Definition at line 1189 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getPlannerId()

const std::string& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getPlannerId ( ) const
inline

Definition at line 347 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getPlannerParams()

std::map<std::string, std::string> moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getPlannerParams ( const std::string &  planner_id,
const std::string &  group = "" 
)
inline

Definition at line 266 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getPlanningPipelineId()

const std::string& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getPlanningPipelineId ( ) const
inline

Definition at line 317 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getPlanningTime()

double moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getPlanningTime ( ) const
inline

Definition at line 1009 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getPoseReferenceFrame()

const std::string& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getPoseReferenceFrame ( ) const
inline

Definition at line 585 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getPoseTarget()

const geometry_msgs::msg::PoseStamped& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getPoseTarget ( const std::string &  end_effector_link) const
inline

Definition at line 540 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getPoseTargets()

const std::vector<geometry_msgs::msg::PoseStamped>& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getPoseTargets ( const std::string &  end_effector_link) const
inline

Definition at line 558 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getRobotModel ( ) const
inline

Definition at line 218 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getStartState()

moveit::core::RobotStatePtr moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getStartState ( )
inline

Definition at line 411 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getTargetRobotState() [1/2]

moveit::core::RobotState& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getTargetRobotState ( )
inline

Definition at line 391 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getTargetRobotState() [2/2]

const moveit::core::RobotState& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getTargetRobotState ( ) const
inline

Definition at line 396 of file move_group_interface.cpp.

◆ getTargetType()

ActiveTargetType moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getTargetType ( ) const
inline

Definition at line 595 of file move_group_interface.cpp.

◆ getTF()

const std::shared_ptr<tf2_ros::Buffer>& moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getTF ( ) const
inline

Definition at line 208 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ getTrajectoryConstraints()

moveit_msgs::msg::TrajectoryConstraints moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::getTrajectoryConstraints ( ) const
inline

Definition at line 1201 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ hasPoseTarget()

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::hasPoseTarget ( const std::string &  end_effector_link) const
inline

Definition at line 534 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ initializeConstraintsStorage()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::initializeConstraintsStorage ( const std::string &  host,
unsigned int  port 
)
inline

Definition at line 1213 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ move()

moveit::core::MoveItErrorCode moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::move ( bool  wait)
inline

Definition at line 715 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ plan()

moveit::core::MoveItErrorCode moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::plan ( Plan plan)
inline

Definition at line 638 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setEndEffectorLink()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setEndEffectorLink ( const std::string &  end_effector)
inline

Definition at line 479 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setGoalJointTolerance()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setGoalJointTolerance ( double  tolerance)
inline

Definition at line 988 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setGoalOrientationTolerance()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setGoalOrientationTolerance ( double  tolerance)
inline

Definition at line 998 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setGoalPositionTolerance()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setGoalPositionTolerance ( double  tolerance)
inline

Definition at line 993 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setJointValueTarget()

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setJointValueTarget ( const geometry_msgs::msg::Pose &  eef_pose,
const std::string &  end_effector_link,
const std::string &  frame,
bool  approx 
)
inline

Definition at line 425 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setMaxAccelerationScalingFactor()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setMaxAccelerationScalingFactor ( double  value)
inline

Definition at line 362 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setMaxScalingFactor()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setMaxScalingFactor ( double &  variable,
const double  target_value,
const char *  factor_name,
double  fallback_value 
)
inline

Definition at line 367 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setMaxVelocityScalingFactor()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setMaxVelocityScalingFactor ( double  value)
inline

Definition at line 357 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setNumPlanningAttempts()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setNumPlanningAttempts ( unsigned int  num_planning_attempts)
inline

Definition at line 352 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setPathConstraints() [1/2]

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setPathConstraints ( const moveit_msgs::msg::Constraints &  constraint)
inline

Definition at line 1136 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setPathConstraints() [2/2]

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setPathConstraints ( const std::string &  constraint)
inline

Definition at line 1141 of file move_group_interface.cpp.

◆ setPlannerId()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setPlannerId ( const std::string &  planner_id)
inline

Definition at line 342 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setPlannerParams()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setPlannerParams ( const std::string &  planner_id,
const std::string &  group,
const std::map< std::string, std::string > &  params,
bool  replace = false 
)
inline

Definition at line 284 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setPlanningPipelineId()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setPlanningPipelineId ( const std::string &  pipeline_id)
inline

Definition at line 306 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setPlanningTime()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setPlanningTime ( double  seconds)
inline

Definition at line 1003 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setPoseReferenceFrame()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setPoseReferenceFrame ( const std::string &  pose_reference_frame)
inline

Definition at line 575 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setPoseTargets()

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setPoseTargets ( const std::vector< geometry_msgs::msg::PoseStamped > &  poses,
const std::string &  end_effector_link 
)
inline

Definition at line 515 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setStartState()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setStartState ( const moveit::core::RobotState start_state)
inline

Definition at line 401 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setStartStateToCurrentState()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setStartStateToCurrentState ( )
inline

Definition at line 406 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setSupportSurfaceName()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setSupportSurfaceName ( const std::string &  support_surface)
inline

Definition at line 580 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setTargetType()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setTargetType ( ActiveTargetType  type)
inline

Definition at line 590 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setTrajectoryConstraints()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setTrajectoryConstraints ( const moveit_msgs::msg::TrajectoryConstraints &  constraint)
inline

Definition at line 1164 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setWorkspace()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setWorkspace ( double  minx,
double  miny,
double  minz,
double  maxx,
double  maxy,
double  maxz 
)
inline

Definition at line 1222 of file move_group_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ startStateMonitor()

bool moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::startStateMonitor ( double  wait)
inline

Definition at line 600 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ stop()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::stop ( )
inline

Definition at line 903 of file move_group_interface.cpp.

Here is the caller graph for this function:

The documentation for this class was generated from the following file: