Skip to content

Commit b22a754

Browse files
committed
Applied suggested formatting and typo fixes
1 parent 88d6b8a commit b22a754

File tree

3 files changed

+16
-21
lines changed

3 files changed

+16
-21
lines changed

include/control_filters/gravity_compensation.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,6 @@ namespace control_filters
2929
{
3030

3131

32-
3332
template <typename T>
3433
class GravityCompensation : public filters::FilterBase<T>
3534
{

src/control_filters/README.md

+14-16
Original file line numberDiff line numberDiff line change
@@ -1,37 +1,35 @@
1-
# Control Filters
1+
# Control filters
22

33
## Available filters
44

55
* Gravity Compensation: implements a gravity compensation algorithm, removing the gravity component from the incoming data (Wrench).
6-
*
76

7+
## Gravity compensation filter
88

9-
## Gravity Compensation filter
9+
This filter implements a gravity compensation algorithm, applied to an `data_in` wrench, computed at a `sensor_frame` in which the center of gravity (CoG) of the to-be-compensated mass is known.
1010

11-
This filter implements a gravity compensation algorithm, applied to an `data_in wrench`, computed at a `sensor frame` in which the center of gravity (CoG) of the to-be-compensated mass is known.
12-
13-
The filter relies on ROS TF, and might fail if transforms are missing.
11+
The filter relies on tf2, and might fail if transforms are missing.
1412

1513
Note that, for convenience, the filter can perform additional frame changes if data_out frame id is given.
1614

17-
### required parameters
15+
### Required parameters
1816

1917
* `world_frame` (&Rscr;<sub>w</sub>): frame in which the `CoG.force` is represented.
2018
* `sensor_frame` (&Rscr;<sub>s</sub>): frame in which the `CoG.pos` is defined
2119
* `CoG.pos` (p<sub>s</sub>): position of the CoG of the mass the filter should compensate for
2220
* `CoG.force` (g<sub>w</sub>): constant (but updatable) force of gravity at the Cog (typically m.G), defined along axes of the `world_frame`
2321

24-
### algorithm
22+
### Algorithm
2523

2624
Given
2725
* above-required parameters, &Rscr;<sub>w</sub>, &Rscr;<sub>s</sub>, p<sub>s</sub>, g<sub>w</sub>
28-
* `data_in`, a wrench &Fscr;<sub>i</sub> = {f<sub>i</sub>, &tau;<sub>i</sub>} represented in `data_in.frame` &Rscr;<sub>i</sub>
29-
* access to TF homogeneous transforms:
26+
* `data_in`, a wrench &Fscr;<sub>i</sub> = {f<sub>i</sub>, &tau;<sub>i</sub>} represented in the `data_in` frame &Rscr;<sub>i</sub>
27+
* access to tf2 homogeneous transforms:
3028
* T<sub>si</sub> from &Rscr;<sub>i</sub> to &Rscr;<sub>s</sub>
3129
* T<sub>sw</sub> from &Rscr;<sub>w</sub> to &Rscr;<sub>s</sub>
3230
* T<sub>os</sub> from &Rscr;<sub>s</sub> to &Rscr;<sub>o</sub>
3331

34-
Compute `data_out` compensated wrench &Fscr;c<sub>o</sub> = {fc<sub>o</sub>, &tau;c<sub>o</sub>} represented in `data_out.frame` &Rscr;<sub>o</sub> if given, or `data_in.frame` &Rscr;<sub>i</sub> otherwise, with equations:
32+
Compute `data_out` compensated wrench &Fscr;c<sub>o</sub> = {fc<sub>o</sub>, &tau;c<sub>o</sub>} represented in the `data_out` frame &Rscr;<sub>o</sub> if given, or the `data_in` frame &Rscr;<sub>i</sub> otherwise, with equations:
3533

3634
&Fscr;c<sub>o</sub> = T<sub>os</sub>.&Fscr;c<sub>s</sub>,
3735

@@ -40,20 +38,20 @@ with &Fscr;c<sub>s</sub> = {fc<sub>s</sub>, &tau;c<sub>s</sub>} the compensated
4038

4139
and,
4240

43-
fc<sub>s</sub> = f<sub>s</sub> - T<sub>sw</sub>.g<sub>w</sub>
41+
fc<sub>s</sub> = f<sub>s</sub> - T<sub>sw</sub>g<sub>w</sub>
4442

4543
its force and,
4644

47-
&tau;c<sub>s</sub> = &tau;<sub>s</sub> - p<sub>s</sub> x (T<sub>sw</sub>.g<sub>w</sub>)
45+
&tau;c<sub>s</sub> = &tau;<sub>s</sub> - p<sub>s</sub> x (T<sub>sw</sub>g<sub>w</sub>)
4846

4947
its torque, and
5048

51-
&Fscr;<sub>s</sub> = T<sub>si</sub>.&Fscr;<sub>i</sub>
49+
&Fscr;<sub>s</sub> = T<sub>si</sub>.&Fscr;<sub>i</sub> = {f<sub>s</sub>, &tau;<sub>s</sub>}
5250

5351
the full transform of the input wrench &Fscr;<sub>i</sub> to sensor frame &Rscr;<sub>s</sub>
5452

5553
Remarks :
5654
* a full vector is used for gravity force, to not impose gravity to be only along z of `world_frame`.
57-
* `data_in.frame` is usually equal to `sensor_frame`, but could be different since measurement of wrech might occur in another frame. Ex: measurements are at the **FT sensor flange** = `data_in.frame`, but CoG is given in **FT sensor base** = `sensor_frame` (=frame to which it is mounted on the robot), introducing an offset (thichkess of the sensor) to be accounted for.
58-
* `data_out.frame` is usually `data_in.frame`, but for convenience, can be set to any other useful frame. Ex: Wrench expressed in a `control_frame` for instance center of a gripper.
55+
* `data_in` frame is usually equal to `sensor_frame`, but could be different since measurement of wrench might occur in another frame. E.g.: measurements are at the **FT sensor flange** = `data_in` frame, but CoG is given in **FT sensor base** = `sensor_frame` (=frame to which it is mounted on the robot), introducing an offset (thickness of the sensor) to be accounted for.
56+
* `data_out` frame is usually `data_in` frame, but for convenience, can be set to any other useful frame. E.g.: wrench expressed in a `control_frame` like the center of a gripper.
5957
* T<sub>sw</sub> will only rotate the g<sub>w</sub> vector, because gravity is a field applied everywhere, and not a wrench (no torque should be induced by transforming from &Rscr;<sub>w</sub> to &Rscr;<sub>s</sub>).

src/control_filters/gravity_compensation_filter_parameters.yaml

+2-4
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,15 @@
11
gravity_compensation_filter:
22
world_frame: {
33
type: string,
4-
# default_value: world,
5-
description: "fixed world frame in which the constant field-induced force is given",
4+
description: "Fixed world frame in which the constant field-induced force is given.",
65
read_only: true,
76
validation: {
87
not_empty<>: []
98
},
109
}
1110
sensor_frame: {
1211
type: string,
13-
# default_value: ft_sensor,
14-
description: "Sensor frame in which center of gravity (CoG) is measured and computation occur",
12+
description: "Sensor frame in which center of gravity (CoG) is measured and computation occur.",
1513
read_only: true,
1614
validation: {
1715
not_empty<>: []

0 commit comments

Comments
 (0)