, including all inherited members.
attached_object_pub_ | object_manipulator::MechanismInterface | [private] |
attachObjectToGripper(std::string arm_name, std::string object_collision_name) | object_manipulator::MechanismInterface | |
attemptMoveArmToGoal(std::string arm_name, const std::vector< double > &desired_joint_values, const motion_planning_msgs::OrderedCollisionOperations &collision_operations, const std::vector< motion_planning_msgs::LinkPadding > &link_padding) | object_manipulator::MechanismInterface | |
attemptTrajectory(std::string arm_name, const trajectory_msgs::JointTrajectory &trajectory, bool unnormalize) | object_manipulator::MechanismInterface | |
attemptTrajectory(std::string arm_name, const std::vector< std::vector< double > > &positions, bool unnormalize, float time_per_segment) | object_manipulator::MechanismInterface | |
callSwitchControllers(std::vector< std::string > start_controllers, std::vector< std::string > stop_controllers) | object_manipulator::MechanismInterface | [private] |
check_state_validity_client_ | object_manipulator::MechanismInterface | |
checkController(std::string controller) | object_manipulator::MechanismInterface | |
checkStateValidity(std::string arm_name, const std::vector< double > &joint_values, const motion_planning_msgs::OrderedCollisionOperations &collision_operations, const std::vector< motion_planning_msgs::LinkPadding > &link_padding) | object_manipulator::MechanismInterface | |
checkStateValidity(std::string arm_name, const std::vector< double > &joint_values) | object_manipulator::MechanismInterface | [inline] |
clipDesiredPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, double clip_dist, double clip_angle) | object_manipulator::MechanismInterface | |
convertGraspableObjectComponentsToFrame(object_manipulation_msgs::GraspableObject &object, std::string frame_id) | object_manipulator::MechanismInterface | |
detachAndAddBackObjectsAttachedToGripper(std::string arm_name, std::string object_collision_name) | object_manipulator::MechanismInterface | |
fingertipPadding(std::string arm_name, double pad) | object_manipulator::MechanismInterface | [static] |
fk_service_client_ | object_manipulator::MechanismInterface | |
getFK(std::string arm_name, std::vector< double > positions, geometry_msgs::PoseStamped &pose_stamped) | object_manipulator::MechanismInterface | |
getGripperPose(std::string arm_name, std::string frame_id) | object_manipulator::MechanismInterface | |
getIKForPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, kinematics_msgs::GetConstraintAwarePositionIK::Response &ik_response, const motion_planning_msgs::OrderedCollisionOperations &collision_operations, const std::vector< motion_planning_msgs::LinkPadding > &link_padding) | object_manipulator::MechanismInterface | |
getInterpolatedIK(std::string arm_name, geometry_msgs::PoseStamped start_pose, geometry_msgs::Vector3Stamped direction, float desired_trajectory_length, const std::vector< double > &seed_joint_position, const sensor_msgs::JointState &joint_state, const motion_planning_msgs::OrderedCollisionOperations &collision_operations, const std::vector< motion_planning_msgs::LinkPadding > &link_padding, bool reverse_trajectory, trajectory_msgs::JointTrajectory &trajectory, float &actual_trajectory_length) | object_manipulator::MechanismInterface | |
getJointNames(std::string arm_name) | object_manipulator::MechanismInterface | [private] |
getObjectPoseForGrasp(std::string arm_name, const geometry_msgs::Pose &grasp_pose) | object_manipulator::MechanismInterface | |
grasp_status_client_ | object_manipulator::MechanismInterface | |
graspPostureQuery(std::string arm_name) | object_manipulator::MechanismInterface | |
gripperPadding(std::string arm_name, double pad) | object_manipulator::MechanismInterface | [static] |
hand_posture_client_ | object_manipulator::MechanismInterface | |
handPostureGraspAction(std::string arm_name, const object_manipulation_msgs::Grasp &grasp, int goal) | object_manipulator::MechanismInterface | |
ik_query_client_ | object_manipulator::MechanismInterface | |
ik_service_client_ | object_manipulator::MechanismInterface | |
interpolated_ik_service_client_ | object_manipulator::MechanismInterface | |
interpolated_ik_set_params_client_ | object_manipulator::MechanismInterface | |
joint_trajectory_normalizer_service_ | object_manipulator::MechanismInterface | |
left_cartesian_controller_ | object_manipulator::MechanismInterface | [private] |
left_cartesian_pub_ | object_manipulator::MechanismInterface | |
left_joint_controller_ | object_manipulator::MechanismInterface | [private] |
list_controllers_service_ | object_manipulator::MechanismInterface | |
listener_ | object_manipulator::MechanismInterface | [private] |
MechanismInterface() | object_manipulator::MechanismInterface | |
modifyMoveArmGoal(move_arm_msgs::MoveArmGoal &move_arm_goal, motion_planning_msgs::ArmNavigationErrorCodes &error_code, std::vector< planning_environment_msgs::ContactInformation > &contact_info_) | object_manipulator::MechanismInterface | |
move_arm_action_client_ | object_manipulator::MechanismInterface | |
moveArmConstrained(std::string arm_name, const geometry_msgs::PoseStamped &commanded_pose, const motion_planning_msgs::OrderedCollisionOperations &collision_operations, const std::vector< motion_planning_msgs::LinkPadding > &link_padding, const motion_planning_msgs::Constraints &path_constraints, const double &redundancy=0.0, const bool &compute_viable_pose=true) | object_manipulator::MechanismInterface | |
moveArmToPose(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, const motion_planning_msgs::OrderedCollisionOperations &collision_operations, const std::vector< motion_planning_msgs::LinkPadding > &link_padding) | object_manipulator::MechanismInterface | |
moveArmToPoseCartesian(std::string arm_name, const geometry_msgs::PoseStamped &desired_pose, ros::Duration timeout, double dist_tol, double angle_tol, double clip_dist, double clip_angle, double timestep) | object_manipulator::MechanismInterface | |
negate(const geometry_msgs::Vector3 &vec) | object_manipulator::MechanismInterface | [inline] |
normalize(const geometry_msgs::Vector3 &vec) | object_manipulator::MechanismInterface | [inline] |
point_head_action_client_ | object_manipulator::MechanismInterface | |
pointHeadAction(const geometry_msgs::PointStamped &target, std::string pointing_frame="/narrow_stereo_optical_frame") | object_manipulator::MechanismInterface | |
poseDists(geometry_msgs::Pose start, geometry_msgs::Pose end, double &pos_dist, double &angle) | object_manipulator::MechanismInterface | |
positionAndAngleDist(Eigen::eigen2_Transform3d start, Eigen::eigen2_Transform3d end, double &pos_dist, double &angle, Eigen::Vector3d &axis, Eigen::Vector3d &direction) | object_manipulator::MechanismInterface | |
priv_nh_ | object_manipulator::MechanismInterface | [private] |
reactive_grasp_action_client_ | object_manipulator::MechanismInterface | |
reactive_lift_action_client_ | object_manipulator::MechanismInterface | |
reactive_place_action_client_ | object_manipulator::MechanismInterface | |
right_cartesian_controller_ | object_manipulator::MechanismInterface | [private] |
right_cartesian_pub_ | object_manipulator::MechanismInterface | |
right_joint_controller_ | object_manipulator::MechanismInterface | [private] |
root_nh_ | object_manipulator::MechanismInterface | [private] |
sendCartesianPoseCommand(std::string arm_name, geometry_msgs::PoseStamped desired_pose, double clip_dist, double clip_angle) | object_manipulator::MechanismInterface | |
setInterpolatedIKParams(std::string arm_name, int num_steps, int collision_check_resolution, bool start_from_end) | object_manipulator::MechanismInterface | [private] |
startController(std::string controller) | object_manipulator::MechanismInterface | |
stopController(std::string controller) | object_manipulator::MechanismInterface | |
switch_controller_service_ | object_manipulator::MechanismInterface | |
switchControllers(std::string start_controller, std::string stop_controller) | object_manipulator::MechanismInterface | |
switchToCartesian() | object_manipulator::MechanismInterface | |
switchToJoint() | object_manipulator::MechanismInterface | |
traj_action_client_ | object_manipulator::MechanismInterface | |
transformPointCloud(std::string target_frame, const sensor_msgs::PointCloud &cloud_in, sensor_msgs::PointCloud &cloud_out) | object_manipulator::MechanismInterface | |
transformPose(const std::string target_frame, const geometry_msgs::PoseStamped &stamped_in) | object_manipulator::MechanismInterface | |
translateGripper(std::string arm_name, const geometry_msgs::Vector3Stamped &direction, motion_planning_msgs::OrderedCollisionOperations ord, const std::vector< motion_planning_msgs::LinkPadding > &link_padding, float requested_distance, float min_distance, float &actual_distance) | object_manipulator::MechanismInterface | |
translateGripperCartesian(std::string arm_name, const geometry_msgs::Vector3Stamped &direction, ros::Duration timeout, double dist_tol, double angle_tol, double clip_dist, double clip_angle, double timestep) | object_manipulator::MechanismInterface | |
translateGripperPose(geometry_msgs::Vector3Stamped translation, geometry_msgs::PoseStamped start_pose, std::string arm_id) | object_manipulator::MechanismInterface | |
vectorLen(const geometry_msgs::Vector3 &vec) | object_manipulator::MechanismInterface | [inline] |