Definition at line 67 of file bhand_node.py.
def bhand_node.BHand.__init__ | ( | self, | |
args | |||
) |
Definition at line 69 of file bhand_node.py.
def bhand_node.BHand.actionsToString | ( | self, | |
action | |||
) |
@param action: action to convert @type state: bhand_controller.msg.Service @returns the equivalent string of the action
Definition at line 725 of file bhand_node.py.
def bhand_node.BHand.allState | ( | self | ) |
Actions performed in all states
Definition at line 689 of file bhand_node.py.
def bhand_node.BHand.canError | ( | self, | |
n | |||
) |
Manages the CAN errors ocurred @param n: number of produced @type n: int @returns: True or false depending on the result
Definition at line 866 of file bhand_node.py.
def bhand_node.BHand.closeFingers | ( | self, | |
value | |||
) |
Closes all the fingers
Definition at line 954 of file bhand_node.py.
def bhand_node.BHand.commandCallback | ( | self, | |
data | |||
) |
Function called when receive a new value @param data: state to convert @type data: sensor_msgs.JointState
Definition at line 753 of file bhand_node.py.
def bhand_node.BHand.controlLoop | ( | self | ) |
Main loop of the component Manages actions by state
Definition at line 295 of file bhand_node.py.
def bhand_node.BHand.emergencyState | ( | self | ) |
Actions performed in emergency state
Definition at line 646 of file bhand_node.py.
def bhand_node.BHand.failureRecover | ( | self | ) |
Sets the recovery flag TRUE. Function called after timer
Definition at line 893 of file bhand_node.py.
def bhand_node.BHand.failureState | ( | self | ) |
Actions performed in failure state
Definition at line 653 of file bhand_node.py.
def bhand_node.BHand.handActions | ( | self, | |
req | |||
) |
Handles the callback to Actions ROS service. Allows a set of predefined actions like init_hand, close_grasp, ... @param req: action id to perform @type req: bhand_controller.srv.Actions @returns: True or false depending on the result
Definition at line 830 of file bhand_node.py.
def bhand_node.BHand.initFailureRecoverTimer | ( | self, | |
timer = 5 |
|||
) |
Function to start the timer to recover from FAILURE STATE
Definition at line 885 of file bhand_node.py.
def bhand_node.BHand.initReadTempTimer | ( | self | ) |
Function to start the timer to read the temperature
Definition at line 787 of file bhand_node.py.
def bhand_node.BHand.initState | ( | self | ) |
Actions performed in init state
Definition at line 368 of file bhand_node.py.
def bhand_node.BHand.openFingers | ( | self | ) |
Opens all the fingers
Definition at line 942 of file bhand_node.py.
def bhand_node.BHand.publishROSstate | ( | self | ) |
Publish the State of the component at the desired frequency
Definition at line 797 of file bhand_node.py.
def bhand_node.BHand.readTemp | ( | self | ) |
Function periodically to enable the read of temperature
Definition at line 774 of file bhand_node.py.
def bhand_node.BHand.readyState | ( | self | ) |
Actions performed in ready state
Definition at line 395 of file bhand_node.py.
def bhand_node.BHand.rosPublish | ( | self | ) |
Publish topics at standard frequency
Definition at line 348 of file bhand_node.py.
def bhand_node.BHand.rosSetup | ( | self | ) |
Creates and inits ROS components
Definition at line 200 of file bhand_node.py.
def bhand_node.BHand.rosShutdown | ( | self | ) |
Shutdows all ROS components @return: 0 if it's performed successfully, -1 if there's any problem or the component is running
Definition at line 248 of file bhand_node.py.
def bhand_node.BHand.setControlMode | ( | self, | |
mode | |||
) |
Configures the hand to work under the desired control mode @param mode: new mode @type mode: string
Definition at line 923 of file bhand_node.py.
def bhand_node.BHand.setControlModeServiceCb | ( | self, | |
req | |||
) |
Sets the hand control mode @param req: Requested service @type req: bhand_controller.srv.SetControlMode
Definition at line 900 of file bhand_node.py.
def bhand_node.BHand.setJointVelocity | ( | self, | |
finger | |||
) |
Sets the joint velocity of the desired joint Takes the velocity value from the attribute desired_joints_velocity @param joint: finger of the hand (F1, F2, F3, SPREAD) @type joint: string
Definition at line 610 of file bhand_node.py.
def bhand_node.BHand.setup | ( | self | ) |
Initializes de hand @return: True if OK, False otherwise
Definition at line 186 of file bhand_node.py.
def bhand_node.BHand.shutdown | ( | self | ) |
Shutdowns device @return: 0 if it's performed successfully, -1 if there's any problem or the component is running
Definition at line 226 of file bhand_node.py.
def bhand_node.BHand.shutdownState | ( | self | ) |
Actions performed in shutdown state
Definition at line 636 of file bhand_node.py.
def bhand_node.BHand.standbyState | ( | self | ) |
Actions performed in standby state
Definition at line 385 of file bhand_node.py.
def bhand_node.BHand.start | ( | self | ) |
Runs ROS configuration and the main control loop @return: 0 if OK
Definition at line 278 of file bhand_node.py.
def bhand_node.BHand.stateToString | ( | self, | |
state | |||
) |
@param state: state to convert @type state: bhand_controller.msg.State @returns the equivalent string of the state
Definition at line 698 of file bhand_node.py.
def bhand_node.BHand.stop | ( | self | ) |
Creates and inits ROS components
Definition at line 269 of file bhand_node.py.
def bhand_node.BHand.strain_to_nm | ( | self, | |
x | |||
) |
Converts from raw encoder unit reading to Newton-meters. @param x: value to convert @returns nm: the torque value in Newton-meters.
Definition at line 813 of file bhand_node.py.
def bhand_node.BHand.switchToState | ( | self, | |
new_state | |||
) |
Performs the change of state
Definition at line 667 of file bhand_node.py.
bhand_node.BHand::_hand_service [private] |
Definition at line 202 of file bhand_node.py.
bhand_node.BHand::_joints_publisher [private] |
Definition at line 202 of file bhand_node.py.
bhand_node.BHand::_joints_subscriber [private] |
Definition at line 202 of file bhand_node.py.
Definition at line 202 of file bhand_node.py.
bhand_node.BHand::_state_publisher [private] |
Definition at line 202 of file bhand_node.py.
bhand_node.BHand::_tact_array_publisher [private] |
Definition at line 202 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.
Definition at line 69 of file bhand_node.py.