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_msgs::msg::RobotState &start_state)
 
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)
 Convert a vector of PoseStamped to a vector of PlaceLocation. More...
 
moveit::core::MoveItErrorCode move (bool wait)
 
moveit::core::MoveItErrorCode execute (const moveit_msgs::msg::RobotTrajectory &trajectory, bool wait)
 
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 constructRobotState (moveit_msgs::msg::RobotState &state) 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 88 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 93 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 183 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 1004 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 1239 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 471 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 476 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 1249 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 955 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 1156 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 1102 of file move_group_interface.cpp.

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

◆ constructRobotState()

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::constructRobotState ( moveit_msgs::msg::RobotState &  state) const
inline

Definition at line 1097 of file move_group_interface.cpp.

◆ detachObject()

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

Definition at line 1030 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 
)
inline

Definition at line 889 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 1306 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 597 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 309 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 286 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 486 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 481 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 1066 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 1061 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 1056 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 220 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 237 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 210 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 1254 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 215 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 200 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 1269 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 334 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 253 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 304 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 1092 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 566 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 525 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 541 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 205 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 406 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 378 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 383 of file move_group_interface.cpp.

◆ getTargetType()

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

Definition at line 576 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 195 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 1277 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 519 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 1285 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 818 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

Convert a vector of PoseStamped to a vector of PlaceLocation.

Definition at line 741 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 466 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 1071 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 1081 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 1076 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 414 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 349 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 354 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 344 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 339 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 1216 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 1221 of file move_group_interface.cpp.

◆ setPlannerId()

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

Definition at line 329 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 271 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 293 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 1086 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 556 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 500 of file move_group_interface.cpp.

Here is the caller graph for this function:

◆ setStartState() [1/2]

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

Definition at line 393 of file move_group_interface.cpp.

Here is the call graph for this function:

◆ setStartState() [2/2]

void moveit::planning_interface::MoveGroupInterface::MoveGroupInterfaceImpl::setStartState ( const moveit_msgs::msg::RobotState &  start_state)
inline

Definition at line 388 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 399 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 561 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 571 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 1244 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 1294 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 581 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 994 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: