Python ROS Wrapper documentation

This file presents the different Functions, Classes & Enums available with the API.

API functions

This class allows you to control the robot via internal API.
By controlling, we mean:
  • Moving the robot.
  • Using Vision.
  • Controlling Conveyors Belt.
  • Playing with hardware.

List of functions subsections:

Main purpose functions

class NiryoRosWrapper[source]
calibrate_auto()[source]

Call service to calibrate motors then wait for its end. If failed, raise NiryoRosWrapperException

Returns:status, message
Return type:(int, str)
calibrate_manual()[source]

Call service to calibrate motors then wait for its end. If failed, raise NiryoRosWrapperException

Returns:status, message
Return type:(int, str)
get_learning_mode()[source]

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

Returns:True if activate else False
Return type:bool
set_learning_mode(set_bool)[source]

Call service to set_learning_mode according to set_bool. If failed, raise NiryoRosWrapperException

Parameters:set_bool (bool) – True to activate, False to deactivate
Returns:status, message
Return type:(int, str)
set_arm_max_velocity(percentage)[source]

Set relative max velocity (in %)

Parameters:percentage (int) – Percentage of max velocity
Returns:status, message
Return type:(int, str)

Joints & Pose

class NiryoRosWrapper[source]
get_joints()[source]

Use /joint_states topic to get joints status

Returns:list of joints value
Return type:list[float]
get_pose()[source]

Use /niryo_robot/robot_state topic to get pose status

Returns:RobotState object (position.x/y/z && rpy.roll/pitch/yaw && orientation.x/y/z/w)
Return type:RobotState
get_pose_as_list()[source]

Use /niryo_robot/robot_state topic to get pose status

Returns:list corresponding to [x, y, z, roll, pitch, yaw]
Return type:list[float]
move_joints(j1, j2, j3, j4, j5, j6)[source]

Execute Move joints action

Parameters:
Returns:

status, message

Return type:

(int, str)

move_to_sleep_pose()[source]

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

Returns:status, message
Return type:(int, str)
move_pose(x, y, z, roll, pitch, yaw)[source]

Move robot end effector pose to a (x, y, z, roll, pitch, yaw) pose.

Parameters:
Returns:

status, message

Return type:

(int, str)

shift_pose(axis, value)[source]

Execute Shift pose action

Parameters:
  • axis (ShiftPose) – Value of RobotAxis enum corresponding to where the shift happens
  • value (float) – shift value
Returns:

status, message

Return type:

(int, str)

shift_linear_pose(axis, value)[source]

Execute Shift pose action with a linear trajectory

Parameters:
  • axis (ShiftPose) – Value of RobotAxis enum corresponding to where the shift happens
  • value (float) – shift value
Returns:

status, message

Return type:

(int, str)

move_linear_pose(x, y, z, roll, pitch, yaw)[source]

Move robot end effector pose to a (x, y, z, roll, pitch, yaw) pose, with a linear trajectory

Parameters:
Returns:

status, message

Return type:

(int, str)

set_jog_use_state(state)[source]

Turn jog controller On or Off

Parameters:state (bool) – True to turn on, else False
Returns:status, message
Return type:(int, str)
jog_joints_shift(shift_values)[source]

Make a Jog on joints position

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

Make a Jog on end-effector position

Parameters:shift_values (list[float]) – list corresponding to the shift to be applied to the position
Returns:status, message
Return type:(int, str)
forward_kinematics(j1, j2, j3, j4, j5, j6)[source]

Compute forward kinematics

Parameters:
Returns:

list corresponding to [x, y, z, roll, pitch, yaw]

Return type:

list[float]

inverse_kinematics(x, y, z, roll, pitch, yaw)[source]

Compute inverse kinematics

Parameters:
Returns:

list of joints value

Return type:

list[float]

Saved poses

class NiryoRosWrapper[source]
move_pose_saved(pose_name)[source]

Move robot end effector pose to a pose saved

Parameters:pose_name (str) –
Returns:status, message
Return type:(int, str)
get_pose_saved(pose_name)[source]

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

Parameters:pose_name (str) – Pose Name
Returns:x, y, z, roll, pitch, yaw
Return type:tuple[float]
save_pose(name, x, y, z, roll, pitch, yaw)[source]

Save pose in robot’s memory

Parameters:
Returns:

status, message

Return type:

(int, str)

delete_pose(name)[source]

Send delete command to the pose manager service

Parameters:name (str) –
Returns:status, message
Return type:(int, str)
get_saved_pose_list()[source]

Ask the pose manager service which positions are available

Returns:list of positions name
Return type:list[str]

Pick & place

class NiryoRosWrapper[source]
pick_from_pose(x, y, z, roll, pitch, yaw)[source]

Execute 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:
Returns:

status, message

Return type:

(int, str)

place_from_pose(x, y, z, roll, pitch, yaw)[source]

Execute 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:
Returns:

status, message

Return type:

(int, str)

pick_and_place(pick_pose, place_pose, dist_smoothing=0.0)[source]

Execute 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 (float) – Distance from waypoints before smoothing trajectory
Returns:

status, message

Return type:

(int, str)

Trajectories

class NiryoRosWrapper[source]
get_trajectory_saved(trajectory_name)[source]

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

Parameters:trajectory_name (str) –
Raises:NiryoRosWrapperException – If trajectory file doesn’t exist
Returns:list of [x, y, z, qx, qy, qz, qw]
Return type:list[list[float]]
execute_trajectory_saved(trajectory_name)[source]

Execute trajectory saved in Robot internal storage

Parameters:trajectory_name (str) –
Returns:status, message
Return type:(int, str)
execute_trajectory_from_poses(list_poses_raw, dist_smoothing=0.0)[source]

Execute 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 (float) – Distance from waypoints before smoothing trajectory
Returns:

status, message

Return type:

(int, str)

execute_trajectory_from_poses_and_joints(list_pose_joints, list_type=None, dist_smoothing=0.0)[source]

Execute 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 (float) – Distance from waypoints before smoothing trajectory
Returns:

status, message

Return type:

(int, str)

save_trajectory(trajectory_name, list_poses_raw)[source]

Save trajectory object and send it to the trajectory manager service

Parameters:
  • trajectory_name (str) – name which will have the trajectory
  • list_poses_raw (list[list[float]]) – list of [x, y, z, qx, qy, qz, qw] or list of [x, y, z, roll, pitch, yaw]
Returns:

status, message

Return type:

(int, str)

delete_trajectory(trajectory_name)[source]

Send delete command to the trajectory manager service

Parameters:trajectory_name (str) – name
Returns:status, message
Return type:(int, str)
get_saved_trajectory_list()[source]

Ask the pose trajectory service which trajectories are available

Returns:list of trajectory name
Return type:list[str]

Tools

class NiryoRosWrapper[source]
get_current_tool_id()[source]

Use /niryo_robot_hardware/tools/current_id topic to get current tool id

Returns:Tool Id
Return type:ToolID
update_tool()[source]

Call service niryo_robot_tools_commander/update_tool to update tool

Returns:status, message
Return type:(int, str)
grasp_with_tool(pin_id=-1)[source]

Grasp with the tool linked to tool_id. This action correspond 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:status, message
Return type:(int, str)
release_with_tool(pin_id=-1)[source]

Release with the tool associated to tool_id. This action correspond 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:status, message
Return type:(int, str)
open_gripper(speed=500)[source]

Open gripper with a speed ‘speed’

Parameters:speed (int) – Default -> 500
Returns:status, message
Return type:(int, str)
close_gripper(speed=500)[source]

Close gripper with a speed ‘speed’

Parameters:speed (int) – Default -> 500
Returns:status, message
Return type:(int, str)
pull_air_vacuum_pump()[source]

Pull air

Returns:status, message
Return type:(int, str)
push_air_vacuum_pump()[source]

Pull air

Returns:status, message
Return type:(int, str)
setup_electromagnet(pin_id)[source]

Setup electromagnet on pin

Parameters:pin_id (PinID) – Pin ID
Returns:status, message
Return type:(int, str)
activate_electromagnet(pin_id)[source]

Activate electromagnet associated to electromagnet_id on pin_id

Parameters:pin_id (PinID) – Pin ID
Returns:status, message
Return type:(int, str)
deactivate_electromagnet(pin_id)[source]

Deactivate electromagnet associated to electromagnet_id on pin_id

Parameters:pin_id (PinID) – Pin ID
Returns:status, message
Return type:(int, str)
enable_tcp(enable=True)[source]

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 (Bool) – True to enable, False otherwise.
Returns:status, message
Return type:(int, str)
set_tcp(x, y, z, roll, pitch, yaw)[source]

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

Parameters:
Returns:

status, message

Return type:

(int, str)

reset_tcp()[source]

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

Returns:status, message
Return type:(int, str)

Hardware

class NiryoRosWrapper[source]
set_pin_mode(pin_id, pin_mode)[source]

Set pin number pin_id to mode pin_mode

Parameters:
Returns:

status, message

Return type:

(int, str)

digital_write(pin_id, digital_state)[source]

Set pin_id state to pin_state

Parameters:
Returns:

status, message

Return type:

(int, str)

digital_read(pin_id)[source]

Read pin number pin_id and return its state

Parameters:pin_id (PinID) –
Returns:state
Return type:PinState
get_hardware_status()[source]

Get hardware status : Temperature, Hardware version, motors names & types …

Returns:Infos contains in a HardwareStatus object (see niryo_robot_msgs)
Return type:HardwareStatus
get_digital_io_state()[source]

Get Digital IO state : Names, modes, states

Returns:Infos contains in a DigitalIOState object (see niryo_robot_msgs)
Return type:DigitalIOState

Conveyor Belt

class NiryoRosWrapper[source]
set_conveyor()[source]

Scan for conveyor on can bus. If conveyor detected, return the conveyor ID

Raises:NiryoRosWrapperException
Returns:ID
Return type:ConveyorID
unset_conveyor(conveyor_id)[source]

Remove specific conveyor.

Parameters:conveyor_id (ConveyorID) – Basically, ConveyorID.ONE or ConveyorID.TWO
Raises:NiryoRosWrapperException
Returns:status, message
Return type:(int, str)
control_conveyor(conveyor_id, bool_control_on, speed, direction)[source]

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

Parameters:
  • conveyor_id (ConveyorID) – ConveyorID.ID_1 or ConveyorID.ID_2
  • bool_control_on (bool) – True for activate, False for deactivate
  • speed (int) – target speed
  • direction (ConveyorDirection) – Target direction
Returns:

status, message

Return type:

(int, str)

Vision

class NiryoRosWrapper[source]
get_compressed_image()[source]

Get last stream image in a compressed format

Returns:string containing a JPEG compressed image
Return type:str
set_brightness(brightness_factor)[source]

Modify image brightness

Parameters:brightness_factor (float) – 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.
Returns:status, message
Return type:(int, str)
set_contrast(contrast_factor)[source]

Modify image contrast

Parameters:contrast_factor (float) – 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.
Returns:status, message
Return type:(int, str)
set_saturation(saturation_factor)[source]

Modify image saturation

Parameters:saturation_factor (float) – How 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:status, message
Return type:(int, str)
get_target_pose_from_rel(workspace_name, height_offset, x_rel, y_rel, yaw_rel)[source]

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 (str) – name of the workspace
  • height_offset (float) – offset between the workspace and the target height
  • x_rel (float) –
  • y_rel (float) –
  • yaw_rel (float) –
Returns:

target_pose

Return type:

RobotState

get_target_pose_from_cam(workspace_name, height_offset, shape, color)[source]

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 (str) – name of the workspace
  • height_offset (float) – offset between the workspace and the target height
  • shape (ObjectShape) – shape of the target
  • color (ObjectColor) – color of the target
Returns:

object_found, object_pose, object_shape, object_color

Return type:

(bool, RobotState, str, str)

vision_pick_w_obs_joints(workspace_name, height_offset, shape, color, observation_joints)[source]

Move Joints to observation_joints, then execute a vision pick

vision_pick_w_obs_pose(workspace_name, height_offset, shape, color, observation_pose_list)[source]

Move Pose to observation_pose, then execute a vision pick

vision_pick(workspace_name, height_offset, shape, color)[source]

Picks the specified object from the workspace. This function has multiple phases: 1. detect object using the camera 2. prepare the current tool for picking 3. approach the object 4. move down to the correct picking pose 5. actuate the current tool 6. lift the object

Parameters:
  • workspace_name (str) – name of the workspace
  • height_offset (float) – offset between the workspace and the target height
  • shape (ObjectShape) – shape of the target
  • color (ObjectColor) – color of the target
Returns:

object_found, object_shape, object_color

Return type:

(bool, ObjectShape, ObjectColor)

move_to_object(workspace, height_offset, shape, color)[source]

Same as get_target_pose_from_cam but directly moves to this position

Parameters:
  • workspace (str) – name of the workspace
  • height_offset (float) – offset between the workspace and the target height
  • shape (ObjectShape) – shape of the target
  • color (ObjectColor) – color of the target
Returns:

object_found, object_shape, object_color

Return type:

(bool, ObjectShape, ObjectColor)

detect_object(workspace_name, shape, color)[source]
Parameters:
  • workspace_name (str) – name of the workspace
  • shape (ObjectShape) – shape of the target
  • color (ObjectColor) – color of the target
Returns:

object_found, object_pose, object_shape, object_color

Return type:

(bool, RobotState, str, str)

get_camera_intrinsics()[source]

Get calibration object: camera intrinsics, distortions coefficients

Returns:raw camera intrinsics, distortions coefficients
Return type:(list, list)
save_workspace_from_poses(name, list_poses_raw)[source]

Save 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 (str) – workspace name, max 30 char.
  • list_poses_raw (list[list]) – list of 4 corners pose
Returns:

status, message

Return type:

(int, str)

save_workspace_from_points(name, list_points_raw)[source]

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

Parameters:
  • name (str) – workspace name, max 30 char.
  • list_points_raw (list[list[float]]) – list of 4 corners [x, y, z]
Returns:

status, message

Return type:

(int, str)

delete_workspace(name)[source]

Call workspace manager to delete a certain workspace

Parameters:name (str) – workspace name
Returns:status, message
Return type:(int, str)
get_workspace_poses(name)[source]

Get the 4 workspace poses of the workspace called ‘name’

Parameters:name (str) – workspace name
Returns:List of the 4 workspace poses
Return type:list[list]
get_workspace_ratio(name)[source]

Give the length over width ratio of a certain workspace

Parameters:name (str) – workspace name
Returns:ratio
Return type:float
get_workspace_list()[source]

Ask the workspace manager service names of the available workspace

Returns:list of workspaces name
Return type:list[str]

Enums

class ShiftPose[source]
AXIS_X = 0
AXIS_Y = 1
AXIS_Z = 2
ROT_ROLL = 3
ROT_PITCH = 4
ROT_YAW = 5
class ToolID[source]

Tools IDs (need to match tools ids in niryo_robot_tools_commander package)

NONE = 0
GRIPPER_1 = 11
GRIPPER_2 = 12
GRIPPER_3 = 13
GRIPPER_4 = 14
ELECTROMAGNET_1 = 30
VACUUM_PUMP_1 = 31
class PinMode[source]

Pin Mode is either OUTPUT or INPUT

OUTPUT = 0
INPUT = 1
class PinState[source]

Pin State is either LOW or HIGH

LOW = 0
HIGH = 1
class PinID[source]

Pins ID

GPIO_1A = 2
GPIO_1B = 3
GPIO_1C = 16
GPIO_2A = 26
GPIO_2B = 19
GPIO_2C = 6
SW_1 = 12
SW_2 = 13
class ConveyorID[source]
NONE = 0
ID_1 = 12
ID_2 = 13
class ConveyorDirection[source]
FORWARD = 1
BACKWARD = -1
class ObjectColor[source]
RED = 'RED'
GREEN = 'GREEN'
BLUE = 'BLUE'
ANY = 'ANY'
class ObjectShape[source]
CIRCLE = 'CIRCLE'
SQUARE = 'SQUARE'
ANY = 'ANY'