Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add gravity compensation filter #153

Open
wants to merge 29 commits into
base: ros2-master
Choose a base branch
from

Conversation

guihomework
Copy link
Contributor

This is a rework of PR #115 for the gravity-compensation filter part, now using generate_parameter_library.

@guihomework guihomework force-pushed the add-gravity-compensation-filter-rolling branch from 528d4ea to 5715e8f Compare March 9, 2023 15:57
@guihomework guihomework force-pushed the add-gravity-compensation-filter-rolling branch from ab3838d to b18ffbd Compare March 13, 2023 19:31
@guihomework
Copy link
Contributor Author

The new changes to this PR stem from using the filter in admittance control and realizing mistakes.

One major mistake was the switch to wrench transforms (as suggested in a TODO in previous version of this code), because it (correctly) applies an additional torque, which should not happen due to gravity being a field and not a force exerted at a certain point than generates a torque when moved. So one should not transform the wrench to base or what ever other computation frame, just rotate it, and remove the gravity force on the correct axes.

Additionally, since there are lookupTransforms done, I offered the possibility to have a different output frame than the input frame. A transform back was pre-existing anyway, so might as well be one that is useful if desired.

I refactored variable names and comments to better explain what happens, and simplified the frames (no need to compute in world frame, sensor_frame=measurement frame is completely fine in my opinion).
I generalized the force field to a vector, to permit having a tilted world in which gravity is not along -z.

I would still like to add a test using a param.yaml + maybe some transforms to fully evaluate the filter in real conditions. The current tests were not sufficient to spot the wrench "transform" errors, because they set up identity transforms which are a special case.

@destogl destogl marked this pull request as ready for review March 19, 2023 20:53
Copy link
Member

@destogl destogl left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The calculations look too complex to me – at least to the older version as I can remember. Is everything necessary?

Also, tests should not declare parameters if possible, but generate_parameter_library should take care of it

README.md Outdated
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Those changes should be removed.

Comment on lines 30 to 32



Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change

bool GravityCompensation<T>::configure()
{
clock_ = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
p_tf_Buffer_.reset(new tf2_ros::Buffer(clock_));
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

would it be possible to get somehow clock from the node? This could lead to wrong definition of clocks and thus not getting correct transformations.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Unless the filter_base is changed, I don't think the filter has any access to the node (only its logger and parameter interfaces). Maybe the filter should get a time and dt passed when updated (as controllers do)

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe for a follow-up PR, you could augment the filterbase to also store a clock interface

transform_data_out_sensor_ = p_tf_Buffer_->lookupTransform(
data_out.header.frame_id, parameters_.sensor_frame, rclcpp::Time());
// rotation only (because gravity is a field) from world (gravity frame) to sensor frame
rot_sensor_world_ = p_tf_Buffer_->lookupTransform(
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are you sure this is correct?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

for the rotation, well, if I use the full transform, the -mg force along z world gets transformed from the world to sensor frame, generating a force matching -mg in the sensor frame, but also the cross product of the relative distance between sensor and world with the -mg, creating a torque. Gravity is not creating such a torque at the CoG. The only cross product is the distance of CoG to center of measurement with the simple gravity force at CoG (but oriented correctly).
The same calculation is done there https://github.com/ros-controls/ros2_controllers/blob/master/admittance_controller/include/admittance_controller/admittance_rule_impl.hpp#L318

Comment on lines 40 to 42
node_->declare_parameter("world_frame", "world");
node_->declare_parameter("sensor_frame", "sensor");
node_->declare_parameter("CoG.force", std::vector<double>({0.0, 0.0, -gravity_acc * mass}));
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We shouldn't do this. We have generate_parameter_library to take care of this things. So no declaration of setting of parameters, but using generate_parameter_library that sets the params when node is started.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For differnet cases simply use different *.yaml and test files

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

hum, ok. I did not know this change to generate_parameter_library had to also be applied to the tests which are quite flexible with node parameter declaration.
Indeed, in other PRs where I had to create tests with a YAML, the values in the YAML have to match the values in the test (to verify the values were loaded correctly by code). This means 2 files have to be edited when setting the parameters, to ensure everything matches. It is easier when params and verified in one place.
Maybe I could move to "set_parameter" only instead of declaring. But I think this might be complex or impossible because param declaration happens in the filter_chain, with the node passed to it, and should already have the params overriden there. To override the params in the node, they must be declared isn't it ? this is a chicken-egg problem.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I did the change. I am not sure this is was really needed, but at least there is no "visible" declaration.

Comment on lines 31 to 33
// TODO(destogl): do this
// subclassing and friending so we can access member variables

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// TODO(destogl): do this
// subclassing and friending so we can access member variables

Copy link
Contributor

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could we add a short documentation here please? Some (pseudo-) formulas to describe the mathematics would be great, otherwise it is very hard to review.
Maybe in a separate readme.[md,rst] together with some high-level description of what the filter is good for.

@guihomework
Copy link
Contributor Author

Could we add a short documentation here please? Some (pseudo-) formulas to describe the mathematics would be great, otherwise it is very hard to review. Maybe in a separate readme.[md,rst] together with some high-level description of what the filter is good for.

Sure, this could permit to avoid others not understanding immediately what was going on either, redoing all the maths.

@guihomework
Copy link
Contributor Author

The calculations look too complex to me – at least to the older version as I can remember. Is everything necessary?

Also, tests should not declare parameters if possible, but generate_parameter_library should take care of it

I think I will clarify with a tiny drawing in a readme. I would say the code I started from was a special case, and did not work in all cases, especially if the force torque measurement does not happen in a frame that the kinematics knows about (not talking about lookup here).
One example was in case the force torque sensor is mounted at the robot flange, but the measurement happens 5 cm further (thickness of the sensor). So one needs to consider this transform, which adds one transform. But I simplified (removed one transform from Cog to world) the original code to not have to move the computation in world frame and back. World frame is just where gravity is defined. Computation do not have to be there I believe.

@guihomework
Copy link
Contributor Author

Could we add a short documentation here please? Some (pseudo-) formulas to describe the mathematics would be great, otherwise it is very hard to review. Maybe in a separate readme.[md,rst] together with some high-level description of what the filter is good for.

I added a README.md inside the source folder, as the general README does not even describe the PID etc...

For differenet cases simply use different *.yaml and test files

I will try address this in some near future (also for #152)

@christophfroehlich
Copy link
Contributor

I added a README.md inside the source folder, as the general README does not even describe the PID etc...

Great thx, I already realized the lack of any docs here. -> #154 ;)

I'll have a look the next days.

Copy link
Contributor

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM

Thanks for the docs, sounds reasonable and according to the actual implementation.
I only added some typo and format-related suggestions.

## Available filters

* Gravity Compensation: implements a gravity compensation algorithm, removing the gravity component from the incoming data (Wrench).
*
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
*

@@ -0,0 +1,59 @@
# Control Filters
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
# Control Filters
# Control filters

*


## Gravity Compensation filter
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
## Gravity Compensation filter
## Gravity compensation filter


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.

The filter relies on ROS TF, and might fail if transforms are missing.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
The filter relies on ROS TF, and might fail if transforms are missing.
The filter relies on tf2, and might fail if transforms are missing.


## Gravity Compensation filter

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.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
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.
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.


and,

fc<sub>s</sub> = f<sub>s</sub> - T<sub>sw</sub>.g<sub>w</sub>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
fc<sub>s</sub> = f<sub>s</sub> - T<sub>sw</sub>.g<sub>w</sub>
fc<sub>s</sub> = f<sub>s</sub> - T<sub>sw</sub>g<sub>w</sub>


its force and,

&tau;c<sub>s</sub> = &tau;<sub>s</sub> - p<sub>s</sub> x (T<sub>sw</sub>.g<sub>w</sub>)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
&tau;c<sub>s</sub> = &tau;<sub>s</sub> - p<sub>s</sub> x (T<sub>sw</sub>.g<sub>w</sub>)
&tau;c<sub>s</sub> = &tau;<sub>s</sub> - p<sub>s</sub> x (T<sub>sw</sub>g<sub>w</sub>)


its torque, and

&Fscr;<sub>s</sub> = T<sub>si</sub>.&Fscr;<sub>i</sub>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
&Fscr;<sub>s</sub> = T<sub>si</sub>.&Fscr;<sub>i</sub>
&Fscr;<sub>s</sub> = T<sub>si</sub>&Fscr;<sub>i</sub> = {f<sub>s</sub>, &tau;<sub>s</sub>}


Remarks :
* a full vector is used for gravity force, to not impose gravity to be only along z of `world_frame`.
* `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.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
* `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.
* `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.

Remarks :
* a full vector is used for gravity force, to not impose gravity to be only along z of `world_frame`.
* `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.
* `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.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
* `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.
* `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.

@guihomework
Copy link
Contributor Author

Thanks a lot @christophfroehlich for the review and sorry for fixing spell-checking, I had forgotten to install a spell checker in VS Code, my former editor had one integrated.

Now, only the issue about removing clock access is open I believe and is not straight forward to solve. @destogl can we live with this ?

bmagyar
bmagyar previously approved these changes May 6, 2023
bool GravityCompensation<T>::configure()
{
clock_ = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
p_tf_Buffer_.reset(new tf2_ros::Buffer(clock_));
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe for a follow-up PR, you could augment the filterbase to also store a clock interface

test/control_filters/test_gravity_compensation.cpp Outdated Show resolved Hide resolved
@guihomework guihomework dismissed stale reviews from bmagyar and christophfroehlich via 819941c May 9, 2023 09:59
@guihomework
Copy link
Contributor Author

I just added one export that solves an issue when building in symlink-install

  ament_cmake_symlink_install_targets()
  'gravity_compensation_filter_parameters' is an interface library - there's
  nothing to symlink install.  Perhaps you forgot to add EXPORT or INCLUDES
  DESTINATION?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants