Open gaspatxo opened 4 months ago
This is probably because of the way KDL handles synchronization between translation and rotation, using eqradius
.
See path_line.cpp
used by pilz planner trajectory_generator.cpp
/**
* Constructs a Line Path
* F_base_start and F_base_end give the begin and end frame wrt the base
* orient gives the method of rotation interpolation
* eqradius : equivalent radius :
* serves to compare rotations and translations.
* the "amount of motion"(pos,vel,acc) of the rotation is taken
* to be the amount motion of a point at distance eqradius from the
* rotation axis.
*
* Eqradius is introduced because it is unavoidable that you have to compare rotations and translations :
* e.g. : You can have motions that only contain rotation, and motions that only contain translations.
* The motion planning goes as follows :
* - translation is planned with the given parameters
* - rotation is planned planned with the parameters calculated with eqradius.
* - The longest of the previous two remains unchanged,
* the shortest in duration is scaled to take as long as the longest.
* This guarantees that the geometric path in 6D space remains independent of the motion profile parameters.
This issue is being labeled as stale because it has been open 45 days with no activity. It will be automatically closed after another 45 days without follow-ups.
I tried using moveit built from source after #3000 , the issue seems to have been reduced a bit, but it is still very much present.
This issue is being labeled as stale because it has been open 45 days with no activity. It will be automatically closed after another 45 days without follow-ups.
Description
My goal is to control the linear velocity at which my end effector moves throughout a move sequence. I am using the Pilz
LIN
planner and its multi-segment capability.The speed is respected when movements do not include rotation, being the
max_trans_vel
(inpilz_cartesianl_limits.yaml
) multiplied bymaxVelocityScalingFactor
.However, when rotation is involved in a move, it deviates from the specified:
In all moves the
maxVelocityScalingFactor
is the same,0.1
pilz_cartesianl_limits.yaml
:I have tested this in the Panda and xarm7 robotic arms and in both cases the behaviour is the same.
Your environment
ROS2 Humble on Ubuntu 22.04 using moveit2 binary humble install with cyclone DDS
Steps to reproduce
/move_group_sequence
capability for the panda arm #1281The pilz LIN section in moveit docs says: