Skip to content
Logo
Switch Manual
English
Download
  • Remote control API
    • Introduction
    • Data types and variables
    • Function description
    • Visual Studio Reference Remote interface library Description
    • Frequently Asked Questions
  • ROS development instructions
    • ROS environment Installation
    • Movelt Environment Installation
    • ROS robot development Kit Instructions
  • ROS2 development instructions
    • Basic Environment Installation of ROS2
    • Function package compilation and basic configuration
    • MoveIt Setup Assistant Environment Configuration
    • Configure robot connection
    • Running and Operating MoveIt Examples
    • Instruction control of the mechanical arm and related interface call instructions
    • Appendix
Develop
/
ROS2 Development Instructions
/
Instruction control of the mechanical arm and related interface call instructions

Instruction control of the mechanical arm and related interface call instructions#

Method 2: Controlling the Robotic Arm via Terminal Commands#

We can use RobotControl, RobotIoControl, and RobotMove commands to control the robotic arm’s power enablement, input/output, and movement respectively.

Important Notes:

  1. All commands require a space after the colon ‘:’

  2. Command parameters can be found in the relevant srv files under src/duco_msg/srv

Before using commands, complete the configuration process and package compilation described in previous chapters.

After preparing your environment, navigate to the src resource package directory, open a terminal, and execute commands.

Below are detailed explanations of available commands:

RobotControl#

Controls power and enablement state of the robotic system.

Input Parameters:

string command: Instruction

int8 arm_num: Arm number (set to 0)

bool block: Blocking instruction (false = non-blocking command that returns immediately)

string response: Return message (string)

Available Commands:

  1. poweron (Power on)

  2. enable (Enable movement)

  3. disable (Disable movement)

  4. poweroff (Power off)

Command Template:

1ros2 service call /duco_robot/robot_control duco_msg/srv/RobotControl "{command: '', arm_num: , block: }"

Command Example:

1ros2 service call /duco_robot/robot_control duco_msg/srv/RobotControl "{command: 'poweron', arm_num: 0, block: true}"
../../_images/RC.jpg

RobotIoControl#

Configures and retrieves general purpose I/O.

Input Parameters:

string command: Instruction

int8 arm_num: Arm number (set to 0)

int8 type: I/O type (0 = general I/O, 1 = tool I/O)

int8 port: I/O port (GEN I/O range 1-16, TOOL I/O range 0-1)

bool value: SetIO value

bool block: Blocking instruction (false = non-blocking)

string response: Return message (string)

Available Commands:

  1. setIo (Configure output)

  2. getIo (Retrieve input)

Command Template:

1ros2 service call /duco_robot/robot_io_control duco_msg/srv/RobotIoControl "{command: '', arm_num: , type: , port: , value: , block: }"

Command Example:

1ros2 service call /duco_robot/robot_io_control duco_msg/srv/RobotIoControl "{command: 'setIo', arm_num: 0, type: 0, port: 1, value: true, block: true}"
../../_images/RIC.jpg

RobotMove#

Controls robotic arm movement.

Input Parameters:

string command: Instruction

int8 arm_num: Arm number (set to 0)

float32[] p: Cartesian target position (x,y,z,rx,ry,rz)

float32[] q: Target joint angles in radians

float32 v: Max end-effector linear velocity (range: 0.01-5 m/s)

float32 a: Max end-effector linear acceleration (range: 0.01-∞ m/s²)

float32 r: Trajectory blend radius (meters, 0 = no blending)

string tool: Tool name (“default”)

string wobj: Workobject coordinate system (“default”)

bool block: Blocking instruction

string response: Return message (string)

Available Commands:

  1. movej: Joint space move to target joint angles

  2. movej2: Synchronized phase move to target joint angles

  3. movejpose: Joint space move to target end-effector position

  4. movejpose2: Synchronized phase move to target end-effector position

  5. movel: Linear Cartesian move to target pose

  6. movetcp: Linear incremental move in tool coordinate system

Command Template:

1ros2 service call /duco_robot/robot_move duco_msg/srv/RobotMove "{command: '', arm_num: , v: , a: , r: , tool: '', wobj: '', block: , q: [,,,,,], p: [,,,,,]}"

Command Example:

1ros2 service call /duco_robot/robot_move duco_msg/srv/RobotMove "{command: 'movejpose', arm_num: 0, v: 1, a: 1, r: 0, tool: 'default', wobj: 'default', block: true, q: [1,1,1,1,1,1], p: [0.49,0.14,0.44,-1.14,0,-1.57]}"
../../_images/RM.jpg

API Documentation#

RobotControl#

 1/**
 2 * @brief: Robot power on;
 3 * @param block: Whether to block. If false, it's a non-blocking command and will return immediately;
 4 * @return: Blocking execution returns the task end status, non-blocking execution returns the task ID;
 5 */
 6int32_t power_on(bool block)
 7// Example:
 8power_on(true)
 9
10/**
11 * @brief: Robot power off;
12 * @param block: Whether to block. If false, it's a non-blocking command and will return immediately;
13 * @return: Blocking execution returns the task end status, non-blocking execution returns the task ID;
14 */
15int32_t power_off(bool block)
16// Example:
17power_off(true)
18
19/**
20 * @brief: Robot enable;
21 * @param block: Whether to block. If false, it's a non-blocking command and will return immediately;
22 * @return: Blocking execution returns the task end status, non-blocking execution returns the task ID;
23 */
24int32_t enable(bool block) ;
25// Example:
26enable(true)
27
28/**
29 * @brief: Robot disable;
30 * @param block: Whether to block. If false, it's a non-blocking command and will return immediately;
31 * @return: Blocking execution returns the task end status, non-blocking execution returns the task ID;
32 */
33int32_t disable(bool block) ;
34// Example:
35disable(true)

RobotIoControl#

 1 /**
 2 * @brief: Read the high/low level of the robot end-effector's digital input port. Returns true for high level, false for low level;
 3 * @param num: End-effector digital input port number, range 1-2;
 4 * @return: true for high level, false for low level;
 5 */
 6bool get_tool_digital_in(int16_t num) ;
 7// Example:
 8get_tool_digital_in(1)
 9
10/**
11 * @brief: Read the high/low level of the control cabinet's user digital input port. Returns true for high level, false for low level;
12 * @param num: Control cabinet input port number, range 1-16;
13 * @return: true for high level, false for low level;
14 */
15bool get_standard_digital_in(int16_t num) ;
16// Example:
17get_standard_digital_in(1)
18
19 /**
20 * @brief: Set end-effector digital output;
21 * @param num:   End-effector digital output port number, range 1-2;
22 * @param value: true for high level, false for low level;
23 * @param block: Whether to block. If false, it's a non-blocking command and will return immediately;
24 * @return: Blocking execution returns the task end status, non-blocking execution returns the task ID;
25 */
26int32_t set_tool_digital_out(int16_t num, bool value, bool block) ;
27// Example:
28set_tool_digital_out(1, true, true)
29
30/**
31 * @brief: Control the high/low level of the control cabinet's digital output port;
32 * @param num:   Control cabinet output port number, range 1-16;
33 * @param value: true for high level, false for low level;
34 * @param block: Whether to block. If false, it's a non-blocking command and will return immediately;
35 * @return: Blocking execution returns the task end status, non-blocking execution returns the task ID;
36 */
37int32_t set_standard_digital_out(int16_t num, bool value, bool block) ;
38// Example:
39set_standard_digital_out(1, true, true)

RobotMove#

  1 /**
  2 * @brief: Move robot from current state to target joint angles via joint motion;
  3 * @param: joints_list Target joint angles for joints 1-6, unit: rad;
  4 * @param v: Joint angular velocity, unit: percentage of system set speed %, range (0,100];
  5 * @param a: Joint angular acceleration, unit: percentage of system set acceleration %, range (0,100];
  6 * @param: r: Blend radius, unit: percentage of maximum system blend radius %, default 0 (no blending), range [0,50);
  7 * @param block: Whether to block. If false, it's a non-blocking command and will return immediately;
  8 * @param op: Optional parameter;
  9 * @param def_acc: Whether to use system default acceleration. false uses custom acceleration, true uses system auto-planned acceleration. Optional, default false;
 10 * @return: Blocking execution: returns task end status (Finished if no blending, Interrupt if blended);
 11 *         Non-blocking execution: returns task ID for querying execution status via get_noneblock_taskstate(id);
 12 */
 13int32_t movej(const std::vector<double> & joints_list, double v, double a, double r, bool block, const OP &op = _op, bool def_acc = false) ;
 14// Example:
 15movej([1,1,1,1,1,1], 1, 1, 0, true)
 16
 17/**
 18 * @brief: Move robot from current state to target joint angles via joint motion;
 19 * @param: joints_list Target joint angles for joints 1-6, unit: rad;
 20 * @param v: Joint angular velocity, range [0.01*PI/180, 1.25*PI], unit: rad/s;
 21 * @param a: Joint angular acceleration, range [0.01*PI/180, 12.5*PI], unit: rad/s²;
 22 * @param r: Blend radius, unit: m, default 0 (no blending). Value >0 indicates blending with next motion;
 23 * @param block: Whether to block. If false, it's a non-blocking command and will return immediately;
 24 * @param op: Optional parameter;
 25 * @param def_acc: Whether to use system default acceleration. false uses custom acceleration, true uses system auto-planned acceleration. Optional, default false;
 26 * @return: Blocking execution: returns task end status (Finished if no blending, Interrupt if blended);
 27 *         Non-blocking execution: returns task ID for querying execution status via get_noneblock_taskstate(id);
 28 */
 29int32_t movej2(const std::vector<double> & joints_list, double v, double a, double r, bool block, const OP &op = _op, bool def_acc = false) ;
 30// Example:
 31movej2([1,1,1,1,1,1], 1, 1, 0, true)
 32
 33 /**
 34 * @brief: Move robot via joint motion to target end-effector pose;
 35 * @param p: Target end-effector pose, position unit: m, orientation as Rx,Ry,Rz in rad;
 36 * @param v: Joint angular velocity, unit: percentage of system set speed %, range (0,100];
 37 * @param a: Joint acceleration, unit: percentage of system set acceleration %, range (0,100];
 38 * @param r: Blend radius, unit: percentage of maximum system blend radius %, default 0 (no blending), range [0,50);
 39 * @param q_near: Nearby joint angles for inverse kinematics solution. Uses current position if empty;
 40 * @param tool:   Tool coordinate system to use. Defaults to current tool if empty;
 41 * @param wobj:   Workpiece coordinate system to use. Defaults to current wobj if empty;
 42 * @param block:  Whether to block. If false, it's a non-blocking command and will return immediately;
 43 * @param op: Optional parameter;
 44 * @param def_acc: Whether to use system default acceleration. false uses custom acceleration, true uses system auto-planned acceleration. Optional, default false;
 45 * @return: Blocking execution: returns task end status (Finished if no blending, Interrupt if blended);
 46 *         Non-blocking execution: returns task ID for querying execution status via get_noneblock_taskstate(id);
 47 */
 48int32_t movej_pose(const std::vector<double> & p, double v, double a, double r, const std::vector<double> & q_near, const std::string& tool, const std::string& wobj, bool block, const OP &op = _op, bool def_acc = false) ;
 49// Example:
 50movej_pose([0.49,0.14,0.44,-1.14,0,-1.57], 1, 1, 0, [1,1,1,1,1,1], "default", "default", true)
 51
 52/**
 53 * @brief: Move robot via joint motion to target end-effector pose;
 54 * @param p: Target end-effector pose, position unit: m, orientation as Rx,Ry,Rz in rad;
 55 * @param v: Joint angular velocity, range [0.01*PI/180, 1.25*PI], unit: rad/s;
 56 * @param a: Joint acceleration, range [0.01*PI/180, 12.5*PI], unit: rad/s²;
 57 * @param r: Blend radius, unit: m, default 0 (no blending). Value >0 indicates blending with next motion;
 58 * @param q_near: Nearby joint angles for inverse kinematics solution. Uses current position if empty;
 59 * @param tool:   Tool coordinate system to use. Defaults to current tool if empty;
 60 * @param wobj:   Workpiece coordinate system to use. Defaults to current wobj if empty;
 61 * @param block:  Whether to block. If false, it's a non-blocking command and will return immediately;
 62 * @param op: Optional parameter;
 63 * @param def_acc: Whether to use system default acceleration. false uses custom acceleration, true uses system auto-planned acceleration. Optional, default false;
 64 * @return: Blocking execution: returns task end status (Finished if no blending, Interrupt if blended);
 65 *         Non-blocking execution: returns task ID for querying execution status via get_noneblock_taskstate(id);
 66 */
 67int32_t movej_pose2(const std::vector<double> & p, double v, double a, double r, const std::vector<double> & q_near, const std::string& tool, const std::string& wobj, bool block, const OP &op = _op, bool def_acc = false) ;
 68// Example:
 69movej_pose2([0.49,0.14,0.44,-1.14,0,-1.57], 1, 1, 0, [1,1,1,1,1,1], "default", "default", true)
 70
 71/**
 72 * @brief: Move robot end-effector along a straight path to target pose;
 73 * @param p: Target end-effector pose, position unit: m, orientation as Rx,Ry,Rz in rad;
 74 * @param v: End-effector velocity, range [0.00001, 5], unit: m/s;
 75 * @param a: End-effector acceleration, range [0.00001, ∞], unit: m/s²;
 76 * @param r: Blend radius, unit: m, default 0 (no blending). Value >0 indicates blending with next motion;
 77 * @param q_near: Nearby joint angles for inverse kinematics solution. Uses current position if empty;
 78 * @param tool:   Tool coordinate system to use. Defaults to current tool if empty;
 79 * @param wobj:   Workpiece coordinate system to use. Defaults to current wobj if empty;
 80 * @param block:  Whether to block. If false, it's a non-blocking command and will return immediately;
 81 * @param op: Optional parameter;
 82 * @param def_acc: Whether to use system default acceleration. false uses custom acceleration, true uses system auto-planned acceleration. Optional, default false;
 83 * @return: Blocking execution: returns task end status (Finished if no blending, Interrupt if blended);
 84 *         Non-blocking execution: returns task ID for querying execution status via get_noneblock_taskstate(id);
 85 */
 86int32_t movel(const std::vector<double> & p, double v, double a, double r, const std::vector<double> & q_near, const std::string& tool = "default", const std::string& wobj = "default", bool block = true, const OP &op = _op, bool def_acc = false) ;
 87// Example:
 88movel([0.49,0.14,0.44,-1.14,0,-1.57], 1, 1, 0, [1,1,1,1,1,1])
 89
 90/**
 91 * @brief: Move robot along a straight path in tool coordinate system by specified offset;
 92 * @param pose_offset: Pose offset in tool coordinate system;
 93 * @param v: Linear velocity, range [0.00001, 5], unit: m/s (if x,y,z all 0, converted proportionally to angular velocity);
 94 * @param a: Acceleration, range [0.00001, ∞], unit: m/s²;
 95 * @param r: Blend radius, unit: m, default 0 (no blending). Value >0 indicates blending with next motion;
 96 * @param tool:   Tool coordinate system to use. Defaults to current tool if empty;
 97 * @param block:  Whether to block. If false, it's a non-blocking command and will return immediately;
 98 * @param op: Optional parameter;
 99 * @param def_acc: Whether to use system default acceleration. false uses custom acceleration, true uses system auto-planned acceleration. Optional, default false;
100 * @return: Blocking execution: returns task end status (Finished if no blending, Interrupt if blended);
101 *         Non-blocking execution: returns task ID for querying execution status via get_noneblock_taskstate(id);
102 */
103int32_t tcp_move(const std::vector<double> & pose_offset, double v, double a, double r, const std::string& tool, bool block, const OP &op = _op, bool def_acc = false) ;
104// Example:
105movetcp([0.49,0.14,0.44,-1.14,0,-1.57], 1, 1, 0, "default", "default")
Running and Operating MoveIt Examples
Appendix

On this page

  • Method 2: Controlling the Robotic Arm via Terminal Commands
    • RobotControl
    • RobotIoControl
    • RobotMove
  • API Documentation
    • RobotControl
    • RobotIoControl
    • RobotMove
Copyright ©2024 DUCO Robots CO., LTD.