-
Notifications
You must be signed in to change notification settings - Fork 134
/
Copy pathGetCartesianPath.srv
64 lines (49 loc) · 2.33 KB
/
GetCartesianPath.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
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
# Define the frame for the specified waypoints
Header header
# The start at which to start the Cartesian path
RobotState start_state
# Mandatory name of group to compute the path for
string group_name
# Optional name of IK link for which waypoints are specified.
# If not specified, the tip of the group (which is assumed to be a chain)
# is assumed to be the link
string link_name
# A sequence of waypoints to be followed by the specified link,
# while moving the specified group, such that the group moves only
# in a straight line between waypoints
geometry_msgs/Pose[] waypoints
# The maximum distance (in Cartesian space) between consecutive points
# in the returned path. This must always be specified and > 0
float64 max_step
# If jump_threshold is set > 0, it acts as a scaling factor that is used to
# filter out large relative joint-space jumps in the generated Cartesian path.
# To this end, the average joint-space distance between consecutive waypoints
# is computed. If any joint-space distance is larger than this average distance
# by a factor of jump_threshold_factor, this step is considered a jump
# and the returned path is truncated before the step.
float64 jump_threshold
# If prismatic_jump_threshold or revolute_jump_threshold are set > 0, then for
# all active prismatic or revolute joints, the joint-space difference between
# consecutive waypoints is compared to the respective absolute threshold.
# If any threshold is exceeded, this step is considered a jump and the returned path
# is truncated before the step.
float64 prismatic_jump_threshold
float64 revolute_jump_threshold
# Set to true if collisions should be avoided when possible
bool avoid_collisions
# Specify additional constraints to be met by the Cartesian path
Constraints path_constraints
# Maximum cartesian speed for the given link.
# If max_cartesian_speed <= 0 the trajectory is not modified.
string cartesian_speed_limited_link
float64 max_cartesian_speed # m/s
---
# The state at which the computed path starts
RobotState start_state
# The computed solution trajectory, for the desired group, in configuration space
RobotTrajectory solution
# If the computation was incomplete, this value indicates the fraction of the path
# that was in fact computed (number of waypoints traveled through)
float64 fraction
# The error code of the computation
MoveItErrorCodes error_code