PyRIDE  0.1.0
Public Member Functions
PyPR2 Class Reference

PyPR2 is the main Python extension module of PyRIDE on PR2/ROS system. More...

List of all members.

Public Member Functions

 listTFFrames ()
 Return a list of supported PR2 TF frame names.
 isSupportedTFFrame ()
 Check whether the input TF frame is supported in the current system.
 useMoveIt ()
 Return whether MoveIt is in use.
 moveTorsoBy (length, best_time)
 Move the PR2 torso height by a certain length.
 moveBodyTo (x, y, theta, best_time)
 Move the PR2 body to a pose at (x,y,theta).
 moveBodyWithSpeed (x, y, theta)
 Set the PR2 body moving speed in the form of (x,y,theta).
 moveHeadTo (head_yaw, head_pitch)
 Move the PR2 head to a specific yaw and pitch position.
 pointHeadTo (reference_frame, x, y, z)
 Point the PR2 head towards a specific coordinates in a reference frame.
 getHeadPos ()
 Get the current robot head yaw and pitch in radian.
 getJointPos (joint_name)
 Get the current (angle) position of a joint.
 getPositionForJoints (joint_names)
 Get the current (angle) position of a joint.
 getArmJointPositions (left_arm)
 Get the current joint positions of one of the PR2 arm.
 getRobotPose ()
 Get the current PR2 body pose.
 getRelativeTF (reference_frame, frame)
 Get the relative position and orientation of an input frame w.r.t to a reference frame.
 tuckBothArms ()
 Tuck both PR2 arms to their safe positions.
 navigateBodyTo (target_position, target_orientation)
 Navigate PR2 body to a specified pose.
 moveArmTo (position, orientation, use_left_arm)
 Move a PR2 arm to a specified pose.
 moveArmInTrajectory (trajectory, period, left_arm, relative)
 Move a PR2 arm to a specified trajectory.
 getArmPose (left_arm)
 Get the current arm pose in task space with respect to base_foot_print TF frame.
 moveArmWithJointPos (joint_position, time_to_reach)
 Move a PR2 arm to the specified joint position within a time frame.
 moveArmWithJointTrajectory (joint_trajectory)
 Move a PR2 arm to a sequence of waypoints, i.e. joint trajectory.
 moveArmWithJointTrajectoryAndSpeed (joint_trajectory)
 Move a PR2 arm to a sequence of waypoints, i.e. joint trajectory, coupled with associated joint velocities.
 moveArmWithJointVelocity (joint_velocities)
 Move a PR2 arm with raw joint velocity command.
 cancelMoveArmAction (is_left_arm)
 Cancel current arm movement action invoked by PyPR2.moveArmWithJointPos or PyPR2.moveArmWithJointTrajectory method call.
 useJointVelocityControl (enable)
 Enable or disable the use of joint velocity controllers.
 cancelMoveBodyAction ()
 Cancel current body movement action invoked by PyPR2.moveBodyTo or PyPR2.moveBodyWithSpeed method call.
 openGripper (which_gripper)
 Opens one or both PR2 grippers.
 closeGripper (which_gripper)
 Closes one or both PR2 grippers.
 setGripperPosition (which_gripper, position)
 Opens one or both PR2 grippers.
 setTiltLaserPeriodic (amplitude, period)
 Set the PR2 tilt laser in a pure periodic movement.
 setTiltLaserTraj (positions, durations)
 Set a specific sequence of repeated PR2 tilt laser position.
 registerBaseScanCallback (laser_data_callback, target_frame)
 Register a callback function for receiving base laser scan data. None object can be used to stop receiving the scan data. If target frame is provided, the 3D position (x,y,z) w.r.t the target frame will be returned. Otherwise, raw laser scan data is returned.
 registerTiltScanCallback (laser_data_callback, target_frame)
 Register a callback function for receiving tilt laser scan data. None object can be used to stop receiving the scan data. If target frame is provided, the 3D position (x,y,z) w.r.t the target frame will be returned. Otherwise, raw laser scan data is returned.
 addSolidObject (name, volume, position, orientation)
 Add a solid object to the current collision scene.
 delSolidObject ()
 Delete an existing solid object from the current collision scene.
 listSolidObjects ()
 Return a list of known solid objects in the collision scene.
 pickUpObject (name, place, grasp_position, grasp_orientation, use_left_arm, distance_from)
 Pickup a solid object from a location (another solid object) use a specific grasp pose and approaching distance.
 placeObject (name, place, place_position, place_orientation, use_left_arm, distance_from)
 Place a solid object to a location (another solid object) use a specific place pose and retreating distance.
 setTeamMemberID (member_id, team_id)
 Sets the ID number of the robot.
 say (text)
 Use Text-to-Speech system to say the input text.
 sendTeamMessage (message)
 Broadcast a message to other robots in the same team (colour).
Remote Client Access Functions
 onRemoteCommand (cmd_id, cmd_text)
 Callback function when a custom command is received from a remote client.
 onUserLogOn (user_name)
 Callback function when a user logs in through a remote client.
 onUserLogOff (user_name)
 Callback function when a remote user logs off.
 disconnect (username)
 Disconnect all remote clients.
 blockRemoteExclusiveControl (toblock)
 Block or unblock exclusive control of connected remote clients.
 updateOperationalStatus (op_state, op_text)
 Send robot operational status notification to all connected remote clients.
Timer Management Functions
 onTimer (timer_id)
 Callback function when a timer object is fired.
 onTimerLapsed (timer_id)
 Callback function when a timer object is fired for the last time.
 addTimer (init_start, repeats, interval)
 Add a timer object.
 removeTimer (timer_id)
 Remove a timer object.
 isTimerRunning (timer_id)
 Check whether a timer object is still alive.
 removeAllTimers ()
 Remove all timer objects in the system.
Miscellaneous Functions
 onSnapshotImage (image_name)
 Callback function when PyPR2.takeCameraSnapshot is called.
 setToMannequinMode (to_set)
 Set PR2 to the mannequin mode.
 startDataRecording (data_type, output_file)
 Start to record various sensor data into a ROS bag file.
 stopDataRecording ()
 Stop recording PR2 sensor data.
 startJoystickControl ()
 Start controlling PR2 with a PS3 joystick.
 stopJoystickControl ()
 Stop controlling PR2 with a PS3 joystick.
 setProjectorOff (to_set)
 Set PR2's texture projector to off or on.
 getBatteryStatus ()
 Return the current robot battery status.
 getLowPowerThreshold ()
 Return the current low power threshold.
 setLowPowerThreshold (battery_percentage)
 Set the low power threshold.
 takeCameraSnapshot (all_camera)
 Take a snapshot for the robot camera(s)
 getMyIPAddress ()
 Get the IP address of the robot.
Remote Client User Management Functions
 listCurrentUsers ()
 Return a list of users who are currently logged in through remote clients.
 listAllUsers ()
 Return a list of users who can log in remotely.
 saveConfiguration ()
 Save the current user access configuration.
 addUser (user_name, user_password)
 Add a new remote user into the system.
 removeUser (user_name)
 Remove an existing remote user from the system.
 changeUserPassword (user_name, old_password, new_password)
 Change an existing remote user's password.
Action Callback Functions
 onHeadActionSuccess ()
 Callback function when PyPR2.pointHeadTo method call is successful.
 onHeadActionFailed ()
 Callback function when PyPR2.pointHeadTo method call is failed.
 onMoveArmActionSuccess (is_left_arm)
 Callback function when PyPR2.moveArmWithJointPos or PyPR2.moveArmWithJointTrajectory method call is successful.
 onMoveArmActionFailed (is_left_arm)
 Callback function when PyPR2.moveArmWithJointPos or PyPR2.moveArmWithJointTrajectory method call is failed.
 onMoveTorsoSuccess ()
 Callback function when PyPR2.moveTorsoBy method call is successful.
 onMoveTorsoFailed ()
 Callback function when PyPR2.moveTorsoBy method call is failed.
 onNavigateBodySuccess ()
 Callback function when PyPR2.navigateBodyTo method call is successful.
 onNavigateBodyFailed ()
 Callback function when PyPR2.navigateBodyTo method call is failed.
 onGripperActionSuccess (is_left_gripper)
 Callback function when PyPR2.openGripper, PyPR2.closeGripper and PyPR2.setGripperPosition method call is successful.
 onGripperActionFailed (is_left_gripper)
 Callback function when PyPR2.openGripper, PyPR2.closeGripper and PyPR2.setGripperPosition method call is failed.
 onPowerPluggedChange (is_plugged_in)
 Callback function when PR2 power status changes.
 onBatteryChargeChange (battery_status)
 Callback function when PR2 battery status changes.
 onMoveBodySuccess ()
 Callback function when PyPR2.moveBodyTo method call is successful.
 onMoveBodyFailed ()
 Callback function when PyPR2.moveBodyTo method call is failed.
Miscellaneous Callback Functions
 onNodeStatusUpdate (data)
 Callback function invoked when an external ROS node dispatch status update message to PyRIDE on pyride_pr2/node_status topic.

Detailed Description

PyPR2 is the main Python extension module of PyRIDE on PR2/ROS system.

PyPR2 module consists of a set of callable Python methods specifically related to PR2 low level functionalities and a set of callback functions that should be implemented by PR2 programmers.


Member Function Documentation

addSolidObject ( name  ,
volume  ,
position  ,
orientation   
)

Add a solid object to the current collision scene.

Parameters:
stringname. Name of the solid object.
tuplevolume. The volume of the object in (width,height,depth).
tupleposition. Position of the object in (x,y,z).
tupleorientation. Orientation of the object in quaternion form (w,x,y,z).
Returns:
bool. True == success; False == otherwise.
Note:
Require MoveIt! to be running prior the start of PyRIDE.
addTimer ( init_start  ,
repeats  ,
interval   
)

Add a timer object.

Parameters:
intinit_start. Initial start time (in seconds) after the method is called.
longrepeats. A number of times the timer shall be called. -1 means infinite.
intinterval. Time interval (in seconds) between timer callbacks.
Returns:
long The ID of the timer object.
addUser ( user_name  ,
user_password   
)

Add a new remote user into the system.

Parameters:
struser_name.
struser_password.
Returns:
None.

Block or unblock exclusive control of connected remote clients.

Allow or block the exclusive control right of remote clients. If a client has already taken the exclusive control, the control right will be revoked when the input is set to True.

Parameters:
booltoblock. True for block; False for unblock.
Returns:
None
cancelMoveArmAction ( is_left_arm  )

Cancel current arm movement action invoked by PyPR2.moveArmWithJointPos or PyPR2.moveArmWithJointTrajectory method call.

Parameters:
boolis_left_arm. True cancels the left arm movement; False cancels the right arm movement.
Returns:
None.
Todo:
This function has not been fully tested on PR2 and may be buggy.

Cancel current body movement action invoked by PyPR2.moveBodyTo or PyPR2.moveBodyWithSpeed method call.

Returns:
None.
Todo:
This function has not been fully tested on PR2 and may be buggy.
changeUserPassword ( user_name  ,
old_password  ,
new_password   
)

Change an existing remote user's password.

Parameters:
struser_name name.
strold_password.
strnew_password.
Returns:
None.
closeGripper ( which_gripper  )

Closes one or both PR2 grippers.

Parameters:
intwhich_gripper. 1 = left gripper, 2 = right gripper and 3 = both grippers.
Returns:
bool. True == valid command; False == invalid command.

Delete an existing solid object from the current collision scene.

Parameters:
stringname. Name of the solid object.
Returns:
None.
Note:
Require MoveIt! to be running prior the start of PyRIDE.
disconnect ( username  )

Disconnect all remote clients.

Parameters:
strusername. Optional name of an online user to be disconnected. If no username is provided. All connected clients will be disconnected.
Returns:
None
getArmJointPositions ( left_arm  )

Get the current joint positions of one of the PR2 arm.

Parameters:
boolleft_arm. True for left arm; False for right arm.
Returns:
dictionary(arm_joint_positions).
Note:
Returned dictionary use joint names as keys.
getArmPose ( left_arm  )

Get the current arm pose in task space with respect to base_foot_print TF frame.

Parameters:
boolleft_arm. True == left arm; False == right arm.
Returns:
A dictionary of position and orientation.
Note:
Must have a working inverse kinematic engine i.e. either MoveIt! or S-PR2.

Return the current robot battery status.

Returns:
tuple(battery percentage, is_plugged_in, estimated remaining battery time).

Get the current robot head yaw and pitch in radian.

Returns:
tuple(head_yaw, head_pitch)
getJointPos ( joint_name  )

Get the current (angle) position of a joint.

Parameters:
strjoint_name. Name of a joint.
Returns:
float position. Must be in radian.

Return the current low power threshold.

Returns:
Battery percentage integer.

Get the IP address of the robot.

Returns:
The robot IP address in text.
getPositionForJoints ( joint_names  )

Get the current (angle) position of a joint.

Parameters:
listjoint_names. A list of joint names.
Returns:
list(joint_positions).
getRelativeTF ( reference_frame  ,
frame   
)

Get the relative position and orientation of an input frame w.r.t to a reference frame.

Parameters:
strreference_frame. Label of reference TF frame.
strframe. Label of the target frame.
Returns:
tuple(position,orientation).
Note:
Orientation is in quaternion form (w,x,y,z).

Get the current PR2 body pose.

Returns:
tuple(position,orientation).
Note:
Orientation is in quaternion form (w,x,y,z).

Check whether the input TF frame is supported in the current system.

Parameters:
stringframe. Name of the TF frame.
Returns:
bool. True == supported; False == not supported.
isTimerRunning ( timer_id  )

Check whether a timer object is still alive.

Parameters:
longtimer_id. ID of the timer object.
Returns:
True = timer is alive; False = timer is dead.

Return a list of users who can log in remotely.

Returns:
A list of user names.

Return a list of users who are currently logged in through remote clients.

Returns:
A list of user names.

Return a list of known solid objects in the collision scene.

Returns:
list(name of solid objects).
Note:
Require MoveIt! to be running prior the start of PyRIDE.

Return a list of supported PR2 TF frame names.

Returns:
list(frame names).
moveArmInTrajectory ( trajectory  ,
period  ,
left_arm  ,
relative   
)

Move a PR2 arm to a specified trajectory.

Parameters:
listtrajectory. A list of way points which consists of arm pose dictionaries { 'position', 'orientation' }.
floatperiod. The execution period for completing the trajectory.
boolleft_arm. True to use the left arm; False to use the right arm (default False)
boolrelative. True means the input trajectory is relative to the current arm pose; False means the trajectory is with respect to the basefoot_print reference frame.
Returns:
None.
Note:
This function is available only when S-PR2 is in use.
moveArmTo ( position  ,
orientation  ,
use_left_arm   
)

Move a PR2 arm to a specified pose.

Parameters:
tupleposition. Target position in (x,y,z) w.r.t to odometry_combined reference frame.
tupleorientation. Orientation in quaternion form (w,x,y,z).
booluse_left_arm. True to move the left arm; False to use the right arm.
boolwait. True == method blocks; False == method return immediately. (Use this parameter only for S-PR2).
Returns:
None.
Note:
Must have a working inverse kinematic engine i.e. either MoveIt! or S-PR2.
moveArmWithJointPos ( joint_position  ,
time_to_reach   
)

Move a PR2 arm to the specified joint position within a time frame.

Parameters:
dictjoint_position. A dictionary of arm joint positions in radian. The dictionary must the same structure as the return of PyPR2.getArmJointPositions.
floattime_to_reach. Timeframe for reaching the pose.
Returns:
None.
moveArmWithJointTrajectory ( joint_trajectory  )

Move a PR2 arm to a sequence of waypoints, i.e. joint trajectory.

Parameters:
listjoint_trajectory. A list of waypoints that contain joint position dictionaries with the same structure of the PyPR2.moveArmWithJointPos.
Returns:
None.
moveArmWithJointTrajectoryAndSpeed ( joint_trajectory  )

Move a PR2 arm to a sequence of waypoints, i.e. joint trajectory, coupled with associated joint velocities.

Parameters:
listjoint_trajectory. A list of waypoints with the joint data dictionaries structure of { "joint_name" : { "position" : value, "velocity" : value }, ... }. Each list item, i.e. a waypoint must also have a time to reach value that is consistent with the joint velocities at the adjacent waypoints.
Returns:
None.
moveArmWithJointVelocity ( joint_velocities  )

Move a PR2 arm with raw joint velocity command.

Parameters:
listjoint_velocities. A joint velocity dictionaries with the same structure of the PyPR2.moveArmWithJointPos without time_to_reach parameter.
Returns:
None.
Note:
You must enable joint velocity controller by calling PyPR2.useJointVelocityControl before using this method.
Warning:
You directly control the joint velocity with this method, PyRIDE provides no additional check.
moveBodyTo ( ,
,
theta  ,
best_time   
)

Move the PR2 body to a pose at (x,y,theta).

Parameters:
floatx. X coordinate w.r.t. the current pose.
floaty. Y coordinate w.r.t. the current pose.
floattheta. Angular position w.r.t. the current pose.
floatbest_time. Optional, ask the robot try its best to reach the input pose in this timeframe.
Returns:
bool. True == valid command; False == invalid command.
moveBodyWithSpeed ( ,
,
theta   
)

Set the PR2 body moving speed in the form of (x,y,theta).

Parameters:
floatx. Speed(m/s) in X axis direction.
floaty. Speed(m/s) in Y axis direction.
floattheta. Angular turning rate (rad/s) w.r.t Z axis.
Returns:
None.
Note:
Speed is restricted to maximum of 1 m/s in X/Y direction and 0.7rad/s in turning rate.
Warning:
This is a low level control function and no safty check is provided. Programmers must ensure PR2 robot movement is controlled safely.
moveHeadTo ( head_yaw  ,
head_pitch   
)

Move the PR2 head to a specific yaw and pitch position.

Parameters:
floathead_yaw. Must be in radian.
floathead_pitch. Must be in radian.
boolrelative. True == relative angle values; False == absolute angle values. Optional, default is False.
Returns:
bool. True == valid command; False == invalid command.
Todo:
This function has not been fully tested on PR2 and is still buggy.
moveTorsoBy ( length  ,
best_time   
)

Move the PR2 torso height by a certain length.

Parameters:
floatlength. The relative change in torso height.
floatbest_time. Optional, ask the robot try its best to reach the input pose in this timeframe.
Returns:
bool. True == valid command; False == invalid command.
navigateBodyTo ( target_position  ,
target_orientation   
)

Navigate PR2 body to a specified pose.

Parameters:
tupletarget_position. Position in the form of (x,y,z).
tupletarget_orientation. Orientation in quaternion form (w,x,y,z).
Returns:
None.
Note:
Must have PR2 navigation stack running prior the start of PyRIDE.
onBatteryChargeChange ( battery_status  )

Callback function when PR2 battery status changes.

Parameters:
tuplebattery_status. A tuple of (battery percentage,is_charging,is_battery_below_threshold).
Returns:
None.
Note:
Require low power threshold to be greater than zero.
onGripperActionFailed ( is_left_gripper  )

Callback function when PyPR2.openGripper, PyPR2.closeGripper and PyPR2.setGripperPosition method call is failed.

Parameters:
boolis_left_gripper. True means left gripper; False means right gripper.
Returns:
None.
onGripperActionSuccess ( is_left_gripper  )

Callback function when PyPR2.openGripper, PyPR2.closeGripper and PyPR2.setGripperPosition method call is successful.

Parameters:
boolis_left_gripper. True means left gripper; False means right gripper.
Returns:
None.

Callback function when PyPR2.pointHeadTo method call is failed.

Returns:
None.

Callback function when PyPR2.pointHeadTo method call is successful.

Returns:
None.
onMoveArmActionFailed ( is_left_arm  )

Callback function when PyPR2.moveArmWithJointPos or PyPR2.moveArmWithJointTrajectory method call is failed.

Parameters:
boolis_left_arm. True = left arm; False = right arm.
Returns:
None.
onMoveArmActionSuccess ( is_left_arm  )

Callback function when PyPR2.moveArmWithJointPos or PyPR2.moveArmWithJointTrajectory method call is successful.

Parameters:
boolis_left_arm. True = left arm; False = right arm.
Returns:
None.

Callback function when PyPR2.moveBodyTo method call is failed.

Returns:
None.

Callback function when PyPR2.moveBodyTo method call is successful.

Returns:
None.

Callback function when PyPR2.moveTorsoBy method call is failed.

Returns:
None.

Callback function when PyPR2.moveTorsoBy method call is successful.

Returns:
None.

Callback function when PyPR2.navigateBodyTo method call is failed.

Returns:
None.

Callback function when PyPR2.navigateBodyTo method call is successful.

Returns:
None.
onNodeStatusUpdate ( data  )

Callback function invoked when an external ROS node dispatch status update message to PyRIDE on pyride_pr2/node_status topic.

Parameters:
dictionarydata. node status message in the format of {'node', 'timestamp', 'priority', 'message' }.
Returns:
None.
onPowerPluggedChange ( is_plugged_in  )

Callback function when PR2 power status changes.

Parameters:
boolis_plugged_in. True if the robot is plugged in main power.
Returns:
None.
Note:
Require low power threshold to be greater than zero.
onRemoteCommand ( cmd_id  ,
cmd_text   
)

Callback function when a custom command is received from a remote client.

Parameters:
intcmd_id. Custom command ID.
strcmd_text. Custom command text string.
Returns:
None.
Note:
The remote client must take the exclusive control of the robot before its commands can trigger this callback function.
onSnapshotImage ( image_name  )

Callback function when PyPR2.takeCameraSnapshot is called.

Parameters:
strimage_name. Path for the saved image.
Returns:
None.
onTimer ( timer_id  )

Callback function when a timer object is fired.

Parameters:
inttimer_id. ID of the timer object.
Returns:
None.
onTimerLapsed ( timer_id  )

Callback function when a timer object is fired for the last time.

Parameters:
inttimer_id. ID of the timer object.
Returns:
None.
Note:
This callback function works only on timers with limited life span.
onUserLogOff ( user_name  )

Callback function when a remote user logs off.

Parameters:
struser_name. The name of the user.
Returns:
None.
onUserLogOn ( user_name  )

Callback function when a user logs in through a remote client.

Parameters:
struser_name. The name of the user.
Returns:
None.
openGripper ( which_gripper  )

Opens one or both PR2 grippers.

Parameters:
intwhich_gripper. 1 = left gripper, 2 = right gripper and 3 = both grippers.
Returns:
bool. True == valid command; False == invalid command.
pickUpObject ( name  ,
place  ,
grasp_position  ,
grasp_orientation  ,
use_left_arm  ,
distance_from   
)

Pickup a solid object from a location (another solid object) use a specific grasp pose and approaching distance.

Parameters:
stringname. Name of the solid object.
stringname. Name of the object from where the target object is picked up from.
tuplegrasp_position. Grasp position (x,y,z).
tuplegrasp_orientation. Grasp orientation in quaternion form (w,x,y,z).
booluse_left_arm. True == use the left arm; False = use the right arm.
floatdistance_from. Approaching distance from the object.
Returns:
bool. True == success; False == otherwise.
Warning:
Not fully tested!
Note:
Require MoveIt! to be running prior the start of PyRIDE.
placeObject ( name  ,
place  ,
place_position  ,
place_orientation  ,
use_left_arm  ,
distance_from   
)

Place a solid object to a location (another solid object) use a specific place pose and retreating distance.

Parameters:
stringname. Name of the solid object.
stringname. Name of the object from where the target object is placed to.
tupleplace_position. Place position (x,y,z).
tupleplace_orientation. Place orientation in quaternion form (w,x,y,z).
booluse_left_arm. True == use the left arm; False = use the right arm.
floatdistance_from. Retreating distance from the object.
Returns:
bool. True == success; False == otherwise.
Warning:
Not fully tested!
Note:
Require MoveIt! to be running prior the start of PyRIDE.
pointHeadTo ( reference_frame  ,
,
,
 
)

Point the PR2 head towards a specific coordinates in a reference frame.

Parameters:
strreference_frame. Text label for the requested reference frame (TF frame name).
floatx. X coordinate.
floaty. Y coordinate.
floatz. Z coordinate.
Returns:
bool. True == valid command; False == invalid command.
registerBaseScanCallback ( laser_data_callback  ,
target_frame   
)

Register a callback function for receiving base laser scan data. None object can be used to stop receiving the scan data. If target frame is provided, the 3D position (x,y,z) w.r.t the target frame will be returned. Otherwise, raw laser scan data is returned.

Parameters:
callbacklaser_data_callback. Function that takes a list of raw laser range data or 3D position data as the input.
stringtarget_frame. Optional, the name of the target frame
Returns:
None
registerTiltScanCallback ( laser_data_callback  ,
target_frame   
)

Register a callback function for receiving tilt laser scan data. None object can be used to stop receiving the scan data. If target frame is provided, the 3D position (x,y,z) w.r.t the target frame will be returned. Otherwise, raw laser scan data is returned.

Parameters:
callbacklaser_data_callback. Function that takes a list of raw laser range data or 3D position data as the input.
stringtarget_frame. Optional, the name of the target frame.
Returns:
None

Remove all timer objects in the system.

Returns:
None.
removeTimer ( timer_id  )

Remove a timer object.

Parameters:
longtimer_id. ID of the timer object pending for removal.
Returns:
None.
removeUser ( user_name  )

Remove an existing remote user from the system.

Parameters:
struser_name name.
Returns:
None.

Save the current user access configuration.

Returns:
None.
say ( text  )

Use Text-to-Speech system to say the input text.

Parameters:
strtext. Text to be spoken by the robot.
Returns:
None.
sendTeamMessage ( message  )

Broadcast a message to other robots in the same team (colour).

Parameters:
strmessage. A text based message.
Returns:
None
Note:
(legacy) This is based on the team colour assignment defined in pyrideconfig.xml
setGripperPosition ( which_gripper  ,
position   
)

Opens one or both PR2 grippers.

Parameters:
intwhich_gripper. 1 = left gripper, 2 = right gripper and 3 = both grippers.
floatposition. Must be in range of [0.0,0.08].
Returns:
bool. True == valid command; False == invalid command.
setLowPowerThreshold ( battery_percentage  )

Set the low power threshold.

When the threshold is greater than zero this level, callback PyPR2.onBatteryChargeChange or PyPR2.onPowerPluggedChange will be invoked when battery status changes.

Parameters:
intbattery_percentage. Must be non-negative.
Returns:
None.
setProjectorOff ( to_set  )

Set PR2's texture projector to off or on.

Parameters:
boolto_set. True = set projector off; False = set projector on.
Returns:
None.
setTeamMemberID ( member_id  ,
team_id   
)

Sets the ID number of the robot.

The robot can be assigned as a member of blue team (number 1) or pink team (number 2). This facilitates robot to robot communication.

Note:
This function is inherited from robot soccer competition code for NAO.
Parameters:
intmember_id. Must be a non-negative integer.
intteam_id. Must be either 1 (blue team) or 2 (pink team).
Returns:
None.
setTiltLaserPeriodic ( amplitude  ,
period   
)

Set the PR2 tilt laser in a pure periodic movement.

Parameters:
floatamplitude. Must be non-negative. Amplitude of the periodic movement.
floatperiod. Must be non-negative. Time period of the movement.
Returns:
bool. True == valid command; False == invalid command.
setTiltLaserTraj ( positions  ,
durations   
)

Set a specific sequence of repeated PR2 tilt laser position.

Parameters:
listpositions. A list of (minimum two) tilt laser positions.
listdurations. A list of corresponding durations at the defined tilt laser position.
Returns:
bool. True == valid command; False == invalid command.
setToMannequinMode ( to_set  )

Set PR2 to the mannequin mode.

Parameters:
boolto_set. True = mannequin mode; False = normal mode.
Returns:
None.
startDataRecording ( data_type  ,
output_file   
)

Start to record various sensor data into a ROS bag file.

Parameters:
intdata_type. Types of sensor data to be recorded. Different sensor datatype can be concate together with '|'.
stroutput_file. Optional output file name path.
Returns:
None.
Note:
Check constants.py for sensor data types.
Default output file name path is in the format of /removable/recordings/Ymd_HM_sensordatatype_data.bag.

Start controlling PR2 with a PS3 joystick.

Returns:
None.

Stop recording PR2 sensor data.

Returns:
None.

Stop controlling PR2 with a PS3 joystick.

Returns:
None.
takeCameraSnapshot ( all_camera  )

Take a snapshot for the robot camera(s)

Parameters:
boolall_camera. Take a snapshot from all available cameras.
Returns:
None
Note:
Image(s) taken from the robot camera(s) will be saved in /removeable/recordings/cameras directory on the PR2.

Tuck both PR2 arms to their safe positions.

Returns:
None.
updateOperationalStatus ( op_state  ,
op_text   
)

Send robot operational status notification to all connected remote clients.

Parameters:
intop_state. Must be a positive integer representing the operational status.
strop_text. Optional text for the operational status.
Returns:
None.
Note:
For pre allocated operational status ID, check constants.py.

Enable or disable the use of joint velocity controllers.

Parameters:
boolenable. True = load joint velocity controllers and stop using default joint trajectory action controller. False = switch back to use the joint trajectory action controller.
Returns:
True = successfully load or unload joint velocity controllers; False == otherwise.
Warning:
Using joint velocity controllers means, you have the direct control of joint velocity. Use PyPR2.moveArmWithJointVelocity to control arm joints.
useMoveIt ( )

Return whether MoveIt is in use.

Returns:
list(frame names).

The documentation for this class was generated from the following files:
All Classes Functions