Skip to content

Commit d2d1659

Browse files
christophfroehlichmergify[bot]
authored andcommitted
[JTC] Preallocate std::vector variables for interfaces (#1893)
(cherry picked from commit d7ca589)
1 parent 1ff0951 commit d2d1659

File tree

1 file changed

+8
-0
lines changed

1 file changed

+8
-0
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -769,6 +769,10 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
769769
// Check if only allowed interface types are used and initialize storage to avoid memory
770770
// allocation during activation
771771
joint_command_interface_.resize(allowed_interface_types_.size());
772+
for (auto & itf : joint_command_interface_)
773+
{
774+
itf.reserve(params_.joints.size());
775+
}
772776

773777
has_position_command_interface_ =
774778
contains_interface_type(params_.command_interfaces, hardware_interface::HW_IF_POSITION);
@@ -806,6 +810,10 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
806810
// allocation during activation
807811
// Note: 'effort' storage is also here, but never used. Still, for this is OK.
808812
joint_state_interface_.resize(allowed_interface_types_.size());
813+
for (auto & itf : joint_state_interface_)
814+
{
815+
itf.reserve(params_.joints.size());
816+
}
809817

810818
has_position_state_interface_ =
811819
contains_interface_type(params_.state_interfaces, hardware_interface::HW_IF_POSITION);

0 commit comments

Comments
 (0)