Skip to content

joint_trajectory_controller setHoldPosition could lead to unexpected delay in RT loop when called from inside of RT thread #598

Open
@farshbafdoustar

Description

@farshbafdoustar

The curr_trajectory_box_.set(hold_trajectory_ptr_); in setHoldPosition is putting the hold_trajectory_ptr_ in the box.
If the pointer already in the box, is the last pointer to the current trajectory, the memory pointed by the pointer will be released after the set function. This could lead to an unexpected delay if the current trajectory in the box is a big QuinticSplineSegment (ex. 500 points).

I encountered this delay when I tried to setHoldPosition in update method of my custom controller inherited from joint_trajectory_controller. Have I missed sth?

One workaround could be having a private extra pointer , pointing to the current trajectory in the box and resetting it in a non-RT thread (service call or goalCB). But then it is in opposite to the box concept. Any idea?

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions