Skip to content

update pr2eus docs #4

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
216 changes: 210 additions & 6 deletions docs/pr2eus/pr2-interface.md
Original file line number Diff line number Diff line change
@@ -1,9 +1,29 @@
### pr2-robot
- :super **euscollada-robot**
- :slots rot pos parent descendants worldcoords manager changed links joint-list bodies collision-avoidance-links end-coords-list larm-end-coords rarm-end-coords lleg-end-coords rleg-end-coords head-end-coords torso-end-coords larm-root-link rarm-root-link lleg-root-link rleg-root-link head-root-link torso-root-link larm-collision-avoidance-links rarm-collision-avoidance-links larm rarm lleg rleg torso head force-sensors imu-sensors cameras support-polygons base_bellow_joint_jt base_footprint_joint_jt base_laser_joint_jt bl_caster_l_wheel_joint_jt bl_caster_r_wheel_joint_jt bl_caster_rotation_joint_jt br_caster_l_wheel_joint_jt br_caster_r_wheel_joint_jt br_caster_rotation_joint_jt double_stereo_frame_joint_jt fl_caster_l_wheel_joint_jt fl_caster_r_wheel_joint_jt fl_caster_rotation_joint_jt fr_caster_l_wheel_joint_jt fr_caster_r_wheel_joint_jt fr_caster_rotation_joint_jt head_chain_cb_jt head_mount_joint_jt head_mount_kinect_ir_joint_jt head_mount_kinect_ir_optical_frame_joint_jt head_mount_kinect_rgb_joint_jt head_mount_kinect_rgb_optical_frame_joint_jt head_mount_prosilica_joint_jt head_mount_prosilica_optical_frame_joint_jt head_pan_joint_jt head_plate_frame_joint_jt head_tilt_joint_jt high_def_frame_joint_jt high_def_optical_frame_joint_jt imu_joint_jt l_elbow_flex_joint_jt l_forearm_cam_frame_joint_jt l_forearm_cam_optical_frame_joint_jt l_forearm_joint_jt l_forearm_roll_joint_jt l_gripper_joint_jt l_gripper_l_finger_joint_jt l_gripper_l_finger_tip_joint_jt l_gripper_led_joint_jt l_gripper_motor_accelerometer_joint_jt l_gripper_motor_screw_joint_jt l_gripper_motor_slider_joint_jt l_gripper_palm_joint_jt l_gripper_r_finger_joint_jt l_gripper_r_finger_tip_joint_jt l_gripper_tool_joint_jt l_shoulder_lift_joint_jt l_shoulder_pan_joint_jt l_torso_lift_side_plate_joint_jt l_upper_arm_joint_jt l_upper_arm_roll_joint_jt l_wrist_flex_joint_jt l_wrist_roll_joint_jt laser_tilt_joint_jt laser_tilt_mount_joint_jt left_arm_chain_cb_jt narrow_stereo_frame_joint_jt narrow_stereo_l_stereo_camera_frame_joint_jt narrow_stereo_l_stereo_camera_optical_frame_joint_jt narrow_stereo_optical_frame_joint_jt narrow_stereo_r_stereo_camera_frame_joint_jt narrow_stereo_r_stereo_camera_optical_frame_joint_jt projector_wg6802418_child_frame_joint_jt projector_wg6802418_frame_joint_jt r_elbow_flex_joint_jt r_forearm_cam_frame_joint_jt r_forearm_cam_optical_frame_joint_jt r_forearm_joint_jt r_forearm_roll_joint_jt r_gripper_joint_jt r_gripper_l_finger_joint_jt r_gripper_l_finger_tip_joint_jt r_gripper_led_joint_jt r_gripper_motor_accelerometer_joint_jt r_gripper_motor_screw_joint_jt r_gripper_motor_slider_joint_jt r_gripper_palm_joint_jt r_gripper_r_finger_joint_jt r_gripper_r_finger_tip_joint_jt r_gripper_tool_joint_jt r_shoulder_lift_joint_jt r_shoulder_pan_joint_jt r_torso_lift_side_plate_joint_jt r_upper_arm_joint_jt r_upper_arm_roll_joint_jt r_wrist_flex_joint_jt r_wrist_roll_joint_jt right_arm_chain_cb_jt sensor_mount_frame_joint_jt torso_lift_joint_jt torso_lift_motor_screw_joint_jt wide_stereo_frame_joint_jt wide_stereo_l_stereo_camera_frame_joint_jt wide_stereo_l_stereo_camera_optical_frame_joint_jt wide_stereo_optical_frame_joint_jt wide_stereo_r_stereo_camera_frame_joint_jt wide_stereo_r_stereo_camera_optical_frame_joint_jt base_bellow_link_lk base_laser_link_lk bl_caster_l_wheel_link_lk bl_caster_r_wheel_link_lk bl_caster_rotation_link_lk br_caster_l_wheel_link_lk br_caster_r_wheel_link_lk br_caster_rotation_link_lk fl_caster_l_wheel_link_lk fl_caster_r_wheel_link_lk fl_caster_rotation_link_lk fr_caster_l_wheel_link_lk fr_caster_r_wheel_link_lk fr_caster_rotation_link_lk head_chain_cb_link_lk head_mount_kinect_ir_optical_frame_lk head_mount_kinect_rgb_optical_frame_lk head_mount_kinect_rgb_link_lk head_mount_kinect_ir_link_lk head_mount_prosilica_optical_frame_lk head_mount_prosilica_link_lk head_mount_link_lk projector_wg6802418_child_frame_lk projector_wg6802418_frame_lk narrow_stereo_l_stereo_camera_optical_frame_lk narrow_stereo_r_stereo_camera_optical_frame_lk narrow_stereo_r_stereo_camera_frame_lk narrow_stereo_l_stereo_camera_frame_lk narrow_stereo_optical_frame_lk narrow_stereo_link_lk wide_stereo_l_stereo_camera_optical_frame_lk wide_stereo_r_stereo_camera_optical_frame_lk wide_stereo_r_stereo_camera_frame_lk wide_stereo_l_stereo_camera_frame_lk wide_stereo_optical_frame_lk wide_stereo_link_lk double_stereo_link_lk high_def_optical_frame_lk high_def_frame_lk sensor_mount_link_lk head_plate_frame_lk head_tilt_link_lk head_pan_link_lk imu_link_lk l_forearm_cam_optical_frame_lk l_forearm_cam_frame_lk l_gripper_l_finger_tip_link_lk l_gripper_l_finger_link_lk l_gripper_led_frame_lk l_gripper_motor_accelerometer_link_lk l_gripper_motor_screw_link_lk l_gripper_motor_slider_link_lk l_gripper_l_finger_tip_frame_lk l_gripper_r_finger_tip_link_lk l_gripper_r_finger_link_lk l_gripper_tool_frame_lk l_gripper_palm_link_lk left_arm_chain_cb_link_lk l_wrist_roll_link_lk l_wrist_flex_link_lk l_forearm_link_lk l_forearm_roll_link_lk l_elbow_flex_link_lk l_upper_arm_link_lk l_upper_arm_roll_link_lk l_shoulder_lift_link_lk l_shoulder_pan_link_lk l_torso_lift_side_plate_link_lk laser_tilt_link_lk laser_tilt_mount_link_lk r_forearm_cam_optical_frame_lk r_forearm_cam_frame_lk r_gripper_l_finger_tip_link_lk r_gripper_l_finger_link_lk r_gripper_led_frame_lk r_gripper_motor_accelerometer_link_lk r_gripper_motor_screw_link_lk r_gripper_motor_slider_link_lk r_gripper_l_finger_tip_frame_lk r_gripper_r_finger_tip_link_lk r_gripper_r_finger_link_lk r_gripper_tool_frame_lk r_gripper_palm_link_lk right_arm_chain_cb_link_lk r_wrist_roll_link_lk r_wrist_flex_link_lk r_forearm_link_lk r_forearm_roll_link_lk r_elbow_flex_link_lk r_upper_arm_link_lk r_upper_arm_roll_link_lk r_shoulder_lift_link_lk r_shoulder_pan_link_lk r_torso_lift_side_plate_link_lk torso_lift_link_lk torso_lift_motor_screw_link_lk base_link_lk base_footprint_lk rarm-grasping-obj larm-grasping-obj



:torque-vector *&rest* *args*


### pr2-interface
- :super **robot-move-base-interface**
- :slots r-gripper-action l-gripper-action finger-pressure-origin



#### :move-gripper
&nbsp;&nbsp;&nbsp;*arm* *pos* *&key* *(effort 25)* <br>&nbsp;&nbsp;&nbsp;*(wait t)* <br>&nbsp;&nbsp;&nbsp;*(ignore-stall)*

- Moves gripper of `arm` to target `pos` with `effort`. <br>
`arm` is either :rarm, :larm or :arms. <br>
`pos` is the desired distance between grippers [m]. <br>
If wait is T, this function returns T for each arm if reached goal or stalled, NIL otherwise. <br>
If `ignore-stall` is T, returns NIL for each arm on stall. (e.g. when an object is grasped). <br>
If wait if NIL, returns T for each arm if goal is accepted, NIL otherwise. <br>


#### :gripper
&nbsp;&nbsp;&nbsp;*&rest* *args*

Expand All @@ -14,6 +34,61 @@ Arguments: <br>
Example: (send self :gripper :rarm :position) => 0.00 <br>


#### :angle-vector-with-constraint
&nbsp;&nbsp;&nbsp;*av1* *&optional* *(tm 3000)* *(arm :arms)* *&key* *(rotation-axis t)* <br>&nbsp;&nbsp;&nbsp;*(translation-axis t)* <br>&nbsp;&nbsp;&nbsp;*(revert-if-fail t)* <br>&nbsp;&nbsp;&nbsp;*(initial-angle-vector nil)* <br>&nbsp;&nbsp;&nbsp;*(div 10)* <br>&nbsp;&nbsp;&nbsp;*&rest* <br>&nbsp;&nbsp;&nbsp;*args*

- Send trajectory with interpolation in euclidean space. <br>
`av1` is the target angle vector. `tm` is the total duration of the motion. `arm` is the controller that the trajectory is sent to. <br>
`:rotation-axis` and `:translation-axis` are for setting constraint on interpolated trajectory. <br>
If `:revert-if-fail` is NIL, no trajectory is sent if the interpolation is failed. <br>
If `:initial-angle-vector` is set, the value is used as initial pose of the robot, otherwise the `:reference-vector` is used. <br>


#### :list-controllers


- Returns list of available controllers with cons where cdr is t if the controller is running state, nil otherwise. <br>
<br>


#### :switch-controller
&nbsp;&nbsp;&nbsp;*stop* *start* *&key* *(force)*

- Switch controller <br>
Args: <br>
stop: controller name or list of controllers to stop <br>
start: controller name or list of controllers to start <br>
force: switch with strict policy if set to t, switch with best effort otherwise. <br>
Returns: t if successfully switched controllers, nil otherwise. <br>
<br>


#### :start-mannequin-mode
&nbsp;&nbsp;&nbsp;*&optional* *(controller t)*

- Switch controller to loose_controller. <br>
Args: <br>
controller: :head :arms :rarm :larm, list of controllers or t for all controllers <br>
Returns: t if success, nil otherwise. <br>
<br>


#### :stop-mannequin-mode
&nbsp;&nbsp;&nbsp;*&optional* *(controller t)*

- Switch controller from loose_controller to normal controller. <br>
Args: <br>
controller: :head :arms :rarm :larm, list of controllers or t for all controllers <br>
Returns: t if success, nil otherwise. <br>
<br>


#### :change-inflation-range
&nbsp;&nbsp;&nbsp;*&optional* *(range 0.3)*

- Changes inflation range of local costmap for obstacle avoidance. <br>


:init *&rest* *args* *&key* *(type :default-controller)* *&allow-other-keys*

:state *&rest* *args*
Expand Down Expand Up @@ -44,11 +119,11 @@ Example: (send self :gripper :rarm :position) => 0.00 <br>

:head-angle-vector *av* *tm*

:move-gripper *arm* *pos* *&key* *(effort 25)* *(wait t)*
:start-grasp *&optional* *(arm :arms)* *&key* *((:gain g) 0.01)* *((:objects objs) objects)* *force-assoc* *((:wait wait) t)*

:start-grasp *&optional* *(arm :arms)* *&key* *((:gain g) 0.01)* *((:objects objs) objects)* *force-assoc*
:get-grasp-result *&optional* *(arm :arms)*

:stop-grasp *&optional* *(arm :arms)* *&key* *(wait nil)*
:stop-grasp *&optional* *(arm :arms)* *&key* *((:gain g) 0.03)* *(wait nil)*

:pr2-gripper-state-callback *arm* *msg*

Expand All @@ -60,15 +135,144 @@ Example: (send self :gripper :rarm :position) => 0.00 <br>

:wait-torso *&optional* *(timeout 0)*

:robot-interface-simulation-callback

:check-continuous-joint-move-over-180 *diff-av*

:angle-vector *av* *&optional* *(tm 3000)* *&rest* *args*

:angle-vector-sequence *avs* *&optional* *(tms (list 3000))* *&rest* *args*

:angle-vector-with-constraint *av1* *&optional* *(tm 3000)* *(arm :arms)* *&key* *(rotation-axis t)* *(translation-axis t)* *&rest* *args*

#### :gripper
&nbsp;&nbsp;&nbsp;*&rest* *args*

- get information of gripper <br>
Arguments: <br>
- arm (:larm :rarm :arms) <br>
- type (:position :velocity :pressure) <br>
Example: (send self :gripper :rarm :position) => 0.00 <br>


#### :move-gripper
&nbsp;&nbsp;&nbsp;*arm* *pos* *&key* *(effort 25)* <br>&nbsp;&nbsp;&nbsp;*(wait t)* <br>&nbsp;&nbsp;&nbsp;*(ignore-stall)*

- Moves gripper of `arm` to target `pos` with `effort`. <br>
`arm` is either :rarm, :larm or :arms. <br>
`pos` is the desired distance between grippers [m]. <br>
If wait is T, this function returns T for each arm if reached goal or stalled, NIL otherwise. <br>
If `ignore-stall` is T, returns NIL for each arm on stall. (e.g. when an object is grasped). <br>
If wait if NIL, returns T for each arm if goal is accepted, NIL otherwise. <br>


:wait-torso *&optional* *(timeout 0)*

:finger-pressure *arm* *&key* *(zero nil)*

:reset-fingertip

:pr2-fingertip-callback *arm* *msg*

:pr2-gripper-state-callback *arm* *msg*

:stop-grasp *&optional* *(arm :arms)* *&key* *((:gain g) 0.03)* *(wait nil)*

:get-grasp-result *&optional* *(arm :arms)*

:start-grasp *&optional* *(arm :arms)* *&key* *((:gain g) 0.01)* *((:objects objs) objects)* *force-assoc* *((:wait wait) t)*

:head-angle-vector *av* *tm*

:rarm-angle-vector *av* *tm*

:larm-angle-vector *av* *tm*

:controller-angle-vector *av* *tm* *type*

:fullbody-controller

:midbody-controller

:default-controller

:torso-controller

:head-controller

:rarm-controller

:larm-controller

:wait-interpolation *&optional* *(ctype)* *(timeout 0)*

:publish-joint-state

:state *&rest* *args*

:init *&rest* *args* *&key* *(type :default-controller)* *&allow-other-keys*


:angle-vector-sequence *avs* *&optional* *(tms (list 3000))* *&rest* *args*

:angle-vector *av* *&optional* *(tm 3000)* *&rest* *args*

:check-continuous-joint-move-over-180 *diff-av*


#### :angle-vector-with-constraint
&nbsp;&nbsp;&nbsp;*av1* *&optional* *(tm 3000)* *(arm :arms)* *&key* *(rotation-axis t)* <br>&nbsp;&nbsp;&nbsp;*(translation-axis t)* <br>&nbsp;&nbsp;&nbsp;*(revert-if-fail t)* <br>&nbsp;&nbsp;&nbsp;*(initial-angle-vector nil)* <br>&nbsp;&nbsp;&nbsp;*(div 10)* <br>&nbsp;&nbsp;&nbsp;*&rest* <br>&nbsp;&nbsp;&nbsp;*args*

- Send trajectory with interpolation in euclidean space. <br>
`av1` is the target angle vector. `tm` is the total duration of the motion. `arm` is the controller that the trajectory is sent to. <br>
`:rotation-axis` and `:translation-axis` are for setting constraint on interpolated trajectory. <br>
If `:revert-if-fail` is NIL, no trajectory is sent if the interpolation is failed. <br>
If `:initial-angle-vector` is set, the value is used as initial pose of the robot, otherwise the `:reference-vector` is used. <br>



#### :stop-mannequin-mode
&nbsp;&nbsp;&nbsp;*&optional* *(controller t)*

- Switch controller from loose_controller to normal controller. <br>
Args: <br>
controller: :head :arms :rarm :larm, list of controllers or t for all controllers <br>
Returns: t if success, nil otherwise. <br>
<br>


#### :start-mannequin-mode
&nbsp;&nbsp;&nbsp;*&optional* *(controller t)*

- Switch controller to loose_controller. <br>
Args: <br>
controller: :head :arms :rarm :larm, list of controllers or t for all controllers <br>
Returns: t if success, nil otherwise. <br>
<br>


#### :switch-controller
&nbsp;&nbsp;&nbsp;*stop* *start* *&key* *(force)*

- Switch controller <br>
Args: <br>
stop: controller name or list of controllers to stop <br>
start: controller name or list of controllers to start <br>
force: switch with strict policy if set to t, switch with best effort otherwise. <br>
Returns: t if successfully switched controllers, nil otherwise. <br>
<br>


#### :list-controllers


- Returns list of available controllers with cons where cdr is t if the controller is running state, nil otherwise. <br>
<br>



#### :change-inflation-range
&nbsp;&nbsp;&nbsp;*&optional* *(range 0.3)*

- Changes inflation range of local costmap for obstacle avoidance. <br>



pr2-init *&optional* *(create-viewer)*
Expand Down
Loading