Public Member Functions | |
def | __init__ |
def | close_gripper |
def | get_ee_state |
def | get_gripper_state |
def | get_ik_for_ee |
def | get_joint_state |
def | get_movement |
def | get_time_to_pose |
def | is_executing |
def | move_to_joints |
def | move_to_joints_plan |
def | move_to_pose |
def | open_gripper |
def | relax_arm |
def | reset_movement_history |
def | un_relax_arm |
def | update |
Private Member Functions | |
def | _joint_states_cb |
def | _record_arm_movement |
def | _send_gripper_command |
def | _solve_ik |
def | _update_gripper_state |
Static Private Member Functions | |
def | _get_distance_bw_poses |
def | _get_time_bw_poses |
Private Attributes | |
_arm_movement | |
_controller_client | |
_ee_name | |
_gravity_comp_controllers | |
_gripper_client | |
_gripper_state | |
_is_executing | |
_joint_names | |
_l_gripper_joint_name | |
_last_ee_pose | |
_last_unstable_time | |
_lock | |
_move_group | |
_movement_buffer_size | |
_non_gravity_comp_controllers | |
_planning_scene | |
_r_gripper_joint_name | |
_received_joint_names | |
_received_joint_poses | |
_tf_listener | |
_traj_action_client |
Interface for controlling mid-level operations of the arm. Interfaces with MoveIt and joint trajectory controllers to move the arm to locations using different planning strategies.
def fetch_arm_control.arm.Arm.__init__ | ( | self, | |
tf_listener | |||
) |
def fetch_arm_control.arm.Arm._get_distance_bw_poses | ( | pose0, | |
pose1 | |||
) | [static, private] |
def fetch_arm_control.arm.Arm._get_time_bw_poses | ( | pose0, | |
pose1, | |||
velocity = 0.2 |
|||
) | [static, private] |
Determines how much time should be allowed for moving between pose0 and pose1 at velocity. Args: pose0 (PoseStamped) pose1 (PoseStamped) velocity (float, optional): Defaults to 0.2. Returns: float: How long (in seconds) to allow for moving between pose0 and pose1 and velocity.
def fetch_arm_control.arm.Arm._joint_states_cb | ( | self, | |
msg | |||
) | [private] |
def fetch_arm_control.arm.Arm._record_arm_movement | ( | self, | |
movement | |||
) | [private] |
def fetch_arm_control.arm.Arm._send_gripper_command | ( | self, | |
pos = 0.115 , |
|||
eff = 30.0 , |
|||
wait = True |
|||
) | [private] |
def fetch_arm_control.arm.Arm._solve_ik | ( | self, | |
ee_pose | |||
) | [private] |
def fetch_arm_control.arm.Arm._update_gripper_state | ( | self | ) | [private] |
def fetch_arm_control.arm.Arm.close_gripper | ( | self, | |
pos = 0.0 , |
|||
eff = 100.0 , |
|||
wait = True |
|||
) |
def fetch_arm_control.arm.Arm.get_ee_state | ( | self, | |
ref_frame = 'base_link' |
|||
) |
def fetch_arm_control.arm.Arm.get_gripper_state | ( | self | ) |
def fetch_arm_control.arm.Arm.get_ik_for_ee | ( | self, | |
ee_pose, | |||
seed = None |
|||
) |
def fetch_arm_control.arm.Arm.get_joint_state | ( | self, | |
joint_names = None |
|||
) |
def fetch_arm_control.arm.Arm.get_movement | ( | self | ) |
def fetch_arm_control.arm.Arm.get_time_to_pose | ( | self, | |
target_pose | |||
) |
Returns the time to get to the arm pose held in target_pose. Args: target_pose (PoseStamped|None): A Pose holding the pose to move to, or None if the arm should not move. Returns: float|None: How long (in seconds) to allow for moving arm to the pose in target_pose, or None if the arm will not move.
def fetch_arm_control.arm.Arm.is_executing | ( | self | ) |
def fetch_arm_control.arm.Arm.move_to_joints | ( | self, | |
joints, | |||
times_to_joints, | |||
velocities = None |
|||
) |
def fetch_arm_control.arm.Arm.move_to_joints_plan | ( | self, | |
joints, | |||
velocities = None |
|||
) |
def fetch_arm_control.arm.Arm.move_to_pose | ( | self, | |
ee_pose | |||
) |
def fetch_arm_control.arm.Arm.open_gripper | ( | self, | |
pos = 0.15 , |
|||
eff = 100.0 , |
|||
wait = True |
|||
) |
def fetch_arm_control.arm.Arm.relax_arm | ( | self | ) |
def fetch_arm_control.arm.Arm.reset_movement_history | ( | self | ) |
def fetch_arm_control.arm.Arm.un_relax_arm | ( | self | ) |
def fetch_arm_control.arm.Arm.update | ( | self | ) |
fetch_arm_control::arm.Arm::_ee_name [private] |
fetch_arm_control::arm.Arm::_joint_names [private] |
fetch_arm_control::arm.Arm::_lock [private] |
fetch_arm_control::arm.Arm::_move_group [private] |
fetch_arm_control::arm.Arm::_tf_listener [private] |