Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Paul Rouanet
ros2_control_bolt
Commits
5557a19e
Commit
5557a19e
authored
Jul 21, 2021
by
Paul Rouanet
Browse files
Modif on calibration part of start()
parent
714fe52c
Changes
1
Show whitespace changes
Inline
Side-by-side
ros2_control_bolt/src/system_bolt.cpp
View file @
5557a19e
...
...
@@ -435,10 +435,14 @@ return_type SystemBoltHardware::start()
robot_
->
Start
();
// Calibration part
double
Kp
=
5.
;
double
Kd
=
0.05
;
double
T
=
2.0
;
double
dt
=
0.001
;
std
::
vector
<
CalibrationMethod
>
directions
=
{
AUTO
,
AUTO
,
AUTO
,
AUTO
,
AUTO
,
AUTO
};
auto
calib_ctrl
=
std
::
make_shared
<
JointCalibrator
>
(
joints_
,
directions
,
position_offsets_
,
5.
,
0.05
,
2.
,
0.001
);
joints_
,
directions
,
position_offsets_
,
Kp
,
Kd
,
T
,
dt
);
bool
is_calibrated
=
false
;
std
::
chrono
::
time_point
<
std
::
chrono
::
system_clock
>
last
=
std
::
chrono
::
system_clock
::
now
();
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment