Examples: Basics
In this file, two short programs are implemented & commented in order to help you understand the philosophy behind the Python ROS Wrapper.
Danger
If you are using the real robot, make sure the environment around is clear.
Your first move joint
The following example shows a first use case. It’s a simple MoveJ.
1#!/usr/bin/env python3
2
3from niryo_robot_python_ros_wrapper import NiryoRosWrapper, JointsPosition
4
5# Instantiate the ROS wrapper and initialize the ROS node
6robot = NiryoRosWrapper.init_with_node()
7
8# Calibrate if needed
9robot.calibrate_auto() # Only for Ned2
10
11# Move the robot
12robot.move(JointsPosition(0.1, -0.2, 0.0, 1.1, -0.5, 0.2))
Code details - First MoveJ
First of all, we indicate to the shell that we are running a Python Script:
1#!/usr/bin/env python3
Then, we import the required class/functions to be able to access functions:
1from niryo_robot_python_ros_wrapper import NiryoRosWrapper, JointsPosition
We start a NiryoRosWrapper
and initialize a ROS Node in order to communicate with ROS master:
1# Instantiate the ROS wrapper and initialize the ROS node
2robot = NiryoRosWrapper.init_with_node()
Once the connection is done, we calibrate the robot (Only for Ned2) using its
calibrate_auto()
function:
1# Calibrate if needed
2robot.calibrate_auto() # Only for Ned2
As the robot is now calibrated, we can do a Move Joints by giving the 6 axis positions
in radians! To do so, we use move()
:
1# Move the robot
2robot.move(JointsPosition(0.1, -0.2, 0.0, 1.1, -0.5, 0.2))
Your first pick and place
For our second example, we are going to develop script to make a pick and place.
1#!/usr/bin/env python3
2
3from niryo_robot_python_ros_wrapper import NiryoRosWrapper, Pose
4
5import math
6
7# Instantiate the ROS wrapper and initialize the ROS node
8robot = NiryoRosWrapper.init_with_node()
9
10# Calibrate if needed
11robot.calibrate_auto() # Only for Ned2
12
13# Setup the tool
14robot.update_tool()
15
16# Open the tool
17robot.release_with_tool()
18
19# Move to pick pose
20robot.move(Pose(0.2, 0.1, 0.14, 0.0, math.pi, -math.pi / 2))
21
22# Pick
23robot.grasp_with_tool()
24
25# Move to place pose
26robot.move(Pose(0.2, -0.1, 0.14, 0.0, math.pi, -math.pi / 2))
27
28# Place
29robot.release_with_tool()
Code details - first pick and place
First of all, we import the ROS wrapper:
1#!/usr/bin/env python3
Then, instantiate a NiryoRosWrapper
instance
& calibrate the robot if needed:
1# Instantiate the ROS wrapper and initialize the ROS node
2robot = NiryoRosWrapper.init_with_node()
3
4# Calibrate if needed
5robot.calibrate_auto() # Only for Ned2
Then, we setup the connected tool
with update_tool()
1# Setup the tool
2robot.update_tool()
Now that our initialization is done, we can open the Gripper (or push air from the Vacuum pump)
with release_with_tool()
,
move to the picking pose via move()
& catch an object
with grasp_with_tool()
!
1# Open the tool
2robot.release_with_tool()
3
4# Move to pick pose
5robot.move(Pose(0.2, 0.1, 0.14, 0.0, math.pi, -math.pi / 2))
6
7# Pick
8robot.grasp_with_tool()
We can now move to the next pose, and place the object.
1# Move to place pose
2robot.move(Pose(0.2, -0.1, 0.14, 0.0, math.pi, -math.pi / 2))
3
4# Place
5robot.release_with_tool()