-
Notifications
You must be signed in to change notification settings - Fork 390
Add multi_omni_wheel_drive_controller #1535
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
Open
Amronos
wants to merge
49
commits into
ros-controls:master
Choose a base branch
from
Amronos:add-multi_omni_wheel_drive_controller
base: master
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
Open
Changes from 35 commits
Commits
Show all changes
49 commits
Select commit
Hold shift + click to select a range
de0725f
Add multi_omni_wheel_drive_controller
Amronos cddfb9c
Fix typo
Amronos 82b6d87
Update package.xml
Amronos ff32b2d
Remove ament_lint test dependencies in package.xml
Amronos a5d581a
Update mobile_robot_kinematics.rst
Amronos ed119f4
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos d9b8547
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 4b26153
Update in accordance to #1534
Amronos 249c6f9
Fix pre-commit for omni_wheel_omnidirectional_drive.svg
Amronos da3c9ce
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 363ebe4
Apply suggestions from code review
Amronos 3b574bc
Apply suggestions from code review
Amronos bece933
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 57059bf
Update diagram according to review
Amronos 8c0c3ec
Update mobile_robot_kinematics.rst
Amronos 077eba5
Do some code cleanup and fixes
Amronos fb3a77f
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos c487fa8
Fix a comment
Amronos a67ac1f
Update integration in odometry
Amronos 15fbe3d
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos b64a869
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos cb7fa77
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 4d2a788
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos ad3eda7
Fix incorrect merge
Amronos 1789bb4
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 80e2c91
Merge `master` into add-multi_omni_wheel_drive_controller
Amronos fb75835
Cleanup code and fix deprecation warnings
Amronos d4f7630
Cleanup includes
Amronos d3411d6
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos c7e619d
Merge `upstream/master` into `add-multi_omni_wheel_drive_controller`
Amronos dd8e0a5
Merge `upstream/master` into `add-multi_omni_wheel_drive_controller`
Amronos a70960e
Fix exported interface naming and use global cmake macros
Amronos 57034d8
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 797ed79
Merge `upstream/master` into `add-multi_omni_wheel_drive_controller`
Amronos 5f84437
Fixes for pre-commit
Amronos c228218
Apply suggestions from code review
Amronos 54a9e3d
Remove ``default_value`` for ``wheel_offset``
Amronos 96c4aa1
Apply suggestions from code review
Amronos 162f06e
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 4128004
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 86b351e
Add more tests for different robot configurations
Amronos 44a735a
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 739a755
Align with recent ros2_control changes and best practices
Amronos 2e0bada
Fix pre-commit
Amronos 467c9b7
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos f07064e
Fix incorrect merge
Amronos a4f8024
Fix published messages
Amronos d4b90e0
Merge branch 'master' into add-multi_omni_wheel_drive_controller
Amronos 674c118
Fix transform messages
Amronos File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,97 @@ | ||
cmake_minimum_required(VERSION 3.16) | ||
project(multi_omni_wheel_drive_controller) | ||
|
||
find_package(ros2_control_cmake REQUIRED) | ||
set_compiler_options() | ||
export_windows_symbols() | ||
|
||
# Find dependencies | ||
set(THIS_PACKAGE_INCLUDE_DEPENDS | ||
ament_cmake | ||
controller_interface | ||
generate_parameter_library | ||
geometry_msgs | ||
hardware_interface | ||
nav_msgs | ||
pluginlib | ||
rclcpp | ||
rclcpp_lifecycle | ||
realtime_tools | ||
tf2 | ||
tf2_msgs | ||
Eigen3 | ||
) | ||
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) | ||
find_package(${Dependency} REQUIRED) | ||
endforeach() | ||
|
||
generate_parameter_library( | ||
${PROJECT_NAME}_parameters | ||
src/${PROJECT_NAME}_parameters.yaml | ||
) | ||
|
||
add_library(${PROJECT_NAME} SHARED | ||
src/${PROJECT_NAME}.cpp | ||
src/odometry.cpp | ||
) | ||
target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_17) | ||
target_include_directories(${PROJECT_NAME} | ||
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> | ||
$<INSTALL_INTERFACE:include/${PROJECT_NAME}> | ||
) | ||
target_link_libraries(${PROJECT_NAME} PRIVATE | ||
${PROJECT_NAME}_parameters | ||
Eigen3::Eigen | ||
) | ||
ament_target_dependencies(${PROJECT_NAME} PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS}) | ||
pluginlib_export_plugin_description_file(controller_interface multi_omni_wheel_drive_plugin.xml) | ||
|
||
# Install | ||
install( | ||
DIRECTORY include/ | ||
DESTINATION include/${PROJECT_NAME}/ | ||
) | ||
install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_parameters | ||
EXPORT export_${PROJECT_NAME} | ||
RUNTIME DESTINATION bin | ||
ARCHIVE DESTINATION lib | ||
LIBRARY DESTINATION lib | ||
) | ||
|
||
if(BUILD_TESTING) | ||
find_package(ament_cmake_gmock REQUIRED) | ||
find_package(controller_manager REQUIRED) | ||
find_package(ros2_control_test_assets REQUIRED) | ||
|
||
ament_add_gmock(test_${PROJECT_NAME} test/test_${PROJECT_NAME}.cpp) | ||
target_link_libraries(test_${PROJECT_NAME} | ||
${PROJECT_NAME} | ||
${PROJECT_NAME}_parameters | ||
Eigen3::Eigen | ||
) | ||
ament_target_dependencies(test_${PROJECT_NAME} | ||
geometry_msgs | ||
hardware_interface | ||
nav_msgs | ||
rclcpp | ||
rclcpp_lifecycle | ||
realtime_tools | ||
tf2 | ||
tf2_msgs | ||
Eigen3 | ||
) | ||
|
||
add_definitions(-DTEST_FILES_DIRECTORY="${CMAKE_CURRENT_SOURCE_DIR}/test") | ||
ament_add_gmock(test_load_${PROJECT_NAME} test/test_load_${PROJECT_NAME}.cpp) | ||
ament_target_dependencies(test_load_${PROJECT_NAME} | ||
controller_manager | ||
ros2_control_test_assets | ||
) | ||
|
||
find_package(ament_lint_auto REQUIRED) | ||
ament_lint_auto_find_test_dependencies() | ||
endif() | ||
|
||
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) | ||
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) | ||
ament_package() |
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,78 @@ | ||
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/multi_omni_wheel_drive_controller/doc/userdoc.rst | ||
|
||
.. _multi_omni_wheel_drive_controller_userdoc: | ||
|
||
multi_omni_wheel_drive_controller | ||
================================= | ||
|
||
Controller for mobile robots with omnidirectional drive. | ||
|
||
Supports using 3 or more omni wheels spaced at an equal angle from each other in a circular formation. | ||
To better understand this, have a look at :ref:`mobile_robot_kinematics`. | ||
|
||
The controller uses velocity input, i.e., stamped Twist messages where linear ``x``, ``y``, and angular ``z`` components are used. | ||
Values in other components are ignored. | ||
|
||
Odometry is computed from hardware feedback and published. | ||
|
||
Other features | ||
-------------- | ||
|
||
+ Realtime-safe implementation. | ||
+ Odometry publishing | ||
+ Automatic stop after command time-out | ||
|
||
Description of controller's interfaces | ||
-------------------------------------- | ||
|
||
References (from a preceding controller) | ||
,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,, | ||
|
||
When controller is in chained mode, it exposes the following references which can be commanded by the preceding controller: | ||
|
||
- ``<controller_name>/linear/x/velocity`` double, in m/s | ||
- ``<controller_name>/linear/y/velocity`` double, in m/s | ||
- ``<controller_name>/angular/z/velocity`` double, in rad/s | ||
|
||
Together, these represent the body twist (which in unchained-mode would be obtained from ~/cmd_vel). | ||
|
||
State interfaces | ||
,,,,,,,,,,,,,,,, | ||
|
||
As feedback interface type the joints' position (``hardware_interface::HW_IF_POSITION``) or velocity (``hardware_interface::HW_IF_VELOCITY``, if parameter ``position_feedback=false``) are used. | ||
|
||
Command interfaces | ||
,,,,,,,,,,,,,,,,,,,,,, | ||
|
||
Joints' velocity (``hardware_interface::HW_IF_VELOCITY``) are used. | ||
|
||
|
||
ROS 2 Interfaces | ||
---------------- | ||
|
||
Subscribers | ||
,,,,,,,,,,, | ||
|
||
~/cmd_vel [geometry_msgs/msg/TwistStamped] | ||
Velocity command for the controller. The controller extracts the x and y component of the linear velocity and the z component of the angular velocity. Velocities on other components are ignored. | ||
|
||
Publishers | ||
,,,,,,,,,, | ||
~/odom [nav_msgs::msg::Odometry] | ||
This represents an estimate of the robot's position and velocity in free space. | ||
|
||
/tf [tf2_msgs::msg::TFMessage] | ||
tf tree. Published only if ``enable_odom_tf=true`` | ||
|
||
|
||
Parameters | ||
,,,,,,,,,, | ||
|
||
This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters. The parameter `definition file located in the src folder <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/multi_omni_wheel_drive_controller/src/multi_omni_wheel_drive_controller_parameters.yaml>`_ contains descriptions for all the parameters used by the controller. | ||
|
||
.. generate_parameter_library_details:: ../src/multi_omni_wheel_drive_controller_parameters.yaml | ||
|
||
An example parameter file for this controller can be found in `the test directory <https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/multi_omni_wheel_drive_controller/test/config/test_multi_omni_wheel_drive_controller.yaml>`_: | ||
|
||
.. literalinclude:: ../test/config/test_multi_omni_wheel_drive_controller.yaml | ||
:language: yaml |
122 changes: 122 additions & 0 deletions
122
...ontroller/include/multi_omni_wheel_drive_controller/multi_omni_wheel_drive_controller.hpp
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,122 @@ | ||
// Copyright 2025 Aarav Gupta | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#ifndef MULTI_OMNI_WHEEL_DRIVE_CONTROLLER__MULTI_OMNI_WHEEL_DRIVE_CONTROLLER_HPP_ | ||
#define MULTI_OMNI_WHEEL_DRIVE_CONTROLLER__MULTI_OMNI_WHEEL_DRIVE_CONTROLLER_HPP_ | ||
|
||
#include <memory> | ||
#include <string> | ||
#include <vector> | ||
|
||
#include "controller_interface/chainable_controller_interface.hpp" | ||
#include "geometry_msgs/msg/twist_stamped.hpp" | ||
#include "multi_omni_wheel_drive_controller/odometry.hpp" | ||
#include "nav_msgs/msg/odometry.hpp" | ||
#include "realtime_tools/realtime_buffer.hpp" | ||
#include "realtime_tools/realtime_publisher.hpp" | ||
#include "tf2_msgs/msg/tf_message.hpp" | ||
|
||
// auto-generated by generate_parameter_library | ||
#include "multi_omni_wheel_drive_controller/multi_omni_wheel_drive_controller_parameters.hpp" | ||
|
||
namespace multi_omni_wheel_drive_controller | ||
{ | ||
class MultiOmniWheelDriveController : public controller_interface::ChainableControllerInterface | ||
{ | ||
using TwistStamped = geometry_msgs::msg::TwistStamped; | ||
|
||
public: | ||
MultiOmniWheelDriveController(); | ||
|
||
controller_interface::CallbackReturn on_init() override; | ||
|
||
controller_interface::InterfaceConfiguration command_interface_configuration() const override; | ||
|
||
controller_interface::InterfaceConfiguration state_interface_configuration() const override; | ||
|
||
controller_interface::CallbackReturn on_configure( | ||
const rclcpp_lifecycle::State & previous_state) override; | ||
|
||
controller_interface::CallbackReturn on_activate( | ||
const rclcpp_lifecycle::State & previous_state) override; | ||
|
||
controller_interface::CallbackReturn on_deactivate( | ||
const rclcpp_lifecycle::State & previous_state) override; | ||
|
||
controller_interface::return_type update_reference_from_subscribers( | ||
const rclcpp::Time & time, const rclcpp::Duration & period) override; | ||
|
||
controller_interface::return_type update_and_write_commands( | ||
const rclcpp::Time & time, const rclcpp::Duration & period) override; | ||
|
||
controller_interface::CallbackReturn on_cleanup( | ||
const rclcpp_lifecycle::State & previous_state) override; | ||
|
||
controller_interface::CallbackReturn on_error( | ||
const rclcpp_lifecycle::State & previous_state) override; | ||
|
||
protected: | ||
bool on_set_chained_mode(bool chained_mode) override; | ||
|
||
std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override; | ||
|
||
// Parameters from ROS for multi_omni_wheel_drive_controller | ||
std::shared_ptr<ParamListener> param_listener_; | ||
Params params_; | ||
|
||
const char * feedback_type() const; | ||
|
||
struct WheelHandle | ||
{ | ||
std::reference_wrapper<const hardware_interface::LoanedStateInterface> feedback; | ||
std::reference_wrapper<hardware_interface::LoanedCommandInterface> velocity; | ||
}; | ||
std::vector<WheelHandle> registered_wheel_handles_; | ||
|
||
controller_interface::CallbackReturn configure_wheel_handles( | ||
const std::vector<std::string> & wheel_names, std::vector<WheelHandle> & registered_handles); | ||
|
||
// Timeout to consider cmd_vel commands old | ||
rclcpp::Duration cmd_vel_timeout_ = rclcpp::Duration::from_seconds(0.5); | ||
|
||
bool subscriber_is_active_ = false; | ||
rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr; | ||
realtime_tools::RealtimeBuffer<std::shared_ptr<TwistStamped>> received_velocity_msg_ptr_{nullptr}; | ||
|
||
void compute_and_set_wheel_velocities(); | ||
|
||
std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr; | ||
std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>> | ||
realtime_odometry_publisher_ = nullptr; | ||
|
||
Odometry odometry_; | ||
|
||
std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ = | ||
nullptr; | ||
std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>> | ||
realtime_odometry_transform_publisher_ = nullptr; | ||
|
||
// Variables to help limit the publish rate of odometry as described using params_.publish_rate | ||
rclcpp::Duration publish_period_ = rclcpp::Duration::from_seconds(0); | ||
rclcpp::Time previous_publish_timestamp_{0, 0, RCL_CLOCK_UNINITIALIZED}; | ||
|
||
bool reset(); | ||
void halt(); | ||
|
||
private: | ||
void reset_buffers(); | ||
}; | ||
} // namespace multi_omni_wheel_drive_controller | ||
|
||
#endif // MULTI_OMNI_WHEEL_DRIVE_CONTROLLER__MULTI_OMNI_WHEEL_DRIVE_CONTROLLER_HPP_ |
76 changes: 76 additions & 0 deletions
76
multi_omni_wheel_drive_controller/include/multi_omni_wheel_drive_controller/odometry.hpp
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,76 @@ | ||
// Copyright 2025 Aarav Gupta | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#ifndef MULTI_OMNI_WHEEL_DRIVE_CONTROLLER__ODOMETRY_HPP_ | ||
#define MULTI_OMNI_WHEEL_DRIVE_CONTROLLER__ODOMETRY_HPP_ | ||
|
||
#include <Eigen/Dense> | ||
#include <vector> | ||
|
||
#include "rclcpp/time.hpp" | ||
|
||
namespace multi_omni_wheel_drive_controller | ||
{ | ||
class Odometry | ||
{ | ||
public: | ||
Odometry(); | ||
|
||
bool updateFromPos(const std::vector<double> & wheels_pos, const rclcpp::Time & time); | ||
bool updateFromVel(const std::vector<double> & wheels_vel, const rclcpp::Time & time); | ||
bool updateOpenLoop( | ||
const double & linear_x_vel, const double & linear_y_vel, const double & angular_vel, | ||
const rclcpp::Time & time); | ||
void resetOdometry(); | ||
|
||
double getX() const { return x_; } | ||
double getY() const { return y_; } | ||
double getHeading() const { return heading_; } | ||
double getLinearXVel() const { return linear_x_vel_; } | ||
double getLinearYVel() const { return linear_y_vel_; } | ||
double getAngularVel() const { return angular_vel_; } | ||
|
||
void setParams( | ||
const double & robot_radius, const double & wheel_radius, const double & wheel_offset, | ||
const size_t & wheel_count); | ||
|
||
private: | ||
Eigen::Vector3d compute_robot_velocity(const std::vector<double> & wheels_vel) const; | ||
void integrate(const double & dx, const double & dy, const double & dheading); | ||
|
||
// Current timestamp: | ||
rclcpp::Time timestamp_; | ||
|
||
// Current pose: | ||
double x_; // [m] | ||
double y_; // [m] | ||
double heading_; // [rads] | ||
|
||
// Current velocity: | ||
double linear_x_vel_; // [m/s] | ||
double linear_y_vel_; // [m/s] | ||
double angular_vel_; // [rads/s] | ||
|
||
// Robot kinematic parameters: | ||
double robot_radius_; // [m] | ||
double wheel_radius_; // [m] | ||
double wheel_offset_; // [rads] | ||
|
||
// Previous wheel positions/states [rads]: | ||
std::vector<double> wheels_old_pos_; | ||
}; | ||
|
||
} // namespace multi_omni_wheel_drive_controller | ||
|
||
#endif // MULTI_OMNI_WHEEL_DRIVE_CONTROLLER__ODOMETRY_HPP_ |
Oops, something went wrong.
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.