Breadcrumbs

MoveSplineJoint.srv

Features

The robot moves along a spline curve path that connects the current position to the target position (the last waypoint in position list) via the waypoints of the joint space input in position list.

The input velocity/acceleration means the maximum velocity/acceleration in the path, and the acceleration and deceleration during the motion are determined according to the position of the waypoint.

Parameters

Parameter Name

Data Type

Default Value

Description

pos

std_msgs/Float64MultiArray[]

-

target pos [100][6]

max = 100

posCnt

int8

-

Count of target pos

vel

float64

-

velocity

acc

float64

-

acceleration

time

float64

0.0

Reach time [sec]

mode

int8

0

Movement basis

  • MOVE_MODE_ABSOLUTE =0

  • MOVE_MODE_RELATIVE =1

syncType

int8

0

SYNC = 0

ASYNC = 1


  • If the time is specified, values are processed based on time, ignoring vel and acc.

  • If the mod is MOVE_MODE_RELATIVE, each pos in the pos_list is defined in the relative coordinate of the previous pos. (If pos_list=[q1, q2, ...,q(n-1), q(n)], q1 is the relative angle of the starting point while q(n) is the relative coordinate of q(n-1).)

  • This service does not support online blending of previous and subsequent motions.

Return

Return Name

Data Type

Default Value

Default Value

success

bool

-

True or False