clearpath_config.manipulators.types.arms module

class clearpath_config.manipulators.types.arms.Arm(model: str)

Bases: object

KINOVA_GEN3_6DOF = 'kinova_gen3_6dof'
KINOVA_GEN3_7DOF = 'kinova_gen3_7dof'
KINOVA_GEN3_LITE = 'kinova_gen3_lite'
MODEL = {'kinova_gen3_6dof': <class 'clearpath_config.manipulators.types.arms.KinovaGen3Dof6'>, 'kinova_gen3_7dof': <class 'clearpath_config.manipulators.types.arms.KinovaGen3Dof7'>, 'kinova_gen3_lite': <class 'clearpath_config.manipulators.types.arms.KinovaGen3Lite'>, 'universal_robots': <class 'clearpath_config.manipulators.types.arms.UniversalRobots'>}
UNIVERSAL_ROBOTS = 'universal_robots'
classmethod assert_model(model: str) None
class clearpath_config.manipulators.types.arms.BaseArm(idx: int = None, name: str = None, ip: str = '192.168.131.40', port: int = 10000, ros_parameters: dict = {}, ros_parameters_template: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseManipulator

DEFAULT_IP_ADDRESS = '192.168.131.40'
DEFAULT_IP_PORT = 10000
IP_ADDRESS = 'ip'
IP_PORT = 'port'
MANIPULATOR_MODEL = 'base'
MANIPULATOR_TYPE = 'arm'
URDF_PARAMETERS = {}
from_dict(d: dict) None
classmethod get_ip_from_idx(idx: int) str
get_urdf_parameters() dict
property ip: str
property port: int
set_idx(idx: int) None
to_dict() dict
class clearpath_config.manipulators.types.arms.KinovaGen3Dof6(idx: int = None, name: str = None, ip: str = '192.168.131.40', port: int = 10000, ros_parameters: dict = {}, ros_parameters_template: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseArm

MANIPULATOR_MODEL = 'kinova_gen3_6dof'
static assert_is_supported()

Override this method to temporarily disable accessories that are not currently supported.

When disabling an accessory, raise a clearpath_config.common.types.exception.UnsupportedAccessoryException with a suitable mesage (e.g. ‘SpamEggs driver is not yet released for ROS 2 Jazzy’)

@return None

@exception Raises a clearpath_config.common.types.exception.UnsupportedAccessoryException

if the accessory is not supported

class clearpath_config.manipulators.types.arms.KinovaGen3Dof7(idx: int = None, name: str = None, ip: str = '192.168.131.40', port: int = 10000, ros_parameters: dict = {}, ros_parameters_template: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseArm

MANIPULATOR_MODEL = 'kinova_gen3_7dof'
static assert_is_supported()

Override this method to temporarily disable accessories that are not currently supported.

When disabling an accessory, raise a clearpath_config.common.types.exception.UnsupportedAccessoryException with a suitable mesage (e.g. ‘SpamEggs driver is not yet released for ROS 2 Jazzy’)

@return None

@exception Raises a clearpath_config.common.types.exception.UnsupportedAccessoryException

if the accessory is not supported

class clearpath_config.manipulators.types.arms.KinovaGen3Lite(idx: int = None, name: str = None, ip: str = '192.168.131.40', port: int = 10000, ros_parameters: dict = {}, ros_parameters_template: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseArm

MANIPULATOR_MODEL = 'kinova_gen3_lite'
static assert_is_supported()

Override this method to temporarily disable accessories that are not currently supported.

When disabling an accessory, raise a clearpath_config.common.types.exception.UnsupportedAccessoryException with a suitable mesage (e.g. ‘SpamEggs driver is not yet released for ROS 2 Jazzy’)

@return None

@exception Raises a clearpath_config.common.types.exception.UnsupportedAccessoryException

if the accessory is not supported

class clearpath_config.manipulators.types.arms.UniversalRobots(idx: int = None, name: str = None, ip: str = '192.168.131.40', port: int = 10000, ros_parameters: dict = {}, ros_parameters_template: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseArm

HEADLESS_MODE = 'headless_mode'
INITIAL_POSITIONS = 'initial_positions'
INITIAL_POSITIONS_FILE = 'initial_positions_file'
INPUT_RECIPE_FILENAME = 'input_recipe_filename'
IP_ADDRESS = 'robot_ip'
JOINT_LIMITS_PARAMETERS_FILE = 'joint_limits_parameters_file'
KEEP_ALIVE_COUNT = 'keep_alive_count'
KINEMATICS_PARAMETERS_FILE = 'kinematics_parameters_file'
MANIPULATOR_MODEL = 'universal_robots'
MOCK_SENSOR_COMMANDS = 'mock_sensor_commands'
NON_BLOCKING_READ = 'non_blocking_read'
OUTPUT_RECIPE_FILENAME = 'output_recipe_filename'
PHYSICAL_PARAMETERS_FILE = 'physical_parameters_file'
REVERSE_IP = 'reverse_ip'
REVERSE_PORT = 'reverse_port'
SAFETY_K_POSITION = 'safety_k_position'
SAFETY_LIMITS = 'safety_limits'
SAFETY_POS_MARGIN = 'safety_pos_margin'
SCRIPT_COMMAND_PORT = 'script_command_port'
SCRIPT_FILENAME = 'script_filename'
SCRIPT_SENDER_PORT = 'script_sender_port'
SIM_GAZEBO = 'sim_gazebo'
SIM_IGNITION = 'sim_ignition'
TOOL_BAUD_RATE = 'tool_baud_rate'
TOOL_DEVICE_NAME = 'tool_device_name'
TOOL_PARITY = 'tool_parity'
TOOL_RX_IDLE_CHARS = 'tool_rx_idle_chars'
TOOL_STOP_BITS = 'tool_stop_bits'
TOOL_TCP_PORT = 'tool_tcp_port'
TOOL_TX_IDLE_CHARS = 'tool_tx_idle_chars'
TOOL_VOLTAGE = 'tool_voltage'
TRAJECTORY_PORT = 'trajectory_port'
TRANSMISSION_HW_INTERFACE = 'transmission_hw_interface'
URDF_PARAMETERS = {'headless_mode': '', 'initial_positions': '', 'initial_positions_file': '', 'input_recipe_filename': '', 'joint_limits_parameters_file': '', 'keep_alive_count': '', 'kinematics_parameters_file': '', 'mock_sensor_commands': '', 'non_blocking_read': '', 'output_recipe_filename': '', 'physical_parameters_file': '', 'reverse_ip': '', 'reverse_port': '', 'robot_ip': '', 'safety_k_position': '', 'safety_limits': '', 'safety_pos_margin': '', 'script_command_port': '', 'script_filename': '', 'script_sender_port': '', 'sim_gazebo': '', 'sim_ignition': '', 'tool_baud_rate': '', 'tool_device_name': '', 'tool_parity': '', 'tool_rx_idle_chars': '', 'tool_stop_bits': '', 'tool_tcp_port': '', 'tool_tx_idle_chars': '', 'tool_voltage': '', 'trajectory_port': '', 'transmission_hw_interface': '', 'ur_type': '', 'use_mock_hardware': '', 'use_tool_communication': '', 'visual_parameters_file': ''}
UR_TYPE = 'ur_type'
USE_MOCK_HARDWARE = 'use_mock_hardware'
USE_TOOL_COMMUNICATION = 'use_tool_communication'
VISUAL_PARAMETERS_FILE = 'visual_parameters_file'