Public Member Functions | |
void | allowLooking (bool flag) |
void | allowReplanning (bool flag) |
void | clearPathConstraints () |
void | clearPoseTarget (const std::string &end_effector_link) |
void | clearPoseTargets () |
double | computeCartesianPath (const std::vector< geometry_msgs::Pose > &waypoints, double step, double jump_threshold, moveit_msgs::RobotTrajectory &msg, bool avoid_collisions) |
void | constructGoal (moveit_msgs::MoveGroupGoal &goal_out) |
void | constructGoal (moveit_msgs::PickupGoal &goal_out, const std::string &object) |
void | constructGoal (moveit_msgs::PlaceGoal &goal_out, const std::string &object) |
bool | execute (const Plan &plan, bool wait) |
bool | getCurrentState (robot_state::RobotStatePtr ¤t_state) |
const std::string & | getEndEffector () const |
const std::string & | getEndEffectorLink () const |
double | getGoalJointTolerance () const |
double | getGoalOrientationTolerance () const |
double | getGoalPositionTolerance () const |
bool | getInterfaceDescription (moveit_msgs::PlannerInterfaceDescription &desc) |
robot_state::JointStateGroup * | getJointStateTarget () |
std::vector< std::string > | getKnownConstraints () const |
const Options & | getOptions () const |
double | getPlanningTime () const |
const std::string & | getPoseReferenceFrame () const |
const geometry_msgs::PoseStamped & | getPoseTarget (const std::string &end_effector_link) const |
const std::vector < geometry_msgs::PoseStamped > & | getPoseTargets (const std::string &end_effector_link) const |
double | getReplanningDelay () const |
const robot_model::RobotModelConstPtr & | getRobotModel () const |
ActiveTargetType | getTargetType () const |
const boost::shared_ptr < tf::Transformer > & | getTF () const |
bool | hasPoseTarget (const std::string &end_effector_link) const |
void | initializeConstraintsStorage (const std::string &host, unsigned int port) |
bool | move (bool wait) |
MoveGroupImpl (const Options &opt, const boost::shared_ptr< tf::Transformer > &tf, const ros::Duration &wait_for_server) | |
bool | pick (const std::string &object, const std::vector< manipulation_msgs::Grasp > &grasps) |
bool | place (const std::string &object, const std::vector< geometry_msgs::PoseStamped > &poses) |
Place an object at one of the specified possible locations. | |
bool | place (const std::string &object, const std::vector< manipulation_msgs::PlaceLocation > &locations) |
bool | plan (Plan &plan) |
void | setEndEffectorLink (const std::string &end_effector) |
void | setGoalJointTolerance (double tolerance) |
void | setGoalOrientationTolerance (double tolerance) |
void | setGoalPositionTolerance (double tolerance) |
void | setPathConstraints (const moveit_msgs::Constraints &constraint) |
bool | setPathConstraints (const std::string &constraint) |
void | setPlannerId (const std::string &planner_id) |
void | setPlanningTime (double seconds) |
void | setPoseReferenceFrame (const std::string &pose_reference_frame) |
bool | setPoseTargets (const std::vector< geometry_msgs::PoseStamped > &poses, const std::string &end_effector_link) |
void | setReplanningDelay (double delay) |
void | setStartState (const robot_state::RobotState &start_state) |
void | setStartStateToCurrentState () |
void | setSupportSurfaceName (const std::string &support_surface) |
void | setTargetType (ActiveTargetType type) |
void | setWorkspace (double minx, double miny, double minz, double maxx, double maxy, double maxz) |
void | stop () |
template<typename T > | |
void | waitForAction (const T &action, const ros::Duration &wait_for_server, const std::string &name) |
~MoveGroupImpl () | |
Private Member Functions | |
void | initializeConstraintsStorageThread (const std::string &host, unsigned int port) |
Private Attributes | |
ActiveTargetType | active_target_ |
bool | can_look_ |
bool | can_replan_ |
ros::ServiceClient | cartesian_path_service_ |
robot_state::RobotStatePtr | considered_start_state_ |
boost::scoped_ptr< boost::thread > | constraints_init_thread_ |
boost::scoped_ptr < moveit_warehouse::ConstraintsStorage > | constraints_storage_ |
planning_scene_monitor::CurrentStateMonitorPtr | current_state_monitor_ |
std::string | end_effector_link_ |
ros::ServiceClient | execute_service_ |
double | goal_joint_tolerance_ |
double | goal_orientation_tolerance_ |
double | goal_position_tolerance_ |
bool | initializing_constraints_ |
robot_state::RobotStatePtr | joint_state_target_ |
boost::scoped_ptr < actionlib::SimpleActionClient < moveit_msgs::MoveGroupAction > > | move_action_client_ |
ros::NodeHandle | node_handle_ |
Options | opt_ |
boost::scoped_ptr < moveit_msgs::Constraints > | path_constraints_ |
boost::scoped_ptr < actionlib::SimpleActionClient < moveit_msgs::PickupAction > > | pick_action_client_ |
boost::scoped_ptr < actionlib::SimpleActionClient < moveit_msgs::PlaceAction > > | place_action_client_ |
std::string | planner_id_ |
double | planning_time_ |
std::string | pose_reference_frame_ |
std::map< std::string, std::vector < geometry_msgs::PoseStamped > > | pose_targets_ |
ros::ServiceClient | query_service_ |
double | replan_delay_ |
robot_model::RobotModelConstPtr | robot_model_ |
std::string | support_surface_ |
boost::shared_ptr < tf::Transformer > | tf_ |
ros::Publisher | trajectory_event_publisher_ |
moveit_msgs::WorkspaceParameters | workspace_parameters_ |
Definition at line 80 of file move_group.cpp.
moveit::planning_interface::MoveGroup::MoveGroupImpl::MoveGroupImpl | ( | const Options & | opt, |
const boost::shared_ptr< tf::Transformer > & | tf, | ||
const ros::Duration & | wait_for_server | ||
) | [inline] |
Definition at line 84 of file move_group.cpp.
Definition at line 181 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::allowLooking | ( | bool | flag | ) | [inline] |
Definition at line 613 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::allowReplanning | ( | bool | flag | ) | [inline] |
Definition at line 619 of file move_group.cpp.
Definition at line 743 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::clearPoseTarget | ( | const std::string & | end_effector_link | ) | [inline] |
Definition at line 240 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::clearPoseTargets | ( | ) | [inline] |
Definition at line 245 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::MoveGroupImpl::computeCartesianPath | ( | const std::vector< geometry_msgs::Pose > & | waypoints, |
double | step, | ||
double | jump_threshold, | ||
moveit_msgs::RobotTrajectory & | msg, | ||
bool | avoid_collisions | ||
) | [inline] |
Definition at line 532 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::constructGoal | ( | moveit_msgs::MoveGroupGoal & | goal_out | ) | [inline] |
Definition at line 636 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::constructGoal | ( | moveit_msgs::PickupGoal & | goal_out, |
const std::string & | object | ||
) | [inline] |
Definition at line 690 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::constructGoal | ( | moveit_msgs::PlaceGoal & | goal_out, |
const std::string & | object | ||
) | [inline] |
Definition at line 706 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::execute | ( | const Plan & | plan, |
bool | wait | ||
) | [inline] |
Definition at line 520 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::getCurrentState | ( | robot_state::RobotStatePtr & | current_state | ) | [inline] |
Definition at line 349 of file move_group.cpp.
const std::string& moveit::planning_interface::MoveGroup::MoveGroupImpl::getEndEffector | ( | ) | const [inline] |
Definition at line 255 of file move_group.cpp.
const std::string& moveit::planning_interface::MoveGroup::MoveGroupImpl::getEndEffectorLink | ( | ) | const [inline] |
Definition at line 250 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::MoveGroupImpl::getGoalJointTolerance | ( | ) | const [inline] |
Definition at line 582 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::MoveGroupImpl::getGoalOrientationTolerance | ( | ) | const [inline] |
Definition at line 577 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::MoveGroupImpl::getGoalPositionTolerance | ( | ) | const [inline] |
Definition at line 572 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::getInterfaceDescription | ( | moveit_msgs::PlannerInterfaceDescription & | desc | ) | [inline] |
Definition at line 202 of file move_group.cpp.
robot_state::JointStateGroup* moveit::planning_interface::MoveGroup::MoveGroupImpl::getJointStateTarget | ( | ) | [inline] |
Definition at line 220 of file move_group.cpp.
std::vector<std::string> moveit::planning_interface::MoveGroup::MoveGroupImpl::getKnownConstraints | ( | ) | const [inline] |
Definition at line 748 of file move_group.cpp.
const Options& moveit::planning_interface::MoveGroup::MoveGroupImpl::getOptions | ( | ) | const [inline] |
Definition at line 192 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::MoveGroupImpl::getPlanningTime | ( | ) | const [inline] |
Definition at line 608 of file move_group.cpp.
const std::string& moveit::planning_interface::MoveGroup::MoveGroupImpl::getPoseReferenceFrame | ( | ) | const [inline] |
Definition at line 334 of file move_group.cpp.
const geometry_msgs::PoseStamped& moveit::planning_interface::MoveGroup::MoveGroupImpl::getPoseTarget | ( | const std::string & | end_effector_link | ) | const [inline] |
Definition at line 293 of file move_group.cpp.
const std::vector<geometry_msgs::PoseStamped>& moveit::planning_interface::MoveGroup::MoveGroupImpl::getPoseTargets | ( | const std::string & | end_effector_link | ) | const [inline] |
Definition at line 309 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::MoveGroupImpl::getReplanningDelay | ( | ) | const [inline] |
Definition at line 631 of file move_group.cpp.
const robot_model::RobotModelConstPtr& moveit::planning_interface::MoveGroup::MoveGroupImpl::getRobotModel | ( | ) | const [inline] |
Definition at line 197 of file move_group.cpp.
ActiveTargetType moveit::planning_interface::MoveGroup::MoveGroupImpl::getTargetType | ( | ) | const [inline] |
Definition at line 344 of file move_group.cpp.
const boost::shared_ptr<tf::Transformer>& moveit::planning_interface::MoveGroup::MoveGroupImpl::getTF | ( | ) | const [inline] |
Definition at line 187 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::hasPoseTarget | ( | const std::string & | end_effector_link | ) | const [inline] |
Definition at line 287 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::initializeConstraintsStorage | ( | const std::string & | host, |
unsigned int | port | ||
) | [inline] |
Definition at line 763 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::initializeConstraintsStorageThread | ( | const std::string & | host, |
unsigned int | port | ||
) | [inline, private] |
Definition at line 785 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::move | ( | bool | wait | ) | [inline] |
Definition at line 488 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::pick | ( | const std::string & | object, |
const std::vector< manipulation_msgs::Grasp > & | grasps | ||
) | [inline] |
Definition at line 426 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::place | ( | const std::string & | object, |
const std::vector< geometry_msgs::PoseStamped > & | poses | ||
) | [inline] |
Place an object at one of the specified possible locations.
Definition at line 369 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::place | ( | const std::string & | object, |
const std::vector< manipulation_msgs::PlaceLocation > & | locations | ||
) | [inline] |
Definition at line 393 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::plan | ( | Plan & | plan | ) | [inline] |
Definition at line 458 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setEndEffectorLink | ( | const std::string & | end_effector | ) | [inline] |
Definition at line 235 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setGoalJointTolerance | ( | double | tolerance | ) | [inline] |
Definition at line 587 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setGoalOrientationTolerance | ( | double | tolerance | ) | [inline] |
Definition at line 597 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setGoalPositionTolerance | ( | double | tolerance | ) | [inline] |
Definition at line 592 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setPathConstraints | ( | const moveit_msgs::Constraints & | constraint | ) | [inline] |
Definition at line 721 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::setPathConstraints | ( | const std::string & | constraint | ) | [inline] |
Definition at line 726 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setPlannerId | ( | const std::string & | planner_id | ) | [inline] |
Definition at line 215 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setPlanningTime | ( | double | seconds | ) | [inline] |
Definition at line 602 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setPoseReferenceFrame | ( | const std::string & | pose_reference_frame | ) | [inline] |
Definition at line 324 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::MoveGroupImpl::setPoseTargets | ( | const std::vector< geometry_msgs::PoseStamped > & | poses, |
const std::string & | end_effector_link | ||
) | [inline] |
Definition at line 268 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setReplanningDelay | ( | double | delay | ) | [inline] |
Definition at line 625 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setStartState | ( | const robot_state::RobotState & | start_state | ) | [inline] |
Definition at line 225 of file move_group.cpp.
Definition at line 230 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setSupportSurfaceName | ( | const std::string & | support_surface | ) | [inline] |
Definition at line 329 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setTargetType | ( | ActiveTargetType | type | ) | [inline] |
Definition at line 339 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::setWorkspace | ( | double | minx, |
double | miny, | ||
double | minz, | ||
double | maxx, | ||
double | maxy, | ||
double | maxz | ||
) | [inline] |
Definition at line 771 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::stop | ( | void | ) | [inline] |
Definition at line 562 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::MoveGroupImpl::waitForAction | ( | const T & | action, |
const ros::Duration & | wait_for_server, | ||
const std::string & | name | ||
) | [inline] |
Definition at line 144 of file move_group.cpp.
ActiveTargetType moveit::planning_interface::MoveGroup::MoveGroupImpl::active_target_ [private] |
Definition at line 828 of file move_group.cpp.
Definition at line 816 of file move_group.cpp.
Definition at line 817 of file move_group.cpp.
ros::ServiceClient moveit::planning_interface::MoveGroup::MoveGroupImpl::cartesian_path_service_ [private] |
Definition at line 838 of file move_group.cpp.
robot_state::RobotStatePtr moveit::planning_interface::MoveGroup::MoveGroupImpl::considered_start_state_ [private] |
Definition at line 809 of file move_group.cpp.
boost::scoped_ptr<boost::thread> moveit::planning_interface::MoveGroup::MoveGroupImpl::constraints_init_thread_ [private] |
Definition at line 840 of file move_group.cpp.
boost::scoped_ptr<moveit_warehouse::ConstraintsStorage> moveit::planning_interface::MoveGroup::MoveGroupImpl::constraints_storage_ [private] |
Definition at line 839 of file move_group.cpp.
planning_scene_monitor::CurrentStateMonitorPtr moveit::planning_interface::MoveGroup::MoveGroupImpl::current_state_monitor_ [private] |
Definition at line 803 of file move_group.cpp.
std::string moveit::planning_interface::MoveGroup::MoveGroupImpl::end_effector_link_ [private] |
Definition at line 830 of file move_group.cpp.
Definition at line 836 of file move_group.cpp.
Definition at line 813 of file move_group.cpp.
Definition at line 815 of file move_group.cpp.
Definition at line 814 of file move_group.cpp.
Definition at line 841 of file move_group.cpp.
robot_state::RobotStatePtr moveit::planning_interface::MoveGroup::MoveGroupImpl::joint_state_target_ [private] |
Definition at line 821 of file move_group.cpp.
boost::scoped_ptr<actionlib::SimpleActionClient<moveit_msgs::MoveGroupAction> > moveit::planning_interface::MoveGroup::MoveGroupImpl::move_action_client_ [private] |
Definition at line 804 of file move_group.cpp.
Definition at line 800 of file move_group.cpp.
Definition at line 799 of file move_group.cpp.
boost::scoped_ptr<moveit_msgs::Constraints> moveit::planning_interface::MoveGroup::MoveGroupImpl::path_constraints_ [private] |
Definition at line 829 of file move_group.cpp.
boost::scoped_ptr<actionlib::SimpleActionClient<moveit_msgs::PickupAction> > moveit::planning_interface::MoveGroup::MoveGroupImpl::pick_action_client_ [private] |
Definition at line 805 of file move_group.cpp.
boost::scoped_ptr<actionlib::SimpleActionClient<moveit_msgs::PlaceAction> > moveit::planning_interface::MoveGroup::MoveGroupImpl::place_action_client_ [private] |
Definition at line 806 of file move_group.cpp.
std::string moveit::planning_interface::MoveGroup::MoveGroupImpl::planner_id_ [private] |
Definition at line 812 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::MoveGroupImpl::planning_time_ [private] |
Definition at line 811 of file move_group.cpp.
std::string moveit::planning_interface::MoveGroup::MoveGroupImpl::pose_reference_frame_ [private] |
Definition at line 831 of file move_group.cpp.
std::map<std::string, std::vector<geometry_msgs::PoseStamped> > moveit::planning_interface::MoveGroup::MoveGroupImpl::pose_targets_ [private] |
Definition at line 825 of file move_group.cpp.
Definition at line 837 of file move_group.cpp.
double moveit::planning_interface::MoveGroup::MoveGroupImpl::replan_delay_ [private] |
Definition at line 818 of file move_group.cpp.
robot_model::RobotModelConstPtr moveit::planning_interface::MoveGroup::MoveGroupImpl::robot_model_ [private] |
Definition at line 802 of file move_group.cpp.
std::string moveit::planning_interface::MoveGroup::MoveGroupImpl::support_surface_ [private] |
Definition at line 832 of file move_group.cpp.
boost::shared_ptr<tf::Transformer> moveit::planning_interface::MoveGroup::MoveGroupImpl::tf_ [private] |
Definition at line 801 of file move_group.cpp.
ros::Publisher moveit::planning_interface::MoveGroup::MoveGroupImpl::trajectory_event_publisher_ [private] |
Definition at line 835 of file move_group.cpp.
moveit_msgs::WorkspaceParameters moveit::planning_interface::MoveGroup::MoveGroupImpl::workspace_parameters_ [private] |
Definition at line 810 of file move_group.cpp.