|
def | __init__ (self, args) |
|
def | actionsToString (self, action) |
|
def | allState (self) |
|
def | canError (self, n) |
|
def | closeFingers (self, value) |
|
def | commandCallback (self, data) |
|
def | controlLoop (self) |
|
def | emergencyState (self) |
|
def | failureRecover (self) |
|
def | failureState (self) |
|
def | handActions (self, req) |
|
def | initFailureRecoverTimer (self, timer=5) |
|
def | initReadTempTimer (self) |
|
def | initState (self) |
|
def | openFingers (self) |
|
def | publishROSstate (self) |
|
def | readTemp (self) |
|
def | readyState (self) |
|
def | rosPublish (self) |
|
def | rosSetup (self) |
|
def | rosShutdown (self) |
|
def | setControlMode (self, mode, force=False) |
|
def | setControlModeServiceCb (self, req) |
|
def | setJointVelocity (self, finger) |
|
def | setup (self) |
|
def | shutdown (self) |
|
def | shutdownState (self) |
|
def | standbyState (self) |
|
def | start (self) |
|
def | stateToString (self, state) |
|
def | stop (self) |
|
def | strain_to_nm (self, x) |
|
def | switchToState (self, new_state) |
|
Definition at line 68 of file bhand_node.py.
def bhand_node.BHand.__init__ |
( |
|
self, |
|
|
|
args |
|
) |
| |
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 740 of file bhand_node.py.
def bhand_node.BHand.allState |
( |
|
self | ) |
|
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 883 of file bhand_node.py.
def bhand_node.BHand.closeFingers |
( |
|
self, |
|
|
|
value |
|
) |
| |
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 768 of file bhand_node.py.
def bhand_node.BHand.controlLoop |
( |
|
self | ) |
|
Main loop of the component
Manages actions by state
Definition at line 306 of file bhand_node.py.
def bhand_node.BHand.emergencyState |
( |
|
self | ) |
|
Actions performed in emergency state
Definition at line 661 of file bhand_node.py.
def bhand_node.BHand.failureRecover |
( |
|
self | ) |
|
Sets the recovery flag TRUE. Function called after timer
Definition at line 910 of file bhand_node.py.
def bhand_node.BHand.failureState |
( |
|
self | ) |
|
Actions performed in failure state
Definition at line 668 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 845 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 902 of file bhand_node.py.
def bhand_node.BHand.initReadTempTimer |
( |
|
self | ) |
|
Function to start the timer to read the temperature
Definition at line 802 of file bhand_node.py.
def bhand_node.BHand.initState |
( |
|
self | ) |
|
def bhand_node.BHand.openFingers |
( |
|
self | ) |
|
def bhand_node.BHand.publishROSstate |
( |
|
self | ) |
|
Publish the State of the component at the desired frequency
Definition at line 812 of file bhand_node.py.
def bhand_node.BHand.readTemp |
( |
|
self | ) |
|
Function periodically to enable the read of temperature
Definition at line 789 of file bhand_node.py.
def bhand_node.BHand.readyState |
( |
|
self | ) |
|
def bhand_node.BHand.rosPublish |
( |
|
self | ) |
|
Publish topics at standard frequency
Definition at line 359 of file bhand_node.py.
def bhand_node.BHand.rosSetup |
( |
|
self | ) |
|
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 258 of file bhand_node.py.
def bhand_node.BHand.setControlMode |
( |
|
self, |
|
|
|
mode, |
|
|
|
force = False |
|
) |
| |
Configures the hand to work under the desired control mode
@param mode: new mode
@type mode: string
Definition at line 940 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 917 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 625 of file bhand_node.py.
def bhand_node.BHand.setup |
( |
|
self | ) |
|
Initializes de hand
@return: True if OK, False otherwise
Definition at line 191 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 236 of file bhand_node.py.
def bhand_node.BHand.shutdownState |
( |
|
self | ) |
|
Actions performed in shutdown state
Definition at line 651 of file bhand_node.py.
def bhand_node.BHand.standbyState |
( |
|
self | ) |
|
Actions performed in standby state
Definition at line 400 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 289 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 713 of file bhand_node.py.
def bhand_node.BHand.stop |
( |
|
self | ) |
|
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 828 of file bhand_node.py.
def bhand_node.BHand.switchToState |
( |
|
self, |
|
|
|
new_state |
|
) |
| |
bhand_node.BHand._ft_sensor_publisher |
|
private |
bhand_node.BHand._hand_service |
|
private |
bhand_node.BHand._joints_publisher |
|
private |
bhand_node.BHand._joints_subscriber |
|
private |
bhand_node.BHand._set_control_mode_service |
|
private |
bhand_node.BHand._state_publisher |
|
private |
bhand_node.BHand._tact_array_publisher |
|
private |
bhand_node.BHand.actions_list |
bhand_node.BHand.can_errors |
bhand_node.BHand.can_initialized |
bhand_node.BHand.control_mode |
bhand_node.BHand.desired_freq |
bhand_node.BHand.desired_joints_position |
bhand_node.BHand.desired_joints_velocity |
bhand_node.BHand.failure_recover |
bhand_node.BHand.failure_recover_timer |
bhand_node.BHand.ft_sensor |
bhand_node.BHand.ft_sensor_frame_id |
bhand_node.BHand.grasp_mode |
bhand_node.BHand.hand_initialized |
bhand_node.BHand.joint_names |
bhand_node.BHand.joint_state |
bhand_node.BHand.max_can_errors |
bhand_node.BHand.msg_state |
bhand_node.BHand.msg_tact_array |
bhand_node.BHand.new_command |
bhand_node.BHand.publish_state_timer |
bhand_node.BHand.real_freq |
bhand_node.BHand.ros_initialized |
bhand_node.BHand.sent_joints_velocity |
bhand_node.BHand.t_publish_state |
bhand_node.BHand.t_read_temp |
bhand_node.BHand.tactile_sensors |
bhand_node.BHand.temp_command |
bhand_node.BHand.temp_current_sensor |
bhand_node.BHand.temp_read_timer |
bhand_node.BHand.temp_sensor_number |
bhand_node.BHand.temperatures |
bhand_node.BHand.time_sleep |
bhand_node.BHand.timer_command |
bhand_node.BHand.topic_state_name |
bhand_node.BHand.watchdog_command |
The documentation for this class was generated from the following file: