class documentation

class ToolsRosWrapper(AbstractNiryoRosWrapper):

Constructor: ToolsRosWrapper(service_timeout)

View In Hierarchy

Undocumented

Method __init__ Undocumented
Method activate_electromagnet Activates electromagnet associated to electromagnet_id on pin_id
Method close_gripper Closes gripper with a speed 'speed'
Method deactivate_electromagnet Deactivates electromagnet associated to electromagnet_id on pin_id
Method enable_tcp Enables or disables the TCP function (Tool Center Point). If activation is requested, the last recorded TCP value will be applied. The default value depends on the gripper equipped. If deactivation is requested, the TCP will be coincident with the tool_link.
Method get_current_tool_id Uses /niryo_robot_tools_commander/current_id topic to get current tool id
Method grasp_with_tool Grasps with the tool linked to tool_id. This action corresponds to - Close gripper for Grippers - Pull Air for Vacuum pump - Activate for Electromagnet
Method open_gripper Opens gripper with a speed 'speed'
Method pull_air_vacuum_pump Pulls air
Method push_air_vacuum_pump Pulls air
Method release_with_tool Releases with the tool associated to tool_id. This action corresponds to - Open gripper for Grippers - Push Air for Vacuum pump - Deactivate for Electromagnet
Method reset_tcp Resets the TCP (Tool Center Point) transformation. The TCP will be reset according to the tool equipped.
Method set_tcp Activates the TCP function (Tool Center Point) and defines the transformation between the tool_link frame and the TCP frame.
Method setup_electromagnet Setups electromagnet on pin
Method tool_reboot Reboots the motor of the tool equipped. Useful when an Overload error occurs. (cf HardwareStatus)
Method update_tool Calls service niryo_robot_tools_commander/update_tool to update tool
Method __deal_with_electromagnet Undocumented
Method __deal_with_gripper Undocumented
Method __deal_with_vacuum_pump Undocumented
Instance Variable __current_tool_id_ntv Undocumented
Instance Variable __tool_action_nac Undocumented
def __init__(self, service_timeout=0.2):

Undocumented

def activate_electromagnet(self, pin_id):

Activates electromagnet associated to electromagnet_id on pin_id

Parameters
pin_id:PinIDPin ID
Returns
(int, str)status, message
def close_gripper(self, speed=500, max_torque_percentage=100, hold_torque_percentage=50):

Closes gripper with a speed 'speed'

Parameters
speed:intDefault -> 500
max_torque_percentage:intDefault -> 100
hold_torque_percentage:intDefault -> 20
Returns
(int, str)status, message
def deactivate_electromagnet(self, pin_id):

Deactivates electromagnet associated to electromagnet_id on pin_id

Parameters
pin_id:PinIDPin ID
Returns
(int, str)status, message
def enable_tcp(self, enable=True):

Enables or disables the TCP function (Tool Center Point). If activation is requested, the last recorded TCP value will be applied. The default value depends on the gripper equipped. If deactivation is requested, the TCP will be coincident with the tool_link.

Parameters
enable:BoolTrue to enable, False otherwise.
Returns
(int, str)status, message
def get_current_tool_id(self):

Uses /niryo_robot_tools_commander/current_id topic to get current tool id

Returns
ToolIDTool Id
def grasp_with_tool(self, pin_id=''):

Grasps with the tool linked to tool_id. This action corresponds to - Close gripper for Grippers - Pull Air for Vacuum pump - Activate for Electromagnet

Parameters
pin_id:PinID[Only required for electromagnet] Pin ID of the electromagnet
Returns
(int, str)status, message
def open_gripper(self, speed=500, max_torque_percentage=100, hold_torque_percentage=20):

Opens gripper with a speed 'speed'

Parameters
speed:intDefault -> 500
max_torque_percentage:intDefault -> 100
hold_torque_percentage:intDefault -> 20
Returns
(int, str)status, message
def pull_air_vacuum_pump(self):

Pulls air

Returns
(int, str)status, message
def push_air_vacuum_pump(self):

Pulls air

Returns
(int, str)status, message
def release_with_tool(self, pin_id=''):

Releases with the tool associated to tool_id. This action corresponds to - Open gripper for Grippers - Push Air for Vacuum pump - Deactivate for Electromagnet

Parameters
pin_id:PinID[Only required for electromagnet] Pin ID of the electromagnet
Returns
(int, str)status, message
def reset_tcp(self):

Resets the TCP (Tool Center Point) transformation. The TCP will be reset according to the tool equipped.

Returns
(int, str)status, message
def set_tcp(self, x, y, z, roll, pitch, yaw):

Activates the TCP function (Tool Center Point) and defines the transformation between the tool_link frame and the TCP frame.

Parameters
x:float
y:float
z:float
roll:float
pitch:float
yaw:float
Returns
(int, str)status, message
def setup_electromagnet(self, pin_id):

Setups electromagnet on pin

Parameters
pin_id:PinIDPin ID
Returns
(int, str)status, message
def tool_reboot(self):

Reboots the motor of the tool equipped. Useful when an Overload error occurs. (cf HardwareStatus)

Returns
(bool, str)success, message
def update_tool(self):

Calls service niryo_robot_tools_commander/update_tool to update tool

Returns
(int, str)status, message
def __deal_with_electromagnet(self, pin_id, command_int):

Undocumented

def __deal_with_gripper(self, command_int, speed=500, max_torque_percentage=100, hold_torque_percentage=100):

Undocumented

def __deal_with_vacuum_pump(self, command_int):

Undocumented

__current_tool_id_ntv =

Undocumented

__tool_action_nac =

Undocumented