Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -189,6 +189,9 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
rclcpp::TimerBase::SharedPtr goal_handle_timer_;
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);

// Pre-allocated action feedback message to avoid heap allocation in RT loop
std::shared_ptr<FollowJTrajAction::Feedback> preallocated_feedback_;

// callback for topic interface
void topic_callback(const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> msg);

Expand Down
21 changes: 11 additions & 10 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -367,16 +367,13 @@ controller_interface::return_type JointTrajectoryController::update(

if (active_goal)
{
// send feedback
auto feedback = std::make_shared<FollowJTrajAction::Feedback>();
feedback->header.stamp = time;
feedback->joint_names = params_.joints;

feedback->actual = state_current_;
feedback->desired = state_desired_;
feedback->error = state_error_;
feedback->index = static_cast<int32_t>(next_point_index);
active_goal->setFeedback(feedback);
// send feedback using preallocated message to avoid heap allocation in RT loop
preallocated_feedback_->header.stamp = time;
preallocated_feedback_->actual = state_current_;
preallocated_feedback_->desired = state_desired_;
preallocated_feedback_->error = state_error_;
preallocated_feedback_->index = static_cast<int32_t>(next_point_index);
active_goal->setFeedback(preallocated_feedback_);

// check abort
if (tolerance_violated_while_moving)
Expand Down Expand Up @@ -1938,6 +1935,10 @@ void JointTrajectoryController::init_hold_position_msg()
{
hold_position_msg_ptr_->points[0].effort.resize(dof_, 0.0);
}

// Pre-allocate feedback message to avoid heap allocation in RT loop
preallocated_feedback_ = std::make_shared<FollowJTrajAction::Feedback>();
preallocated_feedback_->joint_names = params_.joints;
Comment on lines +1938 to +1941
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

This has nothing to do with the hold_position message.
let's move this to the on_configure, or rename the method.

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

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

You are right. Sorry

}

} // namespace joint_trajectory_controller
Expand Down