-
Notifications
You must be signed in to change notification settings - Fork 164
/
Copy pathMoveVelocity.srv
34 lines (26 loc) · 1.38 KB
/
MoveVelocity.srv
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
# request: command specification for velocity executions.
# Units:
# joint space/angles: radian/s
# Cartesian space: mm/s, radian/s.
# velocities: the velocity list of the joints/tcp
# For velo_move_joint_timed service: [joint1_velocity, ..., joint7_velocity]
# For velo_move_line_timed service: [x_velocity, y_velocity, z_velocity, rx_velocity, ry_velocity, rz_velocity (axis-angle)]
float32[] speeds
# is_sync: this is special for velo_move_joint service, meaning whether all joints accelerate and decelerate synchronously, true for yes, false for no.
# avaiable for service velo_move_joint_timed
bool is_sync
# is_tool_coord: this is special for velo_move_line service, meaning whether motion is in tool coordinate(true) or not(false)
# avaiable for service velo_move_line_timed
bool is_tool_coord
# the maximum duration of the speed, over this time will automatically set the speed to 0
# duration > 0: seconds, indicates the maximum number of seconds that this speed can be maintained
# duration == 0: always effective, will not stop automativally
# duration < 0: default value, only used to be compatible with the old protocol, equivalent to 0
# avaiable for firmware_version >= 1.8.0
float32 duration
---
# response:
# ret is 0 for successful execution and others for errors or warnings occured
# message is a string returned by function, indicating execution status.
int16 ret
string message