Allows one to move the arm through a set of joint angles safely and controller agnostic. More...
Public Member Functions | |
def | __init__ |
def | can_exec_traj |
Determines whether or not the arm can execute the trajectory by checking the first joint configuration and seeing whether or not it is within joint tolerances. | |
def | execute |
Plays back the specified trajectory. | |
def | get_angle_traj |
def | is_moving |
def | load_arm |
Switches controllers and returns an instance of the arm to control. | |
def | move_to_angles |
Executes a linearly interpolated trajectory from the current joint angles to the q_goal angles. | |
def | pause_moving |
Pauses the movement of the trajectory but doesn't reset its position in the array. | |
def | preempt |
def | restart_moving |
Restarts the currently running movement after being paused. | |
def | stop_moving |
Stops the movement of the trajectory and resets the trajectory so it cannot restart. | |
Public Attributes | |
arm_char | |
ctrl_name | |
ctrl_switcher | |
cur_arm | |
cur_idx | |
cur_joint_traj | |
exec_traj_timer | |
is_paused | |
last_rate | |
param_file | |
running | |
stop_traj |
Allows one to move the arm through a set of joint angles safely and controller agnostic.
Definition at line 32 of file traj_playback.py.
def hrl_pr2_traj_playback.traj_playback.TrajPlayback.__init__ | ( | self, | |
arm_char, | |||
ctrl_name = "%s_arm_controller" , |
|||
param_file = None |
|||
) |
arm_char | 'r' or 'l' to choose which arm to load |
ctrl_name | name of the controller to load from the param_file |
param_file | Location of the parameter file which specifies the controller (e.g. "$(find hrl_pr2_arms)/params/joint_traj_params_electric_low.yaml") |
Definition at line 38 of file traj_playback.py.
def hrl_pr2_traj_playback.traj_playback.TrajPlayback.can_exec_traj | ( | self, | |
joint_trajectory | |||
) |
Determines whether or not the arm can execute the trajectory by checking the first joint configuration and seeing whether or not it is within joint tolerances.
joint_trajectory | List of lists of length 7 representing joint angles to move through. |
Definition at line 136 of file traj_playback.py.
def hrl_pr2_traj_playback.traj_playback.TrajPlayback.execute | ( | self, | |
joint_trajectory, | |||
rate, | |||
blocking = True |
|||
) |
Plays back the specified trajectory.
The arm must currently be at the first joint configuration specified in the joint trajectory within a certain degree of tolerance.
joint_trajectory | List of lists of length 7 representing joint angles to move through. |
rate | Frequency with which to iterate through the list. |
blocking | If True, the function will wait until done, if False, it will return immediately |
Definition at line 64 of file traj_playback.py.
def hrl_pr2_traj_playback.traj_playback.TrajPlayback.get_angle_traj | ( | self, | |
q_goal, | |||
rate = RATE , |
|||
velocity = 0.1 |
|||
) |
Definition at line 119 of file traj_playback.py.
Definition at line 144 of file traj_playback.py.
Switches controllers and returns an instance of the arm to control.
Definition at line 50 of file traj_playback.py.
def hrl_pr2_traj_playback.traj_playback.TrajPlayback.move_to_angles | ( | self, | |
q_goal, | |||
rate = RATE , |
|||
velocity = 0.1 , |
|||
blocking = True |
|||
) |
Executes a linearly interpolated trajectory from the current joint angles to the q_goal angles.
q_goal | List of length 7 representing the desired end configuration. |
rate | Rate with which to execute trajectory. |
velocity | Speed (~rad/s) to move based on a heursitic which weighs relative joint speeds. The elbow will not move quicker than the velocity in rad/s. |
blocking | If True, the function will wait until done, if False, it will return immediately |
Definition at line 113 of file traj_playback.py.
Pauses the movement of the trajectory but doesn't reset its position in the array.
Definition at line 149 of file traj_playback.py.
Definition at line 175 of file traj_playback.py.
def hrl_pr2_traj_playback.traj_playback.TrajPlayback.restart_moving | ( | self, | |
blocking = True |
|||
) |
Restarts the currently running movement after being paused.
Definition at line 160 of file traj_playback.py.
Stops the movement of the trajectory and resets the trajectory so it cannot restart.
Definition at line 168 of file traj_playback.py.
Definition at line 38 of file traj_playback.py.
Definition at line 38 of file traj_playback.py.
Definition at line 38 of file traj_playback.py.
Definition at line 64 of file traj_playback.py.
Definition at line 64 of file traj_playback.py.
Definition at line 38 of file traj_playback.py.
Definition at line 64 of file traj_playback.py.
Definition at line 38 of file traj_playback.py.
Definition at line 64 of file traj_playback.py.
Definition at line 38 of file traj_playback.py.
Definition at line 38 of file traj_playback.py.
Definition at line 64 of file traj_playback.py.