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 task space input in pos_list.
The input velocity/acceleration means the maximum velocity/acceleration in the path and the constant velocity motion is performed with the input velocity according to the condition if the option for the constant speed motion is selected.
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[2] |
- |
linear velocity, angular velocity |
|
acc |
float64[2] |
- |
linear acceleration, angular acceleration |
|
time |
float64 |
0.0 |
Reach time [sec] |
|
ref |
int8 |
0 |
MOVE_REFERENCE_BASE =0 MOVE_REFERENCE_TOOL=1 MOVE_REFERENCE_WORLD=2 |
|
mode |
int8 |
0 |
MOVE_MODE_ABSOLUTE =0 MOVE_MODE_RELATIVE =1 |
|
opt |
int8 |
0 |
SPLINE_VELOCITY_OPTION_DEFAULT=0 SPLINE_VELOCITY_OPTION_CONST=1 |
|
syncType |
int8 |
0 |
SYNC = 0 ASYNC = 1 |
-
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, each pos in the pos_list is defined in the relative coordinate of the previous pos. (If positiolist=[p1, p2, ...,p(n-1), p(n)], p1 is the relative angle of the starting point while p(n) is the relative coordinate of p(n-1).)
-
This service does not support online blending of previous and subsequent motions.
The constant velocity motion according to the distance and velocity between the waypoints cannot be used if the “opt= SPLINE_VELOCITY_OPTION_CONST” option (constant velocity option) is selected, and the motion is automatically switched to the variable velocity motion (opt= SPLINE_VELOCITY_OPTION_DEFAULT) in that case.
Return
|
Return Name |
Data Type |
Default Value |
Description |
|---|---|---|---|
|
success |
bool |
- |
True or False |