forked from h2r/baxter_h2r_packages
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathVelocityJointTrajectoryActionServer.cfg
executable file
·83 lines (73 loc) · 3.04 KB
/
VelocityJointTrajectoryActionServer.cfg
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
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
#!/usr/bin/env python
# Copyright (c) 2013-2014, Rethink Robotics
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# 1. Redistributions of source code must retain the above copyright notice,
# this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
# 3. Neither the name of the Rethink Robotics nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
from dynamic_reconfigure.parameter_generator_catkin import (
ParameterGenerator,
double_t,
)
gen = ParameterGenerator()
gen.add(
'goal_time', double_t, 0,
"Amount of time (s) controller is permitted to be late achieving goal",
5.0, 0.0, 120.0,
)
gen.add(
'stopped_velocity_tolerance', double_t, 0,
"Maximum velocity (m/s) at end of trajectory to be considered stopped",
-1.0, -1.0, 1.0,
)
joints = (
'left_s0', 'left_s1', 'left_e0', 'left_e1', 'left_w0', 'left_w1',
'left_w2', 'right_s0', 'right_s1', 'right_e0', 'right_e1', 'right_w0',
'right_w1', 'right_w2',
)
params = ('_goal', '_trajectory', '_kp', '_ki', '_kd',)
msg = (
" - maximum final error",
" - maximum error during trajectory execution",
" - Kp proportional control gain",
" - Ki integral control gain",
" - Kd derivative control gain",
)
min = (-1.0, -1.0, 0.0, 0.0, 0.0,)
default = (-0.1, -0.1, 2.0, 0.0, 0.0,)
max = (3.0, 3.0, 500.0, 100.0, 100.0,)
for idx, param in enumerate(params):
if idx < 2:
for joint in joints:
gen.add(
joint + param, double_t, 0, joint + msg[idx],
default[idx], min[idx], max[idx]
)
for joint in joints:
for idx, param in enumerate(params):
if idx >= 2:
gen.add(
joint + param, double_t, 0, joint + msg[idx],
default[idx], min[idx], max[idx]
)
exit(gen.generate('baxter_interface', '', 'VelocityJointTrajectoryActionServer'))