Python ROS Wrapper documentation¶
This file presents the different Functions, Classes & Enums available with the API.
API functions¶
- Moving the robot.
- Using Vision.
- Controlling Conveyors Belt.
- Playing with hardware.
List of functions subsections:
Main purpose functions¶
-
class
NiryoRosWrapper
[source]¶ -
calibrate_auto
()[source]¶ Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException
Returns: status, message Return type: (int, str)
-
calibrate_manual
()[source]¶ Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException
Returns: status, message Return type: (int, str)
-
get_learning_mode
()[source]¶ Uses /niryo_robot/learning_mode/state topic subscriber to get learning mode status
Returns: True
if activate elseFalse
Return type: bool
-
Joints & Pose¶
-
class
NiryoRosWrapper
[source] -
get_joints
()[source]¶ Uses /joint_states topic to get joints status
Returns: list of joints value Return type: list[float]
-
get_pose
()[source]¶ Uses /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]¶ Uses /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]¶ Executes Move joints action
Parameters: Returns: status, message
Return type:
-
move_to_sleep_pose
()[source]¶ 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: status, message Return type: (int, str)
-
move_pose
(x, y, z, roll, pitch, yaw, frame='')[source]¶ Moves robot end effector pose to a (x, y, z, roll, pitch, yaw) pose, in a particular frame if defined
Parameters: Returns: status, message
Return type:
-
shift_pose
(axis, value)[source]¶ Executes Shift pose action
Parameters: Returns: status, message
Return type:
-
shift_linear_pose
(axis, value)[source]¶ Executes Shift pose action with a linear trajectory
Parameters: Returns: status, message
Return type:
-
move_linear_pose
(x, y, z, roll, pitch, yaw, frame='')[source]¶ 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: Returns: status, message
Return type:
-
set_jog_use_state
(state)[source]¶ Turns jog controller On or Off
Parameters: state (bool) – True
to turn on, elseFalse
Returns: status, message Return type: (int, str)
-
jog_joints_shift
(shift_values)[source]¶ Makes 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]¶ Makes 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)
-
Saved poses¶
-
class
NiryoRosWrapper
[source] -
move_pose_saved
(pose_name)[source]¶ Moves 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]¶ Gets 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]¶ Saves pose in robot’s memory
Parameters: Returns: status, message
Return type:
-
Pick & place¶
-
class
NiryoRosWrapper
[source] -
pick_from_pose
(x, y, z, roll, pitch, yaw)[source]¶ 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: Returns: status, message
Return type:
-
place_from_pose
(x, y, z, roll, pitch, yaw)[source]¶ 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: Returns: status, message
Return type:
-
Trajectories¶
-
class
NiryoRosWrapper
[source] -
get_trajectory_saved
(trajectory_name)[source]¶ Gets 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]]
-
get_saved_trajectory_list
()[source]¶ Asks the pose trajectory service which trajectories are available
Returns: list of trajectory name Return type: list[str]
-
execute_trajectory_from_poses
(list_poses_raw, dist_smoothing=0.0)[source]¶ Executes trajectory from a list of pose
Parameters: Returns: status, message
Return type:
-
execute_trajectory_from_poses_and_joints
(list_pose_joints, list_type=None, dist_smoothing=0.0)[source]¶ 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 (float) – Distance from waypoints before smoothing trajectory
Returns: status, message
Return type:
-
Dynamic frames¶
-
class
NiryoRosWrapper
[source] -
save_dynamic_frame_from_poses
(frame_name, description, list_robot_poses, belong_to_workspace=False)[source]¶ Create a dynamic frame with 3 poses (origin, x, y)
Parameters: Returns: status, message
Return type:
-
save_dynamic_frame_from_points
(frame_name, description, list_points, belong_to_workspace=False)[source]¶ Create a dynamic frame with 3 points (origin, x, y)
Parameters: Returns: status, message
Return type:
-
edit_dynamic_frame
(frame_name, new_frame_name, new_description)[source]¶ Modify a dynamic frame
Parameters: Returns: status, message
Return type:
-
delete_dynamic_frame
(frame_name, belong_to_workspace=False)[source]¶ Delete a dynamic frame
Parameters: - frame_name (str) – name of the frame to remove
- belong_to_workspace (boolean) – indicate if the frame belong to a workspace
Returns: status, message
Return type:
-
get_saved_dynamic_frame
(frame_name)[source]¶ Get name, description and pose of a dynamic frame
Parameters: frame_name (str) – name of the frame Returns: name, description, position and orientation of a frame Return type: list[str, str, list[float]]
-
get_saved_dynamic_frame_list
()[source]¶ Get list of saved dynamic frames
Returns: list of dynamic frames name, list of description of dynamic frames Return type: list[str], list[str]
-
Tools¶
-
class
NiryoRosWrapper
[source] -
get_current_tool_id
()[source]¶ Uses /niryo_robot_tools_commander/current_id topic to get current tool id
Returns: Tool Id Return type: ToolID
-
update_tool
()[source]¶ Calls service niryo_robot_tools_commander/update_tool to update tool
Returns: status, message Return type: (int, str)
-
grasp_with_tool
(pin_id='')[source]¶ 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: status, message Return type: (int, str)
-
release_with_tool
(pin_id='')[source]¶ 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: status, message Return type: (int, str)
-
open_gripper
(speed=500, max_torque_percentage=100, hold_torque_percentage=20)[source]¶ Opens gripper with a speed ‘speed’
Parameters: Returns: status, message
Return type:
-
close_gripper
(speed=500, max_torque_percentage=100, hold_torque_percentage=50)[source]¶ Closes gripper with a speed ‘speed’
Parameters: Returns: status, message
Return type:
-
setup_electromagnet
(pin_id)[source]¶ Setups electromagnet on pin
Parameters: pin_id (PinID) – Pin ID Returns: status, message Return type: (int, str)
-
activate_electromagnet
(pin_id)[source]¶ Activates 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]¶ Deactivates 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)
-
Hardware¶
-
class
NiryoRosWrapper
[source] -
set_pin_mode
(pin_id, pin_mode)[source]¶ Sets pin number pin_id to mode pin_mode
Parameters: Returns: status, message
Return type:
-
digital_write
(pin_id, digital_state)[source]¶ Sets pin_id state to pin_state
Parameters: Returns: status, message
Return type:
-
digital_read
(pin_id)[source]¶ Reads pin number pin_id and returns its state
Parameters: pin_id (Union[ PinID, str]) – The name of the pin Returns: state Return type: PinState
-
Conveyor Belt¶
-
class
NiryoRosWrapper
[source] -
set_conveyor
()[source]¶ Scans for conveyor on can bus. If conveyor detected, returns the conveyor ID
Raises: NiryoRosWrapperException – Returns: ID Return type: ConveyorID
-
unset_conveyor
(conveyor_id)[source]¶ Removes 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]¶ Controls 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:
-
Vision¶
-
class
NiryoRosWrapper
[source] -
get_compressed_image
(with_seq=False)[source]¶ Gets last stream image in a compressed format
Returns: string containing a JPEG compressed image Return type: str
-
set_brightness
(brightness_factor)[source]¶ Modifies 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]¶ Modifies 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]¶ Modifies 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: 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:
-
vision_pick_w_obs_joints
(workspace_name, height_offset, shape, color, observation_joints)[source]¶ Move Joints to observation_joints, then executes a vision pick
-
vision_pick_w_obs_pose
(workspace_name, height_offset, shape, color, observation_pose_list)[source]¶ Move Pose to observation_pose, then executes 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. 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 (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:
-
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:
-
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:
-
get_camera_intrinsics
()[source]¶ Gets 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]¶ 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: Returns: status, message
Return type:
-
save_workspace_from_points
(name, list_points_raw)[source]¶ Saves workspace by giving the poses of its 4 corners in the good order
Parameters: Returns: status, message
Return type:
-
delete_workspace
(name)[source]¶ Calls workspace manager to delete a certain workspace
Parameters: name (str) – workspace name Returns: status, message Return type: (int, str)
-
get_workspace_poses
(name)[source]¶ Gets 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]
-
Sound¶
For more function, please refer to: Sound API functions
-
class
NiryoRosWrapper
[source] -
sound
¶ Manages sound
Example:
from niryo_robot_python_ros_wrapper.ros_wrapper import * robot = NiryoRosWrapper() robot.sound.play(sound.sounds[0])
Returns: SoundRosWrapper API instance Return type: SoundRosWrapper
-
Led Ring¶
For more function, please refer to: Led Ring API functions
-
class
NiryoRosWrapper
[source] -
led_ring
¶ Manages the LED ring
Example:
from niryo_robot_python_ros_wrapper.ros_wrapper import * robot = NiryoRosWrapper() robot.led_ring.solid(color=[255, 255, 255])
Returns: LedRingRosWrapper API instance Return type: LedRingRosWrapper
-
Custom Button¶
-
class
NiryoRosWrapper
[source] Manages the custom button
Example:
from niryo_robot_python_ros_wrapper.ros_wrapper import * robot = NiryoRosWrapper() print(robot.custom_button.state)
Returns: CustomButtonRosWrapper API instance Return type: CustomButtonRosWrapper
Get the button state from the ButtonAction class
Returns: int value from the ButtonAction class Return type: int
Button press state
Return type: bool
Waits until a specific action occurs and returns true. Returns false if the timeout is reached.
Parameters: action (int) – int value from the ButtonAction class Returns: True if the action has occurred, false otherwise Return type: bool
Returns the detected action. Returns ButtonAction.NO_ACTION if the timeout is reached without action.
Returns: Returns the detected action, or ButtonAction.NO_ACTION if the timeout is reached without any action. Return type: int
Waits for the button to be pressed and returns the press time. Returns 0 if no press is detected after the timeout duration.
Return type: float
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
PinID
[source]¶ Pins ID
-
GPIO_1A
= '1A'¶
-
GPIO_1B
= '1B'¶
-
GPIO_1C
= '1C'¶
-
GPIO_2A
= '2A'¶
-
GPIO_2B
= '2B'¶
-
GPIO_2C
= '2C'¶
-
SW_1
= 'SW1'¶
-
SW_2
= 'SW2'¶
-
DO1
= 'DO1'¶
-
DO2
= 'DO2'¶
-
DO3
= 'DO3'¶
-
DO4
= 'DO4'¶
-
DI1
= 'DI1'¶
-
DI2
= 'DI2'¶
-
DI3
= 'DI3'¶
-
DI4
= 'DI4'¶
-
DI5
= 'DI5'¶
-
AI1
= 'AI1'¶
-
AI2
= 'AI2'¶
-
AO1
= 'AO1'¶
-
AO2
= 'AO2'¶
-
-
class
ConveyorID
[source]¶ ConveyorID to be able to have CAN (id 12 and 13) and TTL (id 9 and 10) conveyor in any possible combination
ID_1 = 12 # One, Ned ID_2 = 13 # One, Ned ID_3 = 9 # Ned2 ID_4 = 10 # Ned2
-
NONE
= 0¶
-
ID_1
= -1¶
-
ID_2
= -2¶
-
-
class
ConveyorCan
[source]¶ ConveyorID to control conveyors with CAN interface
-
NONE
= 0¶
-
ID_1
= 12¶
-
ID_2
= 13¶
-