Public Member Functions | Public Attributes
pr2_gripper_reactive_approach.controller_manager.ControllerManager Class Reference

class to start/stop/switch between joint and Cartesian controllers More...

List of all members.

Public Member Functions

def __init__
def cartesian_command_thread_func
 thread function for sending clipped Cartesian commands
def check_cartesian_done
 check if the Cartesian controller thinks it's gotten to its goal (it's pretty loose about goals)
def check_cartesian_near_pose
 check if we're near to a desired Cartesian pose (either PoseStamped or 7-list of position and quaternion in 'base_link' frame) by pos_thres(m) and rot_thres (rad)
def check_cartesian_really_done
 check if both the Cartesian controllers think we're done and if we're close to where we want to be
def check_controller_states
 figure out which controllers are loaded/started (fills in self.joint_controller_state, self.cartesian_controllers_state, and self.gripper_controller_state with 'not loaded', 'stopped', or 'running'
def check_controllers_ok
 make sure the appropriate controllers (joint or Cartesian) are running/stopped mode is 'joint' or 'cartesian'
def check_joint_trajectory_done
 check the state of the joint trajectory action (returns 1 if done, 0 otherwise)
def clip_pose
 clip pose to be no more than max_pos_dist or max_rot_dist away from the current gripper pose
def command_cartesian
 send a single desired pose to the Cartesian controller (pose is either a PoseStamped or a 7-list of position and quaternion orientation; if the latter, put the frame in frame_id)
def command_gripper
 send a command to the gripper action
def command_interpolated_ik
 find and execute a joint-angle trajectory to perform a collision-free Cartesian movement if start_pose is None, starts from the current pose (if not None, will go straight to the start pose using the joint trajectory action)
def command_joint
 send a single joint configuration to the joint trajectory action (takes in a 7-list of angles, nonblocking)
def command_joint_trajectory
 send an entire joint trajectory to the joint trajectory action
def create_move_arm_goal
 create a basic goal message for move_arm
def dist_from_current_pos_and_rot
 return the distance and angle from the current Cartesian pose to a goal pose
def find_gripper_contact
 tell the gripper to close until contact (on one or both finger pads) contacts_desired is "both", "left", "right", or "either"
def freeze_arm
 tell the joint trajectory action to stop the arm where it is now
def get_current_arm_angles
 use the joint_states_listener to get the arm angles
def get_current_gripper_opening
 use the joint_states_listener to get the current gripper opening
def get_current_wrist_pose_stamped
 return the current pose of the wrist as a PoseStamped
def get_find_gripper_contact_result
 get the final result from find_gripper_contact
def get_find_gripper_contact_state
 get the state from find_gripper_contact
def get_gripper_event_detector_state
 get the state from the gripper event detector
def load_cartesian_controllers
 load the Cartesian controllers with the current set of params on the param server
def load_joint_controllers
 load the joint controller with the current set of params on the param server
def modify_move_arm_goal
 if move_arm_joint returns an error code of START_STATE_IN_COLLISION, we can try to add allowed contact regions to get it out of the start collisions (appears to already be done in C++)
def move_arm_constrained
 move the wrist to the desired location while keeping the current wrist orientation upright start angles are the joint angle start point for IK searches default start angles and location are for moving the arm to the side returns 0 if timed out or no IK solution; otherwise an ArmNavigationErrorCodes (int32, 1=success) from move_arm
def move_arm_joint
 use move_arm to get to a desired joint configuration in a collision-free way returns 0 if timed out; otherwise an ArmNavigationErrorCodes (int32, 1=success) from move_arm
def move_arm_pose
 use move_arm to get to a desired pose in a collision-free way (really, run IK and then call move arm to move to the IK joint angles) returns 0 if timed out or no IK solution; otherwise an ArmNavigationErrorCodes (int32, 1=success) from move_arm
def move_cartesian
 move in Cartesian space using the Cartesian controllers !!! if using non-blocking mode, and not separately using wait_cartesian_really_done or check_cartesian_really_done, you must call stop_cartesian_commands yourself when the move is finished or it will keep sending Cartesian commands !!! if collision_aware, checks whether the path could be collision-free, but uses the Cartesian controllers to execute it if blocking, waits for completion, otherwise returns after sending the goal step_size only used if collision aware (size of steps to check for collisions) pos_thres and rot_thres are thresholds within which the goal is declared reached times out and quits after timeout, and waits settling_time after the controllers declare that they're done (which for the trajectory controller, is usually way too early) if using the non-trajectory controller, overshoot_dist is how far to overshoot the goal to make sure we get there (it will stop when we actually get there) and overshoot_angle is how far to overshoot the goal angle
def move_cartesian_ik
 move in Cartesian space using IK Cartesian interpolation if collision_aware, quits if the path is not collision-free if blocking, waits for completion, otherwise returns after sending the goal step_size is the step size for interpolation pos_thres and rot_thres are thresholds within which the goal is declared reached times out and quits after timeout, and waits settling_time after the controllers declare that they're done
def normalize_angle
 normalize an angle for a continuous joint so that it's the closest version of the angle to the current angle (not +-2*pi)
def normalize_trajectory
 normalize a trajectory (list of lists of joint angles), so that the desired angles are the nearest ones for the continuous joints (5 and 7)
def overshoot_pose
 overshoot pose by overshoot_dist and overshoot_angle, unless we're already within dist_tol/angle_tol
def pplist
 pretty-print list to string
def ppmat
 pretty-print numpy matrix to string
def print_cartesian_pose
 print the current Cartesian pose of the gripper
def reload_cartesian_controllers
 re-load the Cartesian controllers with new parameters (change cart_params before running)
def reload_joint_controllers
 re-load the joint controller with gains a fraction of the defaults
def reset_collision_map
 reset the collision map (and optionally all attached/collision objects)
def return_cartesian_pose
 return the current Cartesian pose of the gripper
def send_move_arm_goal
 send a goal to move arm and wait for the result, modifying the goal if the start state is in collision returns 0 if timed out; otherwise an ArmNavigationErrorCodes value (int32, 1=success) from move_arm
def set_desired_cartesian_to_current
 set the current desired Cartesian pose to the current gripper pose
def set_planning_scene
 set the planning scene (for IK/move_arm calls)
def start_cartesian_commands
 start sending commands from the Cartesian command thread
def start_cartesian_controllers
 start the Cartesian controllers (need to be loaded already)
def start_gripper_controller
 start the gripper controller (needs to be loaded already)
def start_gripper_event_detector
 start up gripper event detector to detect when an object hits the table or when someone is trying to take an object from the robot
def start_gripper_grab
 opens and closes the gripper to determine how hard to grasp the object, then starts up slip servo mode
def start_joint_controllers
 just start the joint controllers (need to be loaded already)
def stop_all_controllers
 stop all controllers
def stop_cartesian_commands
 stop sending commands from the Cartesian command thread
def stop_controllers
 stop controllers that are currently running
def switch_to_cartesian_mode
 stops the joint controllers, starts the Cartesian ones (both need to be loaded already)
def switch_to_joint_mode
 stops the Cartesian controllers, starts the joint ones (both need to be loaded already)
def unload_cartesian_controllers
 unload the Cartesian controllers (to re-load with new params)
def unload_joint_controllers
 unload the joint controller
def wait_cartesian_really_done
 wait for either the Cartesian pose to get near enough to a goal pose or timeout (a ROS duration) is reached or settling_time (a ROS duration) after the Cartesian controllers report that they're done
def wait_for_action_server
 wait for an action server to be ready
def wait_for_service
 wait for a service to be ready
def wait_joint_trajectory_done
 wait for the joint trajectory action to finish (returns 1 if succeeded, 0 otherwise) timeout is a ROS duration; default (0) is infinite timeout returns 0 if timed out, 1 if succeeded

Public Attributes

 angle_tol
 cart_params
 cartesian_cmd_pub
 cartesian_cmd_service
 cartesian_command_lock
 cartesian_command_thread
 cartesian_command_thread_running
 cartesian_controllers
 cartesian_controllers_state
 cartesian_desired_pose
 cartesian_moving_service
 cartesian_preempt_service
 collision_map_interface
 dist_tol
 gripper_action_client
 gripper_controller
 gripper_controller_state
 gripper_event_detector_action_client
 gripper_find_contact_action_client
 gripper_grab_action_client
 ik_utilities
 joint_action_client
 joint_controller
 joint_controller_state
 joint_names
 joint_params
 joint_states_listener
 list_controllers_service
 load_controller_service
 move_arm_client
 overshoot_angle
 overshoot_dist
 switch_controller_service
 tf_listener
 timestep
 unload_controller_service
 use_task_cartesian
 use_trajectory_cartesian
 using_slip_controller
 using_slip_detection
 whicharm

Detailed Description

class to start/stop/switch between joint and Cartesian controllers

Definition at line 76 of file controller_manager.py.


Constructor & Destructor Documentation

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.__init__ (   self,
  whicharm,
  tf_listener = None,
  using_slip_controller = 0,
  using_slip_detection = 0 
)

Definition at line 79 of file controller_manager.py.


Member Function Documentation

thread function for sending clipped Cartesian commands

Definition at line 754 of file controller_manager.py.

check if the Cartesian controller thinks it's gotten to its goal (it's pretty loose about goals)

Definition at line 834 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.check_cartesian_near_pose (   self,
  goal_pose,
  pos_thres,
  rot_thres 
)

check if we're near to a desired Cartesian pose (either PoseStamped or 7-list of position and quaternion in 'base_link' frame) by pos_thres(m) and rot_thres (rad)

Definition at line 844 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.check_cartesian_really_done (   self,
  goal_pose,
  pos_thres,
  rot_thres,
  current_pos = None,
  current_rot = None 
)

check if both the Cartesian controllers think we're done and if we're close to where we want to be

Definition at line 877 of file controller_manager.py.

figure out which controllers are loaded/started (fills in self.joint_controller_state, self.cartesian_controllers_state, and self.gripper_controller_state with 'not loaded', 'stopped', or 'running'

Definition at line 1169 of file controller_manager.py.

make sure the appropriate controllers (joint or Cartesian) are running/stopped mode is 'joint' or 'cartesian'

Definition at line 1029 of file controller_manager.py.

check the state of the joint trajectory action (returns 1 if done, 0 otherwise)

Definition at line 1123 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.clip_pose (   self,
  pose,
  max_pos_dist = 0.02,
  max_rot_dist = math.pi/20.,
  current_pose = None 
)

clip pose to be no more than max_pos_dist or max_rot_dist away from the current gripper pose

Definition at line 692 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.command_cartesian (   self,
  pose,
  frame_id = '/base_link' 
)

send a single desired pose to the Cartesian controller (pose is either a PoseStamped or a 7-list of position and quaternion orientation; if the latter, put the frame in frame_id)

Definition at line 807 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.command_gripper (   self,
  position,
  max_effort,
  blocking = 0 
)

send a command to the gripper action

Definition at line 1148 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.command_interpolated_ik (   self,
  end_pose,
  start_pose = None,
  collision_aware = 1,
  step_size = .02,
  max_joint_vel = .05 
)

find and execute a joint-angle trajectory to perform a collision-free Cartesian movement if start_pose is None, starts from the current pose (if not None, will go straight to the start pose using the joint trajectory action)

Definition at line 630 of file controller_manager.py.

send a single joint configuration to the joint trajectory action (takes in a 7-list of angles, nonblocking)

Definition at line 1058 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.command_joint_trajectory (   self,
  trajectory,
  max_joint_vel = 0.2,
  current_angles = None,
  blocking = 0,
  times_and_vels = None 
)

send an entire joint trajectory to the joint trajectory action

Definition at line 1073 of file controller_manager.py.

create a basic goal message for move_arm

Definition at line 370 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.dist_from_current_pos_and_rot (   self,
  goal_pos,
  goal_rot,
  current_pos = None,
  current_rot = None 
)

return the distance and angle from the current Cartesian pose to a goal pose

Definition at line 858 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.find_gripper_contact (   self,
  contacts_desired,
  zero_fingertips = 0,
  blocking = 1,
  timeout = 12. 
)

tell the gripper to close until contact (on one or both finger pads) contacts_desired is "both", "left", "right", or "either"

Definition at line 274 of file controller_manager.py.

tell the joint trajectory action to stop the arm where it is now

Definition at line 1142 of file controller_manager.py.

use the joint_states_listener to get the arm angles

Definition at line 672 of file controller_manager.py.

use the joint_states_listener to get the current gripper opening

Definition at line 685 of file controller_manager.py.

return the current pose of the wrist as a PoseStamped

Definition at line 679 of file controller_manager.py.

get the final result from find_gripper_contact

Definition at line 306 of file controller_manager.py.

get the state from find_gripper_contact

Definition at line 301 of file controller_manager.py.

get the state from the gripper event detector

Definition at line 365 of file controller_manager.py.

load the Cartesian controllers with the current set of params on the param server

Definition at line 1191 of file controller_manager.py.

load the joint controller with the current set of params on the param server

Definition at line 1234 of file controller_manager.py.

if move_arm_joint returns an error code of START_STATE_IN_COLLISION, we can try to add allowed contact regions to get it out of the start collisions (appears to already be done in C++)

Definition at line 478 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.move_arm_constrained (   self,
  constraint_in = None,
  start_angles = None,
  location = None,
  blocking = 1,
  compute_feasible_goal = True,
  frame_id = 'torso_lift_link' 
)

move the wrist to the desired location while keeping the current wrist orientation upright start angles are the joint angle start point for IK searches default start angles and location are for moving the arm to the side returns 0 if timed out or no IK solution; otherwise an ArmNavigationErrorCodes (int32, 1=success) from move_arm

Definition at line 504 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.move_arm_joint (   self,
  joint_angles,
  blocking = 1 
)

use move_arm to get to a desired joint configuration in a collision-free way returns 0 if timed out; otherwise an ArmNavigationErrorCodes (int32, 1=success) from move_arm

Definition at line 453 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.move_arm_pose (   self,
  pose_stamped,
  start_angles = None,
  blocking = 1 
)

use move_arm to get to a desired pose in a collision-free way (really, run IK and then call move arm to move to the IK joint angles) returns 0 if timed out or no IK solution; otherwise an ArmNavigationErrorCodes (int32, 1=success) from move_arm

Definition at line 590 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.move_cartesian (   self,
  goal_pose,
  collision_aware = 0,
  blocking = 1,
  step_size = .005,
  pos_thres = .001,
  rot_thres = .05,
  timeout = rospy.Duration(30.),
  settling_time = rospy.Duration(1.),
  overshoot_dist = 0.005,
  overshoot_angle = 0.05,
  stuck_dist = .005,
  stuck_angle = .001 
)

move in Cartesian space using the Cartesian controllers !!! if using non-blocking mode, and not separately using wait_cartesian_really_done or check_cartesian_really_done, you must call stop_cartesian_commands yourself when the move is finished or it will keep sending Cartesian commands !!! if collision_aware, checks whether the path could be collision-free, but uses the Cartesian controllers to execute it if blocking, waits for completion, otherwise returns after sending the goal step_size only used if collision aware (size of steps to check for collisions) pos_thres and rot_thres are thresholds within which the goal is declared reached times out and quits after timeout, and waits settling_time after the controllers declare that they're done (which for the trajectory controller, is usually way too early) if using the non-trajectory controller, overshoot_dist is how far to overshoot the goal to make sure we get there (it will stop when we actually get there) and overshoot_angle is how far to overshoot the goal angle

Definition at line 965 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.move_cartesian_ik (   self,
  goal_pose,
  collision_aware = 0,
  blocking = 1,
  step_size = .005,
  pos_thres = .02,
  rot_thres = .1,
  timeout = rospy.Duration(30.),
  settling_time = rospy.Duration(0.25),
  vel = .15 
)

move in Cartesian space using IK Cartesian interpolation if collision_aware, quits if the path is not collision-free if blocking, waits for completion, otherwise returns after sending the goal step_size is the step size for interpolation pos_thres and rot_thres are thresholds within which the goal is declared reached times out and quits after timeout, and waits settling_time after the controllers declare that they're done

Definition at line 1004 of file controller_manager.py.

normalize an angle for a continuous joint so that it's the closest version of the angle to the current angle (not +-2*pi)

Definition at line 620 of file controller_manager.py.

normalize a trajectory (list of lists of joint angles), so that the desired angles are the nearest ones for the continuous joints (5 and 7)

Definition at line 609 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.overshoot_pose (   self,
  desired_pose,
  overshoot_dist,
  overshoot_angle,
  dist_tol,
  angle_tol,
  current_pose = None 
)

overshoot pose by overshoot_dist and overshoot_angle, unless we're already within dist_tol/angle_tol

Definition at line 723 of file controller_manager.py.

pretty-print list to string

Definition at line 1458 of file controller_manager.py.

pretty-print numpy matrix to string

Definition at line 1463 of file controller_manager.py.

print the current Cartesian pose of the gripper

Definition at line 1451 of file controller_manager.py.

re-load the Cartesian controllers with new parameters (change cart_params before running)

Definition at line 1379 of file controller_manager.py.

re-load the joint controller with gains a fraction of the defaults

Definition at line 1406 of file controller_manager.py.

reset the collision map (and optionally all attached/collision objects)

Definition at line 437 of file controller_manager.py.

return the current Cartesian pose of the gripper

Definition at line 1432 of file controller_manager.py.

send a goal to move arm and wait for the result, modifying the goal if the start state is in collision returns 0 if timed out; otherwise an ArmNavigationErrorCodes value (int32, 1=success) from move_arm

Definition at line 385 of file controller_manager.py.

set the current desired Cartesian pose to the current gripper pose

Definition at line 797 of file controller_manager.py.

set the planning scene (for IK/move_arm calls)

Definition at line 447 of file controller_manager.py.

start sending commands from the Cartesian command thread

Definition at line 790 of file controller_manager.py.

start the Cartesian controllers (need to be loaded already)

Definition at line 1313 of file controller_manager.py.

start the gripper controller (needs to be loaded already)

Definition at line 1329 of file controller_manager.py.

start up gripper event detector to detect when an object hits the table or when someone is trying to take an object from the robot

Definition at line 340 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.start_gripper_grab (   self,
  hardness_gain = 0.035,
  timeout = 10.,
  blocking = 1 
)

opens and closes the gripper to determine how hard to grasp the object, then starts up slip servo mode

Definition at line 317 of file controller_manager.py.

just start the joint controllers (need to be loaded already)

Definition at line 1297 of file controller_manager.py.

stop all controllers

Definition at line 1343 of file controller_manager.py.

stop sending commands from the Cartesian command thread

Definition at line 783 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.stop_controllers (   self,
  stop_joint = 0,
  stop_cartesian = 0,
  stop_gripper = 0 
)

stop controllers that are currently running

Definition at line 1348 of file controller_manager.py.

stops the joint controllers, starts the Cartesian ones (both need to be loaded already)

Definition at line 1263 of file controller_manager.py.

stops the Cartesian controllers, starts the joint ones (both need to be loaded already)

Definition at line 1280 of file controller_manager.py.

unload the Cartesian controllers (to re-load with new params)

Definition at line 1207 of file controller_manager.py.

unload the joint controller

Definition at line 1248 of file controller_manager.py.

def pr2_gripper_reactive_approach.controller_manager.ControllerManager.wait_cartesian_really_done (   self,
  goal_pose,
  pos_thres = .02,
  rot_thres = .1,
  timeout = rospy.Duration(30.),
  settling_time = rospy.Duration(3.0),
  overshoot_dist = 0.,
  overshoot_angle = 0.,
  stuck_dist = .03,
  stuck_angle = .12 
)

wait for either the Cartesian pose to get near enough to a goal pose or timeout (a ROS duration) is reached or settling_time (a ROS duration) after the Cartesian controllers report that they're done

Definition at line 890 of file controller_manager.py.

wait for an action server to be ready

Definition at line 252 of file controller_manager.py.

wait for a service to be ready

Definition at line 261 of file controller_manager.py.

wait for the joint trajectory action to finish (returns 1 if succeeded, 0 otherwise) timeout is a ROS duration; default (0) is infinite timeout returns 0 if timed out, 1 if succeeded

Definition at line 1131 of file controller_manager.py.


Member Data Documentation

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 1169 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 1148 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 1029 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.

Definition at line 79 of file controller_manager.py.


The documentation for this class was generated from the following file:


pr2_gripper_reactive_approach
Author(s): Kaijen Hsiao
autogenerated on Mon Oct 6 2014 12:27:12