Skip to content

Commit

Permalink
Merge branch 'master' into renovate-load-controller-tests
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored Apr 29, 2023
2 parents 5853359 + 1e3129d commit 16e73cf
Show file tree
Hide file tree
Showing 14 changed files with 304 additions and 131 deletions.
Original file line number Diff line number Diff line change
@@ -1,13 +1,3 @@

---
name: Pull request
about: Create a pull request
title: ''
labels: ''
assignees: ''

---

Contributions via pull requests are much appreciated. Before sending us a pull request, please ensure that:

1. Limited scope. Your PR should do one thing or one set of things. Avoid adding “random fixes” to PRs. Put those on separate PRs.
Expand Down
10 changes: 7 additions & 3 deletions .github/reviewer-lottery.yml
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,16 @@ groups:
- rosterloh
- progtologist
- arne48
- christophfroehlich
- DasRoteSkelett
- Serafadam
- sgmurray
- harderthan
- jaron-l
- malapatiravi
- homalozoa
- erickisos
- sachinkum0009
- qiayuanliao
- homalozoa
- anfemosa
- jackcenter
- VX792
Expand All @@ -31,6 +34,7 @@ groups:
- aprotyas
- peterdavidfagan
- duringhof
- VanshGehlot
- bijoua29
- lm2292
- LukasMacha97
- mcbed
2 changes: 1 addition & 1 deletion .github/workflows/ci-coverage-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ jobs:
}
}
colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml
- uses: codecov/[email protected].2
- uses: codecov/[email protected].3
with:
file: ros_ws/lcov/total_coverage.info
flags: unittests
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/ci-format.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ jobs:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v3
- uses: actions/setup-python@v4.5.0
- uses: actions/setup-python@v4.6.0
with:
python-version: '3.10'
- name: Install system hooks
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/ci-ros-lint.yml
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@ jobs:
linter: [cpplint]
steps:
- uses: actions/checkout@v3
- uses: ros-tooling/setup-ros@0.6.1
- uses: ros-tooling/action-ros-lint@v0.1
- uses: ros-tooling/setup-ros@master
- uses: ros-tooling/action-ros-lint@master
with:
distribution: rolling
linter: cpplint
Expand Down
5 changes: 1 addition & 4 deletions admittance_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
.. _joint_trajectory_controller_userdoc:
.. _addmittance_controller_userdoc:

Admittance Controller
======================
Expand All @@ -8,9 +8,6 @@ The controller implements ``ChainedControllerInterface``, so it is possible to a

The controller requires an external kinematics plugin to function. The `kinematics_interface <https://github.com/ros-controls/kinematics_interface>`_ repository provides an interface and an implementation that the admittance controller can use.

Parameters:



ROS2 interface of the controller
---------------------------------
Expand Down
4 changes: 2 additions & 2 deletions doc/controllers_index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -41,13 +41,13 @@ Available Controllers
:titlesonly:

Admittance Controller <../admittance_controller/doc/userdoc.rst>
Tricycle Controller <../tricycle_controller/doc/userdoc.rst>
Differential Drive Controller <../diff_drive_controller/doc/userdoc.rst>
Effort Controllers <../effort_controllers/doc/userdoc.rst>
Forward Command Controller <../forward_command_controller/doc/userdoc.rst>
Joint Trajectory Controller <../joint_trajectory_controller/doc/userdoc.rst>
Position Controllers <../position_controllers/doc/userdoc.rst>
Tricycle Controller <../tricycle_controller/doc/userdoc.rst>
Velocity Controllers <../velocity_controllers/doc/userdoc.rst>
Effort Controllers <../effort_controllers/doc/userdoc.rst>


Available Broadcasters
Expand Down
6 changes: 3 additions & 3 deletions forward_command_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@ forward_command_controller

This is a base class implementing a feedforward controller. Specific implementations can be found in:

- :ref:`position_controllers_userdoc`
- :ref:`velocity_controllers_userdoc`
- :ref:`effort_controllers_userdoc`
* :ref:`position_controllers_userdoc`
* :ref:`velocity_controllers_userdoc`
* :ref:`effort_controllers_userdoc`

Hardware interface type
-----------------------
Expand Down
10 changes: 5 additions & 5 deletions joint_state_broadcaster/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -21,26 +21,26 @@ If none of the requested interface are not defined, the controller returns error
Parameters
----------

``use_local_topics``
use_local_topics
Optional parameter (boolean; default: ``False``) defining if ``joint_states`` and ``dynamic_joint_states`` messages should be published into local namespace, e.g., ``/my_state_broadcaster/joint_states``.


``joints``
joints
Optional parameter (string array) to support broadcasting of only specific joints and interfaces.
It has to be used in combination with the ``interfaces`` parameter.
Joint state broadcaster asks for access to all defined interfaces on all defined joints.


``interfaces``
interfaces
Optional parameter (string array) to support broadcasting of only specific joints and interfaces.
It has to be used in combination with the ``joints`` parameter.


``extra_joints``
extra_joints
Optional parameter (string array) with names of extra joints to be added to ``joint_states`` and ``dynamic_joint_states`` with state set to 0.


``map_interface_to_joint_state``
map_interface_to_joint_state
Optional parameter (map) providing mapping between custom interface names to standard fields in ``joint_states`` message.
Usecases:

Expand Down
59 changes: 32 additions & 27 deletions joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,11 @@ Trajectory representation

The controller is templated to work with multiple trajectory representations. By default, a spline interpolator is provided, but it's possible to support other representations. The spline interpolator uses the following interpolation strategies depending on the waypoint specification:

Linear: Only position is specified. Guarantees continuity at the position level. Discouraged because it yields trajectories with discontinuous velocities at the waypoints.
* Linear: Only position is specified. Guarantees continuity at the position level. Discouraged because it yields trajectories with discontinuous velocities at the waypoints.

Cubic: Position and velocity are specified. Guarantees continuity at the velocity level.
* Cubic: Position and velocity are specified. Guarantees continuity at the velocity level.

Quintic: Position, velocity and acceleration are specified: Guarantees continuity at the acceleration level.
* Quintic: Position, velocity and acceleration are specified: Guarantees continuity at the acceleration level.

Hardware interface type
-----------------------
Expand All @@ -26,11 +26,11 @@ Similarly to the trajectory representation case above, it's possible to support
Other features
--------------

Realtime-safe implementation.
* Realtime-safe implementation.

Proper handling of wrapping (continuous) joints.
* Proper handling of wrapping (continuous) joints.

Robust to system clock changes: Discontinuous system clock changes do not cause discontinuities in the execution of already queued trajectory segments.
* Robust to system clock changes: Discontinuous system clock changes do not cause discontinuities in the execution of already queued trajectory segments.

ros2_control interfaces
------------------------
Expand All @@ -45,10 +45,10 @@ The state interfaces are defined with ``joints`` and ``state_interfaces`` parame
Supported state interfaces are ``position``, ``velocity``, ``acceleration`` and ``effort`` as defined in the `hardware_interface/hardware_interface_type_values.hpp <https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp>`_.
Legal combinations of state interfaces are:

- ``position``
- ``position`` and ``velocity``
- ``position``, ``velocity`` and ``acceleration``
- ``effort``
* ``position``
* ``position`` and ``velocity``
* ``position``, ``velocity`` and ``acceleration``
* ``effort``

Commands
^^^^^^^^^
Expand Down Expand Up @@ -230,7 +230,7 @@ ROS2 interface of the controller
~/joint_trajectory (input topic) [trajectory_msgs::msg::JointTrajectory]
Topic for commanding the controller.

~/state (output topic) [control_msgs::msg::JointTrajectoryControllerState]
~/controller_state (output topic) [control_msgs::msg::JointTrajectoryControllerState]
Topic publishing internal states with the update-rate of the controller manager.

~/follow_joint_trajectory (action server) [control_msgs::action::FollowJointTrajectory]
Expand All @@ -244,23 +244,28 @@ The controller types are placed into namespaces according to their command types

The following version of the Joint Trajectory Controller are available mapping the following interfaces:

- position_controllers::JointTrajectoryController
- Input: position, [velocity, [acceleration]]
- Output: position
- position_velocity_controllers::JointTrajectoryController
- Input: position, [velocity, [acceleration]]
- Output: position and velocity
- position_velocity_acceleration_controllers::JointTrajectoryController
- Input: position, [velocity, [acceleration]]
- Output: position, velocity and acceleration

.. - velocity_controllers::JointTrajectoryController
.. - Input: position, [velocity, [acceleration]]
.. - Output: velocity
* position_controllers::JointTrajectoryController

* Input: position, [velocity, [acceleration]]
* Output: position

* position_velocity_controllers::JointTrajectoryController

* Input: position, [velocity, [acceleration]]
* Output: position and velocity

* position_velocity_acceleration_controllers::JointTrajectoryController

* Input: position, [velocity, [acceleration]]
* Output: position, velocity and acceleration

.. * velocity_controllers::JointTrajectoryController
.. * Input: position, [velocity, [acceleration]]
.. * Output: velocity
.. TODO(anyone): would it be possible to output velocty and acceleration?
.. (to have an vel_acc_controllers)
.. - effort_controllers::JointTrajectoryController
.. - Input: position, [velocity, [acceleration]]
.. - Output: effort
.. * effort_controllers::JointTrajectoryController
.. * Input: position, [velocity, [acceleration]]
.. * Output: effort
(*Not implemented yet*) When using pure ``velocity`` or ``effort`` controllers a command is generated using the desired state and state error using a velocity feedforward term plus a corrective PID term. (#171)
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa

// Preallocate variables used in the realtime update() function
trajectory_msgs::msg::JointTrajectoryPoint state_current_;
trajectory_msgs::msg::JointTrajectoryPoint command_current_;
trajectory_msgs::msg::JointTrajectoryPoint state_desired_;
trajectory_msgs::msg::JointTrajectoryPoint state_error_;

Expand Down Expand Up @@ -256,6 +257,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
void read_state_from_hardware(JointTrajectoryPoint & state);

bool read_state_from_command_interfaces(JointTrajectoryPoint & state);
bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);

void query_state_service(
const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
Expand All @@ -267,6 +269,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa

void resize_joint_trajectory_point(
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
void resize_joint_trajectory_point_command(
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
};

} // namespace joint_trajectory_controller
Expand Down
Loading

0 comments on commit 16e73cf

Please sign in to comment.