class documentation

class NiryoRosWrapper(AbstractNiryoRosWrapper):

Constructor: NiryoRosWrapper(collision_policy)

View In Hierarchy

Undocumented

Class Method wait_for_nodes_initialization Undocumented
Static Method copy_position_with_offsets Copies a position and adds offset to some coordinates
Static Method get_axis_limits Returns the joints and positions min and max values
Static Method get_image_parameters Gets last stream image parameters: Brightness factor, Contrast factor, Saturation factor.
Static Method get_robot_status Undocumented
Static Method get_saved_dynamic_frame_list Get list of saved dynamic frames
Static Method get_saved_pose_list Asks the pose manager service which positions are available
Static Method get_workspace_list Asks the workspace manager service names of the available workspace
Static Method list_to_robot_state_msg Translates (x, y, z, roll, pitch, yaw) to a RobotState Object
Static Method point_to_list Undocumented
Static Method quaternion_to_list Undocumented
Static Method robot_state_msg_to_list Translates a RobotState Object to (x, y, z, roll, pitch, yaw)
Static Method wait Undocumented
Method __init__ Undocumented
Method activate_electromagnet Activates electromagnet associated to electromagnet_id on pin_id
Method analog_read Reads pin number pin_id and returns its state
Method analog_write Sets pin_id state to pin_state
Method break_point Undocumented
Method calibrate_auto Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException
Method calibrate_manual Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException
Method clean_trajectory_memory Sends delete all trajectory command to the trajectory manager service
Method clear_collision_detected Undocumented
Method close_gripper Closes gripper with a speed 'speed'
Method compute_trajectory_from_poses Undocumented
Method compute_trajectory_from_poses_and_joints Undocumented
Method control_conveyor Controls conveyor associated to conveyor_id. Then stops it if bool_control_on is False, else refreshes it speed and direction
Method deactivate_electromagnet Deactivates electromagnet associated to electromagnet_id on pin_id
Method delete_dynamic_frame Delete a dynamic frame
Method delete_pose Sends delete command to the pose manager service
Method delete_trajectory Sends delete command to the trajectory manager service
Method delete_workspace Calls workspace manager to delete a certain workspace
Method detect_object No summary
Method digital_read Reads pin number pin_id and returns its state
Method digital_write Sets pin_id state to pin_state
Method edit_dynamic_frame Modify a dynamic frame
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 execute_moveit_robot_trajectory Undocumented
Method execute_registered_trajectory Sends execution command to the trajectory manager service
Method execute_trajectory_from_poses Executes trajectory from a list of pose
Method execute_trajectory_from_poses_and_joints Executes trajectory from list of poses and joints
Method forward_kinematics Computes forward kinematics
Method get_analog_io_state Undocumented
Method get_camera_intrinsics Gets calibration object: camera intrinsics, distortions coefficients
Method get_compressed_image Gets last stream image in a compressed format
Method get_conveyors_feedback Gives conveyors feedback
Method get_conveyors_number Undocumented
Method get_current_tool_id Uses /niryo_robot_tools_commander/current_id topic to get current tool id
Method get_debug_colors Undocumented
Method get_debug_markers Undocumented
Method get_digital_io_state Gets Digital IO state : Names, modes, states
Method get_hardware_status Gets hardware status : Temperature, Hardware version, motors names & types ...
Method get_hardware_version Gets the robot hardware version
Method get_joint_names Uses /joint_states topic to get the name of the joints
Method get_joints Uses /joint_states topic to get joints status
Method get_learning_mode Uses /niryo_robot/learning_mode/state topic subscriber to get learning mode status
Method get_max_velocity_scaling_factor Gets the max velocity scaling factor :return: max velocity scaling factor :rtype: float
Method get_pose Uses /niryo_robot/robot_state topic to get pose status
Method get_pose_as_list Uses /niryo_robot/robot_state topic to get pose status
Method get_pose_saved Gets saved pose from robot intern storage Will raise error if position does not exist
Method get_saved_dynamic_frame Get name, description and pose of a dynamic frame
Method get_saved_trajectory_list Asks the pose trajectory service which trajectories are available
Method get_simulation_mode The simulation mode
Method get_software_version Get the robot software version
Method get_target_pose_from_cam First detects the specified object using the camera and then returns the robot pose in which the object can be picked with the current tool
Method get_target_pose_from_rel Given a pose (x_rel, y_rel, yaw_rel) relative to a workspace, this function returns the robot pose in which the current tool will be able to pick an object at this pose. The height_offset argument (in m) defines how high the tool will hover over the workspace...
Method get_trajectory_saved Gets saved trajectory from robot intern storage Will raise error if position does not exist
Method get_workspace_poses Gets the 4 workspace poses of the workspace called 'name'
Method get_workspace_ratio Gives the length over width ratio of a certain workspace
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 highlight_block Undocumented
Method inverse_kinematics Computes inverse kinematics
Method jog_joints_shift Makes a Jog on joints position
Method jog_pose_shift Makes a Jog on end-effector position
Method move_circle Undocumented
Method move_joints Executes Move joints action
Method move_linear_pose Moves robot end effector pose to a (x, y, z, roll, pitch, yaw) pose, with a linear trajectory, in a particular frame if defined
Method move_linear_relative Move robot end of a offset by a linear movement in a frame
Method move_pose Moves robot end effector pose to a (x, y, z, roll, pitch, yaw) pose, in a particular frame if defined
Method move_pose_saved Moves robot end effector pose to a pose saved
Method move_relative Move robot end of a offset in a frame
Method move_spiral Calls robot action service to draw a spiral trajectory
Method move_to_object Same as get_target_pose_from_cam but directly moves to this position
Method move_to_sleep_pose Moves to Sleep pose which allows the user to activate the learning mode without the risk of the robot hitting something because of gravity
Method move_without_moveit Undocumented
Method open_gripper Opens gripper with a speed 'speed'
Method pick_and_place Executes a pick and place. If an error happens during the movement, error will be raised -> Args param is for development purposes
Method pick_from_pose Executes a picking from a position. If an error happens during the movement, error will be raised A picking is described as : - going over the object - going down until height = z - grasping with tool - going back over the object...
Method place_from_pose Executes a placing from a position. If an error happens during the movement, error will be raised A placing is described as : - going over the place - going down until height = z - releasing the object with tool - going back over the place...
Method pull_air_vacuum_pump Pulls air
Method push_air_vacuum_pump Pulls air
Method reboot_motors Reboots the robots motors
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 request_new_calibration Calls service to set the request calibration value. If failed, raises NiryoRosWrapperException
Method reset_tcp Resets the TCP (Tool Center Point) transformation. The TCP will be reset according to the tool equipped
Method save_dynamic_frame_from_points Create a dynamic frame with 3 points (origin, x, y)
Method save_dynamic_frame_from_poses Create a dynamic frame with 3 poses (origin, x, y)
Method save_last_learned_trajectory Saves trajectory object and sends it to the trajectory manager service
Method save_pose Saves pose in robot's memory
Method save_trajectory Saves trajectory object and sends it to the trajectory manager service
Method save_workspace_from_points Saves workspace by giving the poses of its 4 corners in the good order
Method save_workspace_from_poses Saves workspace by giving the poses of the robot to point its 4 corners with the calibration Tip. Corners should be in the good order
Method set_arm_max_acceleration Sets relative max acceleration (in %)
Method set_arm_max_velocity Sets relative max velocity (in %)
Method set_brightness Modifies image brightness
Method set_contrast Modifies image contrast
Method set_conveyor Scans for conveyor on can bus. If conveyor detected, returns the conveyor ID
Method set_jog_use_state Turns jog controller On or Off
Method set_learning_mode Calsl service to set_learning_mode according to set_bool. If failed, raises NiryoRosWrapperException
Method set_pin_mode Sets pin number pin_id to mode pin_mode
Method set_saturation Modifies image saturation
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 shift_linear_pose Executes Shift pose action with a linear trajectory
Method shift_pose Executes Shift pose action
Method stop_move Stops the robot movement
Method tool_reboot Reboots the motor of the tool equipped. Useful when an Overload error occurs. (cf HardwareStatus)
Method unset_conveyor Removes specific conveyor
Method update_tool Calls service niryo_robot_tools_commander/update_tool to update tool
Method update_trajectory_infos Undocumented
Method vision_pick Picks the specified object from the workspace. This function has multiple phases: 1. detects object using the camera 2. prepares the current tool for picking 3. approaches the object 4. moves down to the correct picking pose 5...
Method vision_pick_w_obs_joints Move Joints to observation_joints, then executes a vision pick
Method vision_pick_w_obs_pose Move Pose to observation_pose, then executes a vision pick
Instance Variable tf_buffer Undocumented
Instance Variable tf_listener Undocumented
Property collision_detected Undocumented
Property custom_button Manages the custom button
Property database Undocumented
Property led_ring Manages the LED ring
Property robot_status Undocumented
Property sound Manages sound
Method __advertise_stop Undocumented
Method __calculate_relative Calculate the pose by a relative movement (x,y,z,roll,pitch,yaw) in the frame (frame_name)
Method __calculate_transform_in_frame Calculate the pose (x,y,z,roll,pitch,yaw) in the frame (frame_name)
Method __calibrate Call service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException
Method __callback_collision_detected Undocumented
Method __conveyor_id_to_conveyor_number Undocumented
Method __conveyor_number_to_conveyor_id Undocumented
Method __execute_trajectory_from_formatted_poses Undocumented
Method __jog_shift Undocumented
Method __list_pose_joints_to_list_poses Undocumented
Method __list_pose_raw_to_list_poses Undocumented
Method __move_pose_with_cmd Executes Move pose action
Method __ping_ros_wrapper_callback Undocumented
Method __transform_pose Transform pose from a local frame to source frame
Method _create_goal Undocumented
Instance Variable __advertise_ros_wrapper_srv Undocumented
Instance Variable __analog_io_state_ntv Undocumented
Instance Variable __break_point_publisher Undocumented
Instance Variable __camera_intrinsics_message_ntv Undocumented
Instance Variable __compressed_image_message_ntv Undocumented
Instance Variable __conveyors_feedback_ntv Undocumented
Instance Variable __custom_button Undocumented
Instance Variable __database Undocumented
Instance Variable __digital_io_state_ntv Undocumented
Instance Variable __follow_joint_traj_nac Undocumented
Instance Variable __hardware_version Undocumented
Instance Variable __highlight_block_publisher Undocumented
Instance Variable __hw_status_ntv Undocumented
Instance Variable __joints_ntv Undocumented
Instance Variable __learning_mode_on_ntv Undocumented
Instance Variable __led_ring Undocumented
Instance Variable __max_velocity_scaling_factor_ntv Undocumented
Instance Variable __node_name Undocumented
Instance Variable __pose_ntv Undocumented
Instance Variable __robot_action_nac Undocumented
Instance Variable __robot_status Undocumented
Instance Variable __service_timeout Undocumented
Instance Variable __simulation_mode Undocumented
Instance Variable __software_version_ntv Undocumented
Instance Variable __sound Undocumented
Instance Variable __tools Undocumented
Instance Variable _collision_detected Undocumented
Instance Variable _collision_policy Undocumented
@classmethod
def wait_for_nodes_initialization(cls, simulation_mode=False):

Undocumented

@staticmethod
def copy_position_with_offsets(copied_pose, x_offset=0.0, y_offset=0.0, z_offset=0.0):

Copies a position and adds offset to some coordinates

@staticmethod
def get_axis_limits():

Returns the joints and positions min and max values

Returns
dictAn object containing all the values
@staticmethod
def get_image_parameters():

Gets last stream image parameters: Brightness factor, Contrast factor, Saturation factor.

Brightness factor: How much to adjust the brightness. 0.5 will give a darkened image, 1 will give the original image while 2 will enhance the brightness by a factor of 2.

Contrast factor: While a factor of 1 gives original image. Making the factor towards 0 makes the image greyer, while factor>1 increases the contrast of the image.

Saturation factor: 0 will give a black and white image, 1 will give the original image while 2 will enhance the saturation by a factor of 2.

Returns
float, float, floatBrightness factor, Contrast factor, Saturation factor
@staticmethod
def get_robot_status():

Undocumented

@staticmethod
def get_saved_dynamic_frame_list(self):

Get list of saved dynamic frames

Returns
list[str], list[str]list of dynamic frames name, list of description of dynamic frames
@staticmethod
def get_saved_pose_list(with_desc=False):

Asks the pose manager service which positions are available

Parameters
with_desc:boolIf True it returns the poses descriptions
Returns
list[str]list of positions name
@staticmethod
def get_workspace_list(with_desc=False):

Asks the workspace manager service names of the available workspace

Returns
list[str]list of workspaces name
@staticmethod
def list_to_robot_state_msg(x, y, z, roll, pitch, yaw):

Translates (x, y, z, roll, pitch, yaw) to a RobotState Object

@staticmethod
def point_to_list(point):

Undocumented

@staticmethod
def quaternion_to_list(quaternion):

Undocumented

@staticmethod
def robot_state_msg_to_list(robot_state):

Translates a RobotState Object to (x, y, z, roll, pitch, yaw)

@staticmethod
def wait(time_sleep):

Undocumented

def __init__(self, collision_policy=CollisionPolicy.HARD):

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 analog_read(self, pin_id):

Reads pin number pin_id and returns its state

Parameters
pin_id:Union[ PinID, str]The name of the pin
Returns
PinStatestate
def analog_write(self, pin_id, analog_state):

Sets pin_id state to pin_state

Parameters
pin_id:Union[ PinID, str]The name of the pin
analog_state:float
Returns
(int, str)status, message
def break_point(self):

Undocumented

def calibrate_auto(self):

Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException

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

Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException

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

Sends delete all trajectory command to the trajectory manager service

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

Undocumented

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 compute_trajectory_from_poses(self, list_poses_raw, dist_smoothing=0.0):

Undocumented

def compute_trajectory_from_poses_and_joints(self, list_pose_joints, list_type=None, dist_smoothing=0.0):

Undocumented

def control_conveyor(self, conveyor_id, bool_control_on, speed, direction):

Controls conveyor associated to conveyor_id. Then stops it if bool_control_on is False, else refreshes it speed and direction

Parameters
conveyor_id:ConveyorIDConveyorID.ID_1 or ConveyorID.ID_2
bool_control_on:boolTrue for activate, False for deactivate
speed:inttarget speed
direction:ConveyorDirectionTarget direction
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 delete_dynamic_frame(self, frame_name, belong_to_workspace=False):

Delete a dynamic frame

Parameters
frame_name:strname of the frame to remove
belong_to_workspace:booleanindicate if the frame belong to a workspace
Returns
(int, str)status, message
def delete_pose(self, name):

Sends delete command to the pose manager service

Parameters
name:str
Returns
(int, str)status, message
def delete_trajectory(self, trajectory_name):

Sends delete command to the trajectory manager service

Parameters
trajectory_name:strname
Returns
(int, str)status, message
def delete_workspace(self, name):

Calls workspace manager to delete a certain workspace

Parameters
name:strworkspace name
Returns
(int, str)status, message
def detect_object(self, workspace_name, shape, color):
Parameters
workspace_name:strname of the workspace
shape:ObjectShapeshape of the target
color:ObjectColorcolor of the target
Returns
(bool, RobotState, str, str)object_found, object_pose, object_shape, object_color
def digital_read(self, pin_id):

Reads pin number pin_id and returns its state

Parameters
pin_id:Union[ PinID, str]The name of the pin
Returns
PinStatestate
def digital_write(self, pin_id, digital_state):

Sets pin_id state to pin_state

Parameters
pin_id:Union[ PinID, str]The name of the pin
digital_state:Union[ PinState, bool]
Returns
(int, str)status, message
def edit_dynamic_frame(self, frame_name, new_frame_name, new_description):

Modify a dynamic frame

Parameters
frame_name:strname of the frame
new_frame_name:strnew name of the frame
new_description:strnew description of the frame
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
@move_command
def execute_moveit_robot_trajectory(self, moveit_robot_trajectory):

Undocumented

def execute_registered_trajectory(self, trajectory_name):

Sends execution command to the trajectory manager service

Parameters
trajectory_name:strname
Returns
(int, str)status, message
def execute_trajectory_from_poses(self, list_poses_raw, dist_smoothing=0.0):

Executes trajectory from a list of pose

Parameters
list_poses_raw:list[list[float]]list of [x, y, z, qx, qy, qz, qw] or list of [x, y, z, roll, pitch, yaw]
dist_smoothing:floatDistance from waypoints before smoothing trajectory
Returns
(int, str)status, message
def execute_trajectory_from_poses_and_joints(self, list_pose_joints, list_type=None, dist_smoothing=0.0):

Executes trajectory from list of poses and joints

Parameters
list_pose_joints:list[list[float]]List of [x,y,z,qx,qy,qz,qw] or list of [x,y,z,roll,pitch,yaw] or a list of [j1,j2,j3,j4,j5,j6]
list_type:list[string]List of string 'pose' or 'joint', or ['pose'] (if poses only) or ['joint'] (if joints only). If None, it is assumed there are only poses in the list.
dist_smoothing:floatDistance from waypoints before smoothing trajectory
Returns
(int, str)status, message
def forward_kinematics(self, j1, j2, j3, j4, j5, j6):

Computes forward kinematics

Parameters
j1:float
j2:float
j3:float
j4:float
j5:float
j6:float
Returns
list[float]list corresponding to [x, y, z, roll, pitch, yaw]
def get_analog_io_state(self):

Undocumented

def get_camera_intrinsics(self):

Gets calibration object: camera intrinsics, distortions coefficients

Returns
(list, list)raw camera intrinsics, distortions coefficients
def get_compressed_image(self, with_seq=False):

Gets last stream image in a compressed format

Returns
strstring containing a JPEG compressed image
def get_conveyors_feedback(self):

Gives conveyors feedback

Returns
List(int, bool, bool, int, int)List[ID, connection_state, running, speed, direction]
def get_conveyors_number(self):

Undocumented

def get_current_tool_id(self):

Uses /niryo_robot_tools_commander/current_id topic to get current tool id

Returns
ToolIDTool Id
def get_debug_colors(self, color):

Undocumented

def get_debug_markers(self):

Undocumented

def get_digital_io_state(self):

Gets Digital IO state : Names, modes, states

Returns
IOsStateInfos contains in a IOsState object (see niryo_robot_msgs)
def get_hardware_status(self):

Gets hardware status : Temperature, Hardware version, motors names & types ...

Returns
HardwareStatusInfos contains in a HardwareStatus object (see niryo_robot_msgs)
def get_hardware_version(self):

Gets the robot hardware version

def get_joint_names(self):

Uses /joint_states topic to get the name of the joints

Returns
list[string]list of the name of the joints
def get_joints(self):

Uses /joint_states topic to get joints status

Returns
list[float]list of joints value
def get_learning_mode(self):

Uses /niryo_robot/learning_mode/state topic subscriber to get learning mode status

Returns
boolTrue if activate else False
def get_max_velocity_scaling_factor(self):

Gets the max velocity scaling factor :return: max velocity scaling factor :rtype: float

def get_pose(self):

Uses /niryo_robot/robot_state topic to get pose status

Returns
RobotStateRobotState object (position.x/y/z && rpy.roll/pitch/yaw && orientation.x/y/z/w)
def get_pose_as_list(self):

Uses /niryo_robot/robot_state topic to get pose status

Returns
list[float]list corresponding to [x, y, z, roll, pitch, yaw]
def get_pose_saved(self, pose_name):

Gets saved pose from robot intern storage Will raise error if position does not exist

Parameters
pose_name:strPose Name
Returns
tuple[float]x, y, z, roll, pitch, yaw
def get_saved_dynamic_frame(self, frame_name):

Get name, description and pose of a dynamic frame

Parameters
frame_name:strname of the frame
Returns
list[str, str, list[float]]name, description, position and orientation of a frame
def get_saved_trajectory_list(self):

Asks the pose trajectory service which trajectories are available

Returns
list[str]list of trajectory name
def get_simulation_mode(self):

The simulation mode

def get_software_version(self):

Get the robot software version

Returns
(str, str, list[str], list[str])rpi_image_version, ros_niryo_robot_version, motor_names, stepper_firmware_versions
def get_target_pose_from_cam(self, workspace_name, height_offset, shape, color):

First detects the specified object using the camera and then returns the robot pose in which the object can be picked with the current tool

Parameters
workspace_name:strname of the workspace
height_offset:floatoffset between the workspace and the target height
shape:ObjectShapeshape of the target
color:ObjectColorcolor of the target
Returns
(bool, RobotState, str, str)object_found, object_pose, object_shape, object_color
def get_target_pose_from_rel(self, workspace_name, height_offset, x_rel, y_rel, yaw_rel):

Given a pose (x_rel, y_rel, yaw_rel) relative to a workspace, this function returns the robot pose in which the current tool will be able to pick an object at this pose. The height_offset argument (in m) defines how high the tool will hover over the workspace. If height_offset = 0, the tool will nearly touch the workspace.

Parameters
workspace_name:strname of the workspace
height_offset:floatoffset between the workspace and the target height
x_rel:float
y_rel:float
yaw_rel:float
Returns
RobotStatetarget_pose
def get_trajectory_saved(self, trajectory_name):

Gets saved trajectory from robot intern storage Will raise error if position does not exist

Parameters
trajectory_name:str
Returns
list[list[float]]list of [x, y, z, qx, qy, qz, qw]
Raises
NiryoRosWrapperExceptionIf trajectory file doesn't exist
def get_workspace_poses(self, name):

Gets the 4 workspace poses of the workspace called 'name'

Parameters
name:strworkspace name
Returns
list[list]List of the 4 workspace poses
def get_workspace_ratio(self, name):

Gives the length over width ratio of a certain workspace

Parameters
name:strworkspace name
Returns
floatratio
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 highlight_block(self, block_id):

Undocumented

def inverse_kinematics(self, x, y, z, roll, pitch, yaw):

Computes inverse kinematics

Parameters
x:float
y:float
z:float
roll:float
pitch:float
yaw:float
Returns
list[float]list of joints value
def jog_joints_shift(self, shift_values):

Makes a Jog on joints position

Parameters
shift_values:list[float]list corresponding to the shift to be applied to each joint
Returns
(int, str)status, message
def jog_pose_shift(self, shift_values):

Makes a Jog on end-effector position

Parameters
shift_values:list[float]list corresponding to the shift to be applied to the position
Returns
(int, str)status, message
def move_circle(self, x, y, z):

Undocumented

@move_command
def move_joints(self, j1, j2, j3, j4, j5, j6):

Executes Move joints action

Parameters
j1:float
j2:float
j3:float
j4:float
j5:float
j6:float
Returns
(int, str)status, message
def move_linear_pose(self, x, y, z, roll, pitch, yaw, frame=''):

Moves robot end effector pose to a (x, y, z, roll, pitch, yaw) pose, with a linear trajectory, in a particular frame if defined

Parameters
x:float
y:float
z:float
roll:float
pitch:float
yaw:float
frame:str
Returns
(int, str)status, message
@move_command
def move_linear_relative(self, offset, frame='world'):

Move robot end of a offset by a linear movement in a frame

Parameters
offset:list[float]list which contains offset of x, y, z, roll, pitch, yaw
frame:strname of local frame
Returns
(int, str)status, message
@move_command
def move_pose(self, x, y, z, roll, pitch, yaw, frame=''):

Moves robot end effector pose to a (x, y, z, roll, pitch, yaw) pose, in a particular frame if defined

Parameters
x:float
y:float
z:float
roll:float
pitch:float
yaw:float
frame:str
Returns
(int, str)status, message
def move_pose_saved(self, pose_name):

Moves robot end effector pose to a pose saved

Parameters
pose_name:str
Returns
(int, str)status, message
@move_command
def move_relative(self, offset, frame='world'):

Move robot end of a offset in a frame

Parameters
offset:list[float]list which contains offset of x, y, z, roll, pitch, yaw
frame:strname of local frame
Returns
(int, str)status, message
@move_command
def move_spiral(self, radius=0.2, angle_step=5, nb_steps=72, plan=1):

Calls robot action service to draw a spiral trajectory

Parameters
radiusmaximum distance between the spiral and the starting point
angle_steprotation between each waypoint creation
nb_stepsnumber of waypoints from the beginning to the end of the spiral
plan:intxyz plan of the spiral: 1 = yz plan, 2 = xz plan, 3 = xy plan
Returns
(int, str)status, message
def move_to_object(self, workspace, height_offset, shape, color):

Same as get_target_pose_from_cam but directly moves to this position

Parameters
workspace:strname of the workspace
height_offset:floatoffset between the workspace and the target height
shape:ObjectShapeshape of the target
color:ObjectColorcolor of the target
Returns
(bool, ObjectShape, ObjectColor)object_found, object_shape, object_color
@move_command
def move_to_sleep_pose(self):

Moves to Sleep pose which allows the user to activate the learning mode without the risk of the robot hitting something because of gravity

Returns
(int, str)status, message
def move_without_moveit(self, joints_target, duration):

Undocumented

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 pick_and_place(self, pick_pose, place_pose, dist_smoothing=0.0):

Executes a pick and place. If an error happens during the movement, error will be raised -> Args param is for development purposes

Parameters
pick_pose:list[float]
place_pose:list[float]
dist_smoothing:floatDistance from waypoints before smoothing trajectory
Returns
(int, str)status, message
def pick_from_pose(self, x, y, z, roll, pitch, yaw):

Executes a picking from a position. If an error happens during the movement, error will be raised A picking is described as : - going over the object - going down until height = z - grasping with tool - going back over the object

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

Executes a placing from a position. If an error happens during the movement, error will be raised A placing is described as : - going over the place - going down until height = z - releasing the object with tool - going back over the place

Parameters
x:float
y:float
z:float
roll:float
pitch:float
yaw:float
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 reboot_motors(self):

Reboots the robots motors

Returns
(int, str)status, message
Raises
NiryoRosWrapperException
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 request_new_calibration(self):

Calls service to set the request calibration value. If failed, raises NiryoRosWrapperException

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 save_dynamic_frame_from_points(self, frame_name, description, list_points, belong_to_workspace=False):

Create a dynamic frame with 3 points (origin, x, y)

Parameters
frame_name:strname of the frame
description:strdescription of the frame
list_points:list[list[float]]3 points needed to create the frame
belong_to_workspace:booleanindicate if the frame belong to a workspace
Returns
(int, str)status, message
def save_dynamic_frame_from_poses(self, frame_name, description, list_robot_poses, belong_to_workspace=False):

Create a dynamic frame with 3 poses (origin, x, y)

Parameters
frame_name:strname of the frame
description:strdescription of the frame
list_robot_poses:list[list[float]]3 poses needed to create the frame
belong_to_workspace:booleanindicate if the frame belong to a workspace
Returns
(int, str)status, message
def save_last_learned_trajectory(self, trajectory_name, trajectory_description):

Saves trajectory object and sends it to the trajectory manager service

Parameters
trajectory_name:strname which will have the trajectory
trajectory_description:strdescription which will have the trajectory
Returns
(int, str)status, message
def save_pose(self, name, x, y, z, roll, pitch, yaw):

Saves pose in robot's memory

Parameters
name:str
x:float
y:float
z:float
roll:float
pitch:float
yaw:float
Returns
(int, str)status, message
def save_trajectory(self, trajectory_points, trajectory_name, trajectory_description):

Saves trajectory object and sends it to the trajectory manager service

Parameters
trajectory_points:list[trajectory_msgsJointTrajectorypoint]list of trajectory_msgs/JointTrajectoryPoint
trajectory_name:strname which will have the trajectory
trajectory_descriptionUndocumented
Returns
(int, str)status, message
def save_workspace_from_points(self, name, list_points_raw):

Saves workspace by giving the poses of its 4 corners in the good order

Parameters
name:strworkspace name, max 30 char.
list_points_raw:list[list[float]]list of 4 corners [x, y, z]
Returns
(int, str)status, message
def save_workspace_from_poses(self, name, list_poses_raw):

Saves workspace by giving the poses of the robot to point its 4 corners with the calibration Tip. Corners should be in the good order

Parameters
name:strworkspace name, max 30 char.
list_poses_raw:list[list]list of 4 corners pose
Returns
(int, str)status, message
def set_arm_max_acceleration(self, percentage):

Sets relative max acceleration (in %)

Parameters
percentage:intPercentage of max acceleration
Returns
(int, str)status, message
def set_arm_max_velocity(self, percentage):

Sets relative max velocity (in %)

Parameters
percentage:intPercentage of max velocity
Returns
(int, str)status, message
def set_brightness(self, brightness_factor):

Modifies image brightness

Parameters
brightness_factor:floatHow much to adjust the brightness. 0.5 will give a darkened image, 1 will give the original image while 2 will enhance the brightness by a factor of 2.
Returns
(int, str)status, message
def set_contrast(self, contrast_factor):

Modifies image contrast

Parameters
contrast_factor:floatWhile a factor of 1 gives original image. Making the factor towards 0 makes the image greyer, while factor>1 increases the contrast of the image.
Returns
(int, str)status, message
def set_conveyor(self):

Scans for conveyor on can bus. If conveyor detected, returns the conveyor ID

Returns
ConveyorIDID
Raises
NiryoRosWrapperException
def set_jog_use_state(self, state):

Turns jog controller On or Off

Parameters
state:boolTrue to turn on, else False
Returns
(int, str)status, message
def set_learning_mode(self, set_bool):

Calsl service to set_learning_mode according to set_bool. If failed, raises NiryoRosWrapperException

Parameters
set_bool:boolTrue to activate, False to deactivate
Returns
(int, str)status, message
def set_pin_mode(self, pin_id, pin_mode):

Sets pin number pin_id to mode pin_mode

Parameters
pin_id:PinID
pin_mode:PinMode
Returns
(int, str)status, message
def set_saturation(self, saturation_factor):

Modifies image saturation

Parameters
saturation_factor:floatHow much to adjust the saturation. 0 will give a black and white image, 1 will give the original image while 2 will enhance the saturation by a factor of 2.
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
@move_command
def shift_linear_pose(self, axis, value):

Executes Shift pose action with a linear trajectory

Parameters
axis:ShiftPoseValue of RobotAxis enum corresponding to where the shift happens
value:floatshift value
Returns
(int, str)status, message
@move_command
def shift_pose(self, axis, value):

Executes Shift pose action

Parameters
axis:ShiftPoseValue of RobotAxis enum corresponding to where the shift happens
value:floatshift value
Returns
(int, str)status, message
def stop_move(self):

Stops the robot movement

Returns
list[float]list of joints value
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 unset_conveyor(self, conveyor_id):

Removes specific conveyor

Parameters
conveyor_id:ConveyorIDBasically, ConveyorID.ONE or ConveyorID.TWO
Returns
(int, str)status, message
Raises
NiryoRosWrapperException
def update_tool(self):

Calls service niryo_robot_tools_commander/update_tool to update tool

Returns
(int, str)status, message
def update_trajectory_infos(self, name, new_name, new_description):

Undocumented

def vision_pick(self, workspace_name, height_offset, shape, color):

Picks the specified object from the workspace. This function has multiple phases: 1. detects object using the camera 2. prepares the current tool for picking 3. approaches the object 4. moves down to the correct picking pose 5. actuates the current tool 6. lifts the object

Parameters
workspace_name:strname of the workspace
height_offset:floatoffset between the workspace and the target height
shape:ObjectShapeshape of the target
color:ObjectColorcolor of the target
Returns
(bool, ObjectShape, ObjectColor)object_found, object_shape, object_color
def vision_pick_w_obs_joints(self, workspace_name, height_offset, shape, color, observation_joints):

Move Joints to observation_joints, then executes a vision pick

def vision_pick_w_obs_pose(self, workspace_name, height_offset, shape, color, observation_pose_list):

Move Pose to observation_pose, then executes a vision pick

tf_buffer =

Undocumented

tf_listener =

Undocumented

@property
collision_detected =

Undocumented

@property
custom_button: CustomButtonRosWrapper =

Manages the custom button

Example:

from niryo_robot_python_ros_wrapper.ros_wrapper import *

robot = NiryoRosWrapper()
print(robot.custom_button.state)
@property
database =

Undocumented

@property
led_ring: LedRingRosWrapper =

Manages the LED ring

Example:

from niryo_robot_python_ros_wrapper.ros_wrapper import *

robot = NiryoRosWrapper()
robot.led_ring.solid(color=[255, 255, 255])
@property
robot_status =

Undocumented

@property
sound: SoundRosWrapper =

Manages sound

Example:

from niryo_robot_python_ros_wrapper.ros_wrapper import *

robot = NiryoRosWrapper()
robot.sound.play(sound.sounds[0])
def __advertise_stop(self):

Undocumented

def __calculate_relative(self, frame_name, offset):

Calculate the pose by a relative movement (x,y,z,roll,pitch,yaw) in the frame (frame_name)

:param frame_name:, name of the frame :type frame_name : str :param offset: list[x, y, z, roll, pitch, yaw] :type offset: list[6*float] :return: status, message :rtype: (int, str)

def __calculate_transform_in_frame(self, frame_name, x, y, z, roll, pitch, yaw):

Calculate the pose (x,y,z,roll,pitch,yaw) in the frame (frame_name)

:param frame_name:, name of the frame :type frame_name : str :param x: :type x: float :param y: :type y: float :param z: :type z: float :param roll: :type roll: float :param pitch: :type pitch: float :param yaw: :type yaw: float :return: point, rotation :rtype: (Position, RPY)

def __calibrate(self, calib_type_int):

Call service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException

Parameters
calib_type_int1 for auto-calibration & 2 for manual calibration
Returns
(int, str)status, message
def __callback_collision_detected(self, msg):

Undocumented

def __conveyor_id_to_conveyor_number(self, conveyor_id):

Undocumented

def __conveyor_number_to_conveyor_id(self, conveyor_number):

Undocumented

@move_command
def __execute_trajectory_from_formatted_poses(self, list_poses, dist_smoothing=0.0):

Undocumented

def __jog_shift(self, cmd, shift_values):

Undocumented

def __list_pose_joints_to_list_poses(self, list_pose_joints, list_type=None):

Undocumented

def __list_pose_raw_to_list_poses(self, list_poses_raw):

Undocumented

@move_command
def __move_pose_with_cmd(self, cmd_type, *pose):

Executes Move pose action

Parameters
cmd_type:ArmMoveCommand -> POSE, LINEAR_POSECommand Type
*posetuple corresponding to x, y, z, roll, pitch, yaw
Returns
(int, str)status, message
def __ping_ros_wrapper_callback(self):

Undocumented

def __transform_pose(self, pose_local_frame, local_frame, source_frame):

Transform pose from a local frame to source frame

Parameters
pose_local_frame:geometry_msgs/Posepose in local frame
local_frame:strname of local frame
source_frame:strname of local frame
Returns
geometry_msgs/PoseStampedtransform_pose pose in frame source
def _create_goal(self, joints_position, duration):

Undocumented

__advertise_ros_wrapper_srv =

Undocumented

__analog_io_state_ntv =

Undocumented

__break_point_publisher =

Undocumented

__camera_intrinsics_message_ntv =

Undocumented

__compressed_image_message_ntv =

Undocumented

__conveyors_feedback_ntv =

Undocumented

__custom_button =

Undocumented

__database =

Undocumented

__digital_io_state_ntv =

Undocumented

__follow_joint_traj_nac =

Undocumented

__hardware_version =

Undocumented

__highlight_block_publisher =

Undocumented

__hw_status_ntv =

Undocumented

__joints_ntv =

Undocumented

__learning_mode_on_ntv =

Undocumented

__led_ring =

Undocumented

__max_velocity_scaling_factor_ntv =

Undocumented

__node_name =

Undocumented

__pose_ntv =

Undocumented

__robot_action_nac =

Undocumented

__robot_status =

Undocumented

__service_timeout =

Undocumented

__simulation_mode =

Undocumented

__software_version_ntv =

Undocumented

__sound =

Undocumented

__tools =

Undocumented

_collision_detected: bool =

Undocumented

_collision_policy =

Undocumented