Skip to content
Closed
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions cartesian_impedance_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ add_message_files(DIRECTORY msg
FILES
CartesianStiffness.msg
CartesianDamping.msg
CartesianDampingRatio.msg
MaxCartesianVelocity.msg
MaxControlForce.msg
MaxPathDeviation.msg
Expand Down
4 changes: 2 additions & 2 deletions cartesian_impedance_msgs/msg/CartesianDamping.msg
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
# oscillate after deflection.
# For all degrees of freedom (without unit: Lehr’s damping ratio)

# [ratio:0.1-1.0]
# [Ns/m]
geometry_msgs/Vector3 translational
# [ratio:0.1-1.0]
# [Ns/rad]
geometry_msgs/Vector3 rotational
Copy link
Contributor

Choose a reason for hiding this comment

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

In this context, what does rotational damping mean? I assume it's dampening about the fixed frame axes? Is there any confusion/issues like those associated with euler angles (i.e. order of application)?

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Yes you are right Shaun. Is dampening about the fixed frame axes. These values are usually consistent and each value during the motion is constant, so there are no singularities that come with Euler angles actually these are just constants which are used to define the properties of the Spring when the robot is in Cartesian Impedance Mode.

13 changes: 13 additions & 0 deletions cartesian_impedance_msgs/msg/CartesianDampingRatio.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
# Damping parameters for the Cartesian Impedance
# the values are divided into translational and rotational
# each of the translational and rotational components is defined as Vector3

# Spring damping (type: double)
# The spring damping determines the extent to which the virtual springs
# oscillate after deflection.
# For all degrees of freedom (without unit: Lehr’s damping ratio)

# [ratio:0.1-1.0]
geometry_msgs/Vector3 translational
# [ratio:0.1-1.0]
geometry_msgs/Vector3 rotational
4 changes: 2 additions & 2 deletions cartesian_impedance_msgs/msg/NullSpace.msg
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@
string[] link_names

# [Nm/rad] must be => 0.0
std_msgs/Float64[] stiffness
float64[] stiffness

# without unit: Lehr’s damping ratio
# must be between 0.3-1.0 suggested is 0.7
std_msgs/Float64[] damping
float64[] damping
17 changes: 10 additions & 7 deletions cartesian_impedance_msgs/msg/SetCartesianImpedance.msg
Original file line number Diff line number Diff line change
@@ -1,10 +1,13 @@
# Here we combine all the parameters message definitions into a single message
# that needs to be send to the controller in order to adjust the Cartesian Impedance Parameters

string tool
CartesianStiffness stiffness
CartesianDamping damping
MaxCartesianVelocity max_cart_vel
MaxControlForce max_ctrl_force
MaxPathDeviation max_path_deviation
NullSpace null_space_params
string tool
CartesianStiffness stiffness
#use this if the damping is in Ns/m, Ns/rad
Copy link
Contributor

Choose a reason for hiding this comment

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

How does the receiving node know which type of Cartesian stiffness is used?

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

Do you mean Cartesian Damping type?

For now the only difference is in the naming, and is up to the user to decide which one to choose. In fact there is not even difference of the variable definition.

Do you have any suggestions how we can differentiate this better, or we could just leave one msg type called damping and let the user either input ratio or Ns/m for the damping parameters. Having two types of damping msgs can be confusing and prone to errors

Copy link
Contributor

Choose a reason for hiding this comment

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

Yes, I meant dampening.

From a usability perspective, any publisher and any subscriber should be able to talk and the semantic intent of the message should be clear. In other words, the messages sent should always mean the same thing regardless of who is producing/consuming it.

I think you should pick convention and then make sure subscribers can translate that convention into whatever is expected by the controller. For example, if you pick Ns/m, then the drive node for the iiwa will require a critical dampening parameter(s) in order to translate into a unit-less dampening. While this may seem like it makes the driver more complex, it does so for the sake of usability and consistent semantics.

Copy link
Member

@gavanderhoorn gavanderhoorn Jun 20, 2016

Choose a reason for hiding this comment

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

If I may make a suggestion, I think the choice for either ratio or Ns/m is something we should get as much input on as possible.

I've talked to multiple people internally (control engineers, mechanical engineers, ..) and have heard passionate arguments for and against both options. Some find ratios much more intuitive, others dislike the relativeness of them. Ns/m is regarded as difficult, and not as 'platform independent' (ie: 0.5 is always 0.5, but the effect of 1.0 Ns/m isn't immediately clear), even though it is something that actually has a unit (and is not a dimensionless nr, so is less ambiguous / depending on context).

Personally I agree with @shaun-edwards (and I think I've said it before), in that any message should be unambiguously interpretable. Making the semantics of fields dependent on implicit or invisible assumptions / knowledge seems like a bad idea.

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

I also agree with @gavanderhoorn that we should definitely find consensus whether we should use ratio's or Ns/m, I think that this should highly depend on the units majority of the robots use as well. I am also looking at how to convert from Ns/m to ratios for example and it seems it is not very straight forward thing to do...

Maybe if we can get input from others who have robots who use Cartesian Impedance and the units they use would be great.

CartesianDamping damping
#use this if the damping parameters are defined as ratios (Lehr's damping ratio)
CartesianDampingRatio damping_ratio
MaxCartesianVelocity max_cart_vel
MaxControlForce max_ctrl_force
MaxPathDeviation max_path_deviation
NullSpace null_space_params