Skip to main content
Skip table of contents

MoveCircle.srv

Features

The robot moves along an arc to the target pos (pos2) via a waypoint (pos1) or to a specified angle from the current position in the task space.

Parameters

Parameter NameData TypeDefault ValueDefault Value

pos

std_msgs/Float64MultiArray[]

-

target[2][6]

  •   position list

vel

float64[2]

-

linear velocity, angular velocity

acc

float64[2]

-

linear acceleration, angular acceleration

time

float64

0.0

Reach time [sec]

radius

float64

0.0

Radius for blending

ref

int8

0

reference coordinate

  • MOVE_REFERENCE_BASE =0
  • MOVE_REFERENCE_TOOL=1
  • MOVE_REFERENCE_WORLD=2

mode

int8

0

Movement basis

  • MOVE_MODE_ABSOLUTE =0
  • MOVE_MODE_RELATIVE =1

angle1

float64

0.0

angle1

angle2

float64

0.0

angle2

blendType

int8

0

Reactive motion mode

  • BLENDING_SPEED_TYPE_DUPLICATE =0
  • BLENDING_SPEED_TYPE_OVERRIDE =1

syncType

int8

0

SYNC = 0

ASYNC = 1

Note

  • If an argument is inputted to vel (e.g., vel=[30, 0]), the input argument corresponds to the linear velocity of the motion while the angular velocity is determined proportionally to the linear velocity.
  • If an argument is inputted to acc (e.g., acc=[60, 0]), the input argument corresponds to the linear acceleration of the motion while the angular acceleration is determined proportionally to the linear acceleration.
  • If the time is specified, values are processed based on time, ignoring vel and acc.
  • The MOVE_REFERENCE_WORLD argument of ref is only available in M2.40 or later versions.
  • If the mod is MOVE_MODE_RELATIVE L, pos[0] and pos[1] are defined in the relative coordinate system of the previous pos. (pos[0] is the relative coordinate from the starting point while pos[1] is the relative coordinate from pos[0].)
  • If only one angle is inputted, the total rotated angle on the circular path is applied to the angle.
  • If two angle values are inputted, angle1 refers to the total rotating angle moving at a constant velocity on the circular path while angle2 refers to the rotating angle in the rotating section for acceleration and deceleration. In that case, the total moving angle angle1 + 2 X angle2 moves along the circular path.

Caution

If the following motion is blended with the conditions of blendType=

BLENDING_SPEED_TYPE_DUPLICATE and radius>0, the preceding motion can be terminated when the following motion is terminated while the remaining motion time determined by the remaining distance, velocity, and acceleration of the preceding motion is greater than the motion time of the following motion. Refer to the following image for more information.

Return

Parameter NameData TypeDefault ValueDefault Value

success

bool

-

True or False

JavaScript errors detected

Please note, these errors can depend on your browser setup.

If this problem persists, please contact our support.