Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
D
dynamic_graph_bridge
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Container Registry
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Stack Of Tasks
dynamic_graph_bridge
Commits
17a992fb
Commit
17a992fb
authored
2 years ago
by
Florent Lamiraux
Browse files
Options
Downloads
Patches
Plain Diff
[SotLoader] Update to recent modifications in sot-core.
parent
32055950
No related branches found
Branches containing commit
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
include/dynamic_graph_bridge/sot_loader.hh
+1
-1
1 addition, 1 deletion
include/dynamic_graph_bridge/sot_loader.hh
src/sot_loader.cpp
+6
-5
6 additions, 5 deletions
src/sot_loader.cpp
with
7 additions
and
6 deletions
include/dynamic_graph_bridge/sot_loader.hh
+
1
−
1
View file @
17a992fb
...
@@ -88,7 +88,7 @@ class SotLoader : public SotLoaderBasic {
...
@@ -88,7 +88,7 @@ class SotLoader : public SotLoaderBasic {
// \brief Compute one iteration of control.
// \brief Compute one iteration of control.
// Basically calls fillSensors, the SoT and the readControl.
// Basically calls fillSensors, the SoT and the readControl.
void
oneIteration
();
void
oneIteration
(
const
double
&
period
);
// \brief Fill the sensors value for the SoT.
// \brief Fill the sensors value for the SoT.
void
fillSensors
(
std
::
map
<
std
::
string
,
dgs
::
SensorValues
>
&
sensorsIn
);
void
fillSensors
(
std
::
map
<
std
::
string
,
dgs
::
SensorValues
>
&
sensorsIn
);
...
...
This diff is collapsed.
Click to expand it.
src/sot_loader.cpp
+
6
−
5
View file @
17a992fb
...
@@ -59,8 +59,9 @@ struct DataToLog {
...
@@ -59,8 +59,9 @@ struct DataToLog {
void
workThreadLoader
(
SotLoader
*
aSotLoader
)
{
void
workThreadLoader
(
SotLoader
*
aSotLoader
)
{
ros
::
Rate
rate
(
1000
);
// 1 kHz
ros
::
Rate
rate
(
1000
);
// 1 kHz
double
periodd
(
1e-3
);
if
(
ros
::
param
::
has
(
"/sot_controller/dt"
))
{
if
(
ros
::
param
::
has
(
"/sot_controller/dt"
))
{
double
periodd
;
ros
::
param
::
get
(
"/sot_controller/dt"
,
periodd
);
ros
::
param
::
get
(
"/sot_controller/dt"
,
periodd
);
rate
=
ros
::
Rate
(
1
/
periodd
);
rate
=
ros
::
Rate
(
1
/
periodd
);
}
}
...
@@ -80,7 +81,7 @@ void workThreadLoader(SotLoader *aSotLoader) {
...
@@ -80,7 +81,7 @@ void workThreadLoader(SotLoader *aSotLoader) {
if
(
!
paused
)
{
if
(
!
paused
)
{
time
=
ros
::
Time
::
now
();
time
=
ros
::
Time
::
now
();
aSotLoader
->
oneIteration
();
aSotLoader
->
oneIteration
(
periodd
);
ros
::
Duration
d
=
ros
::
Time
::
now
()
-
time
;
ros
::
Duration
d
=
ros
::
Time
::
now
()
-
time
;
dataToLog
.
record
((
time
-
timeOrigin
).
toSec
(),
d
.
toSec
());
dataToLog
.
record
((
time
-
timeOrigin
).
toSec
(),
d
.
toSec
());
...
@@ -200,15 +201,15 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) {
...
@@ -200,15 +201,15 @@ void SotLoader::readControl(map<string, dgs::ControlValues> &controlValues) {
void
SotLoader
::
setup
()
{
void
SotLoader
::
setup
()
{
fillSensors
(
sensorsIn_
);
fillSensors
(
sensorsIn_
);
sotController_
->
setupSetSensors
(
sensorsIn_
);
sotController_
->
setupSetSensors
(
sensorsIn_
);
sotController_
->
getControl
(
controlValues_
);
sotController_
->
getControl
(
controlValues_
,
0
);
readControl
(
controlValues_
);
readControl
(
controlValues_
);
}
}
void
SotLoader
::
oneIteration
()
{
void
SotLoader
::
oneIteration
(
const
double
&
period
)
{
fillSensors
(
sensorsIn_
);
fillSensors
(
sensorsIn_
);
try
{
try
{
sotController_
->
nominalSetSensors
(
sensorsIn_
);
sotController_
->
nominalSetSensors
(
sensorsIn_
);
sotController_
->
getControl
(
controlValues_
);
sotController_
->
getControl
(
controlValues_
,
period
);
}
catch
(
std
::
exception
&
)
{
}
catch
(
std
::
exception
&
)
{
throw
;
throw
;
}
}
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment