Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Small improvement in remapping #393

Merged

Conversation

AndyZe
Copy link
Contributor

@AndyZe AndyZe commented Jul 27, 2022

Resizing this output vector with every iteration isn't necessary.

The idea here is, make the variable static so it retains its value between iterations. Only remap if the dimension of the vector changes.

Partial fix to #392

@@ -1136,8 +1136,12 @@ void JointTrajectoryController::sort_to_local_joint_order(
get_node()->get_logger(), "Invalid input size (%zu) for sorting", to_remap.size());
return to_remap;
}
std::vector<double> output;
output.resize(mapping.size(), 0.0);
static std::vector<double> output(dof_, 0.0);
Copy link
Contributor Author

Choose a reason for hiding this comment

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

If it's safe to assume dof_ never changes, this can get simpler.

dof_ changes here:

controller_interface::CallbackReturn JointTrajectoryController::on_configure(
  const rclcpp_lifecycle::State &)
{
  const auto logger = get_node()->get_logger();

  // update parameters
  joint_names_ = get_node()->get_parameter("joints").as_string_array();
  if ((dof_ > 0) && (joint_names_.size() != dof_))
  {
    RCLCPP_ERROR(
      logger,
      "The JointTrajectoryController does not support restarting with a different number of DOF");
    // TODO(andyz): update vector lengths if num. joints did change and re-initialize them so we
    // can continue
    return CallbackReturn::FAILURE;
  }

  dof_ = joint_names_.size();

So it could hypothetically change but that would be really unusual

Copy link
Contributor Author

@AndyZe AndyZe Jul 27, 2022

Choose a reason for hiding this comment

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

I think it doesn't make any sense to allow dof_ to change since the yaml config file contains a list of joint names to control. Example config file here: https://github.com/ros-planning/moveit_resources/blob/ros2/panda_moveit_config/config/ros2_controllers.yaml

Agree, @destogl or @bmagyar ?

Copy link
Member

Choose a reason for hiding this comment

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

Yes! Please also see #394

Copy link
Member

@destogl destogl left a comment

Choose a reason for hiding this comment

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

I agree, although here it is not necessary to have great performance since this is (or at least should be) a non-realtime method.

@AndyZe
Copy link
Contributor Author

AndyZe commented Jul 27, 2022

well, this method is actually called in the update loop. I'll probably end up closing this PR if dof_ becomes constant because it won't be relevant anymore.

@bmagyar bmagyar added the backport-humble This label should be used by maintaines only! Label triggers PR backport to ROS2 humble. label Jul 31, 2023
@bmagyar bmagyar merged commit cc4c221 into ros-controls:master Jul 31, 2023
13 checks passed
mergify bot pushed a commit that referenced this pull request Jul 31, 2023
Co-authored-by: Bence Magyar <bence.magyar.robotics@gmail.com>
(cherry picked from commit cc4c221)
bmagyar pushed a commit that referenced this pull request Aug 1, 2023
bmagyar pushed a commit that referenced this pull request Aug 5, 2023
* Small improvement in remapping (#393) (#724)

* Fix file name for include guard (backport #681)

(cherry picked from commit c619aac)

Co-authored-by: Christoph Fröhlich <christophfroehlich@users.noreply.github.com>

* Activate AdmittanceControllerTestParameterizedInvalidParameters (#711) (#733)

* [JTC] Re-enabling test, bugfixing and hardening. Adding a parameter to define when trajectories with non-zero velocity at the end are used. (backport #705) (#706)

* Add state_publish_rate parameter

---------

Co-authored-by: mergify[bot] <37929162+mergify[bot]@users.noreply.github.com>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
backport-humble This label should be used by maintaines only! Label triggers PR backport to ROS2 humble.
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants