The SlaveMode control modality allows to control DENSO robots by sending the whole trajectory of the robotic arm. The trajectory must be generated by an external motion planner (e.g. MoveIt2), and target points must be sent to the robot controller.
NOTE: The minimum required control frequency is 125 Hz (1 target position each 8 ms).
When connecting to a real robot, please be sure to complete the steps for WINCAPS III preparation as described here.
When connecting to a real robot, please be sure to complete the steps for robot preparation as described here.
The main launch file that starts the application is in the denso_robot_bringup
package.
- COBOTTA robot:
ros2 launch denso_robot_bringup denso_robot_bringup.launch.py model:=cobotta sim:=false ip_address:=192.168.0.1 send_format:=0 recv_format:=2
- NOT COBOTTA robots (e.g. VS-060 robot):
ros2 launch denso_robot_bringup denso_robot_bringup.launch.py model:=vs060 sim:=false ip_address:=192.168.0.1 send_format:=256 recv_format:=258
The main launch file that starts the application is in the denso_robot_bringup
package:
ros2 launch denso_robot_bringup denso_robot_bringup.launch.py model:=<robot_model> sim:=false ip_address:=<robot_ip_address> send_format:=<send_format_value> recv_format:=<recv_format_value>
The arguments for launch files can be listed using:
ros2 launch denso_robot_bringup denso_robot_bringup.launch.py --show-args
The most relevant arguments are the following:
model
(mandatory) - the model of the DENSO robot (COBOTTA, VS-060, etc.). In the original DENSO ROS2 stack 2 robot models are already available ( "cobotta" , "vs060"). To use other robot types, see the ROS2Converter page (under construction) for creating the URDF model and the associated MoveIt2 configuration packageip_address
(mandatory) - IP address of the robotsim
(default: true) - whether the robot is simulated (Gazebo simulator) or an RC8 controller is connected (either WINCAPS III-simulated or real controller)send_format
(default: 288) - parameter to write Hand I/O, Mini I/O or User I/O signals (not considered ifsim:=true
). When Connecting to a COBOTTA robot assign value "0" (no IO configuration)recv_format
(default: 292) - parameter to read Hand I/O, Mini I/O or User I/O signals (not considered ifsim:=true
). When Connecting to a COBOTTA robot assign value "2" (no IO configuration)bcap_slave_control_cycle_msec
(default: 8.0) - DENSO robot control cycle [ms] (not considered ifsim:=true
)
DENSO ROS2 stack (simulation) |
---|
The send_format parameter can be used for write Hand I/O, Mini I/O or User I/O. Following table shows the details of the send_format parameter.
Value | I/O |
---|---|
0 | None |
32 | Hand I/O (Port 64 to 71) |
256 | Mini I/O (Port 16 to 31) |
288 | Hand I/O and Mini I/O |
512 | User I/O (Port 128 or after) |
544 | Hand I/O and User I/O |
The recv_format parameter can be used for write Hand I/O, Mini I/O or User I/O. Following table shows the details of the recv_format parameter.
Value | I/O |
---|---|
0 | None |
34 | Hand I/O (Port 48 to 55 and 64 to 71) |
258 | Mini I/O (Port 0 to 31) |
290 | Hand I/O and Mini I/O |
514 | User I/O (Port 128 or after) |
546 | Hand I/O and User I/O |
When setting the send_format and recv_format parameters, proper subscribers and publishers are launched.
When assigning values 256 or 288 to the send_format parameter, a subscriber named "/${model}/Write_MiniIO" is launched. The subscriber's format is std_msgs/msg/UInt32. The least significant bit means I/O port 0 and the most significant bit means port 31.
When assigning values 258, 290 or 770 to the recv_format parameter, a publisher named "/${model}/Read_MiniIO" is launched. The publisher's format is std_msgs/msg/UInt32. The least significant bit means I/O port 0 and the most significant bit means port 31.
When assigning values 32, 288 or 544 to the send_format parameter, a subscriber named "/${model}/Write_HandIO" is launched. The subscriber's format is std_msgs/msg/UInt32. The least significant bit means I/O port 48 and the most significant bit means port 79.
When assigning values 34, 290 or 546 to the recv_format parameter, a publisher named "/${model}/Read_HandIO" is launched. The publisher's format is std_msgs/msg/UInt32. The least significant bit means I/O port 48 and the most significant bit means port 79.
When assigning values 512 or 544 to the send_format parameter, a subscriber named "/${model}/Write_SendUserIO" is launched. The subscriber's format is denso_robot_core_interfaces/UserIO. The offset parameter means the beginning of user I/O ports to write. It has to be greater than 127, and be multiple of 8. The size parameter means the length of the value array. The value array means the I/O states to write. The least significant bit of the first element means I/O port ${offset}+0, and the most significant bit means port ${offset}+7, and so on.
When assigning values 514, 546 or 770 to the recv_format parameter, a subscriber named "/${model}/Write_RecvUserIO" and a publisher named "/${model}/Read_RecvUserIO" are launched. The subscriber's and publisher's format are denso_robot_core_interfaces/UserIO. The offset parameter means the beginning of user I/O ports to read. It has to be greater than 127, and be multiple of 8. The size parameter means the number of I/O ports to read. It has to be the value dividing the number of I/O ports to read by 8. For example, if you want to read 8 I/O ports, you should set 1 as this parameter. The value array does not use in the "/${model}/Write_RecvUserIO". In the "/${model}/Read_RecvUserIO", it means the I/O states to have had read. The least significant bit of the first element means I/O port ${offset}+0, and the most significant bit means port ${offset}+7, and so on.
To launch the MoveIt2 demo node for pick-and-place application in case of 6DOF robot arms (e.g. COBOTTA, VS060, etc.) run the following command:
ros2 launch denso_robot_moveit_demo denso_robot_moveit_pickandplace.launch.py model:=<robot_model> scale_factor:=<0.01 - 1.0> num_cycles:=<number_of_pick_and_place_cycles>
The arguments for launch files can be listed using:
ros2 launch denso_robot_moveit_demo denso_robot_moveit_pickandplace.launch.py --show-args
The most relevant arguments are the following:
model
(mandatory) - the model of the DENSO robot (COBOTTA, VS-060, etc.). In the original DENSO ROS2 stack 2 robot models are already available ( "cobotta" , "vs060"). To use other robot types, see the ROS2Converter page (under construction) for creating the URDF model and the associated MoveIt2 configuration packagescale_factor
(default: 0.1) - motion speed [0.01-1.0]num_cycles
(default: 1) - number of times to repeat the pick-and-place cycle
To launch the MoveIt2 demo node for pick-and-place application in case of 4DOF robot arms (SCARA robot arms) run the following command:
Please note that for the moment SCARA robots can only be controlled sending target positions in joint space (no Inverse Kinematics plugin has been developed so far) !!
ros2 launch denso_robot_moveit_demo denso_robot_moveit_pickandplace_scara.launch.py model:=<robot_model> scale_factor:=<0.01 - 1.0> num_cycles:=<number_of_pick_and_place_cycles>
The arguments for launch files can be listed using:
ros2 launch denso_robot_moveit_demo denso_robot_moveit_pickandplace_scara.launch.py --show-args
The most relevant arguments are the following:
model
(mandatory) - the model of the DENSO SCARA robot. Description files for SCARA robots (URDF model and associated MoveIt2 configuration package) must be created using the ROS2Converter Tool (under construction)scale_factor
(default: 0.1) - motion speed [0.01-1.0]num_cycles
(default: 1) - number of times to repeat the pick-and-place cycle
To launch the MoveIt2 demo node run the following command:
ros2 launch denso_robot_moveit_demo denso_robot_moveit_demo.launch.py model:=<robot_model> scale_factor:=<0.01 - 1.0>
The arguments for launch files can be listed using:
ros2 launch denso_robot_moveit_demo denso_robot_moveit_demo.launch.py --show-args
The most relevant arguments are the following:
model
(mandatory) - the model of the DENSO robot (COBOTTA, VS-060, etc.). In the original DENSO ROS2 stack 2 robot models are already available ( "cobotta" , "vs060"). To use other robot types, see the ROS2Converter page (under construction) for creating the URDF model and the associated MoveIt2 configuration packagescale_factor
(default: 0.1) - motion speed [0.01-1.0]
Topics used for reading and writing I/O lines are (in case of model:=cobotta
, send_format:=256
and recv_format:=258
- MiniIO configuration for COBOTTA robot model):
/cobotta/Read_MiniIO
/cobotta/Write_MiniIO
-
To read I/O lines:
ros2 topic echo /cobotta/Read_MiniIO
Output will be (I/O lines are converted to UInt value):
data: 6881280 --- data: 6881280 ---
-
To write I/O lines (I/O lines are converted to UInt value):
ros2 topic pub --once /cobotta/Write_MiniIO std_msgs/msg/UInt32 "data: 23658496"