Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
P
panda_mqtt_connector
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
Package registry
Container registry
Model registry
Operate
Environments
Terraform modules
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
This is an archived project. Repository and other project resources are read-only.
Show more breadcrumbs
CeTI
ROS
ROS Packages
panda_mqtt_connector
Commits
77c2a669
Commit
77c2a669
authored
4 years ago
by
Johannes Mey
Browse files
Options
Downloads
Patches
Plain Diff
publish smooth and exact velocity
parent
cbd40bbc
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
src/acceleration_publisher.cpp
+40
-27
40 additions, 27 deletions
src/acceleration_publisher.cpp
with
40 additions
and
27 deletions
src/acceleration_publisher.cpp
+
40
−
27
View file @
77c2a669
...
@@ -10,9 +10,39 @@
...
@@ -10,9 +10,39 @@
#include
<tf2_ros/transform_listener.h>
#include
<tf2_ros/transform_listener.h>
#include
<panda_mqtt_connector/StampedVelocity.h>
#include
<panda_mqtt_connector/StampedVelocity.h>
void
publishVelocity
(
const
ros
::
Publisher
&
vel_smoothed
,
const
tf2_ros
::
Buffer
&
tfBuffer
,
const
ros
::
Duration
&
dt
);
namespace
acceleration_publisher
{
namespace
acceleration_publisher
{
}
}
void
publishVelocity
(
const
ros
::
Publisher
&
vel_smoothed
,
const
tf2_ros
::
Buffer
&
tfBuffer
,
const
ros
::
Duration
&
dt
)
{
geometry_msgs
::
TransformStamped
transformStamped
;
try
{
ros
::
Time
now
=
ros
::
Time
::
now
();
ros
::
Time
past
=
now
-
dt
;
transformStamped
=
tfBuffer
.
lookupTransform
(
"panda_hand"
,
now
,
"panda_hand"
,
past
,
"world"
,
ros
::
Duration
(
1.0
));
double
dx
=
transformStamped
.
transform
.
translation
.
x
;
double
dy
=
transformStamped
.
transform
.
translation
.
y
;
double
dz
=
transformStamped
.
transform
.
translation
.
z
;
double
smoothed_velocity
=
sqrt
(
dx
*
dx
+
dy
*
dz
+
dz
*
dz
)
/
dt
.
toSec
();
if
(
!
isnan
(
smoothed_velocity
))
{
panda_mqtt_connector
::
StampedVelocity
msg
;
msg
.
header
.
stamp
=
now
-
(
dt
*
.5
);
msg
.
velocity
=
smoothed_velocity
;
vel_smoothed
.
publish
(
msg
);
}
}
catch
(
tf2
::
TransformException
&
ex
)
{
ROS_WARN
(
"%s"
,
ex
.
what
());
ros
::
Duration
(
1.0
).
sleep
();
}
}
/**
/**
* The main method of the ROS node
* The main method of the ROS node
*
*
...
@@ -24,43 +54,26 @@ int main(int argc, char **argv) {
...
@@ -24,43 +54,26 @@ int main(int argc, char **argv) {
ros
::
NodeHandle
n
(
"panda_mqtt_connector"
);
ros
::
NodeHandle
n
(
"panda_mqtt_connector"
);
ros
::
Publisher
vel
=
n
.
advertise
<
panda_mqtt_connector
::
StampedVelocity
>
(
"velocity"
,
10
);
ros
::
Publisher
vel
=
n
.
advertise
<
panda_mqtt_connector
::
StampedVelocity
>
(
"velocity"
,
10
);
ros
::
Publisher
vel_smoothed
=
n
.
advertise
<
panda_mqtt_connector
::
StampedVelocity
>
(
"velocity_smoothed"
,
10
);
tf2_ros
::
Buffer
tfBuffer
;
tf2_ros
::
Buffer
tfBuffer
;
tf2_ros
::
TransformListener
tfListener
(
tfBuffer
);
tf2_ros
::
TransformListener
tfListener
(
tfBuffer
);
// the duration to compute the velocity
// the duration to compute the velocity
ros
::
Duration
dt
{
1
,
500000
};
// 0,10000
ros
::
Duration
dt
{
0
,
10000000
};
// 0,10000
ros
::
Duration
dt_smooth
{
0
,
330000000
};
// 0,10000
// wait for the duration. this way the old time at least exists
// wait for the duration. this way the old time at least exists
dt
.
sleep
();
dt
_smooth
.
sleep
();
while
(
n
.
ok
())
{
while
(
n
.
ok
())
{
geometry_msgs
::
TransformStamped
transformStamped
;
ros
::
Duration
(
0.01
).
sleep
();
try
{
ros
::
Time
now
=
ros
::
Time
::
now
();
ros
::
Time
past
=
now
-
dt
;
transformStamped
=
tfBuffer
.
lookupTransform
(
"panda_hand"
,
now
,
publishVelocity
(
vel
,
tfBuffer
,
dt
);
"panda_hand"
,
past
,
publishVelocity
(
vel_smoothed
,
tfBuffer
,
dt_smooth
);
"world"
,
ros
::
Duration
(
1.0
));
panda_mqtt_connector
::
StampedVelocity
msg
;
double
dx
=
transformStamped
.
transform
.
translation
.
x
;
double
dy
=
transformStamped
.
transform
.
translation
.
y
;
double
dz
=
transformStamped
.
transform
.
translation
.
z
;
double
velocity
=
sqrt
(
dx
*
dx
+
dy
*
dz
+
dz
*
dz
)
/
dt
.
toSec
();
msg
.
header
.
stamp
=
now
-
(
dt
*
.5
);
msg
.
velocity
=
velocity
;
vel
.
publish
(
msg
);
}
catch
(
tf2
::
TransformException
&
ex
)
{
ROS_WARN
(
"%s"
,
ex
.
what
());
ros
::
Duration
(
1.0
).
sleep
();
continue
;
}
}
}
return
0
;
return
0
;
}
}
\ No newline at end of file
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