Skip to content

Commit

Permalink
Merge branch 'master' into add-mecanum-drive-controller
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl authored Jul 31, 2024
2 parents 57fac95 + 33e35f0 commit 41596c4
Show file tree
Hide file tree
Showing 163 changed files with 3,280 additions and 786 deletions.
8 changes: 4 additions & 4 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ repos:

# Python hooks
- repo: https://github.com/asottile/pyupgrade
rev: v3.15.2
rev: v3.16.0
hooks:
- id: pyupgrade
args: [--py36-plus]
Expand All @@ -56,14 +56,14 @@ repos:
args: ["--line-length=99"]

- repo: https://github.com/pycqa/flake8
rev: 7.0.0
rev: 7.1.0
hooks:
- id: flake8
args: ["--extend-ignore=E501"]

# CPP hooks
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v18.1.5
rev: v18.1.8
hooks:
- id: clang-format
args: ['-fallback-style=none', '-i']
Expand Down Expand Up @@ -133,7 +133,7 @@ repos:
exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$

- repo: https://github.com/python-jsonschema/check-jsonschema
rev: 0.28.4
rev: 0.28.6
hooks:
- id: check-github-workflows
args: ["--verbose"]
Expand Down
22 changes: 22 additions & 0 deletions ackermann_steering_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,28 @@
Changelog for package ackermann_steering_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.12.0 (2024-07-23)
-------------------
* Add missing includes (`#1226 <https://github.com/ros-controls/ros2_controllers/issues/1226>`_)
* Change the subscription timeout in the tests to 5ms (`#1219 <https://github.com/ros-controls/ros2_controllers/issues/1219>`_)
* Unused header cleanup (`#1199 <https://github.com/ros-controls/ros2_controllers/issues/1199>`_)
* Fix WaitSet issue in tests (`#1206 <https://github.com/ros-controls/ros2_controllers/issues/1206>`_)
* Fix parallel gripper controller CI (`#1202 <https://github.com/ros-controls/ros2_controllers/issues/1202>`_)
* Contributors: Christoph Fröhlich, Henry Moore, Sai Kishor Kothakota

4.11.0 (2024-07-09)
-------------------
* added changes corresponding to the logger and clock propagation in ResourceManager (`#1184 <https://github.com/ros-controls/ros2_controllers/issues/1184>`_)
* Fix steering controllers library kinematics (`#1150 <https://github.com/ros-controls/ros2_controllers/issues/1150>`_)
* Contributors: Christoph Fröhlich, Sai Kishor Kothakota

4.10.0 (2024-07-01)
-------------------
* [Steering controllers library] Reference interfaces are body twist (`#1168 <https://github.com/ros-controls/ros2_controllers/issues/1168>`_)
* Fix steering controllers library code documentation and naming (`#1149 <https://github.com/ros-controls/ros2_controllers/issues/1149>`_)
* Remove unstamped twist subscribers + parameters (`#1151 <https://github.com/ros-controls/ros2_controllers/issues/1151>`_)
* Contributors: Christoph Fröhlich, Sai Kishor Kothakota, Quique Llorente

4.9.0 (2024-06-05)
------------------

Expand Down
2 changes: 1 addition & 1 deletion ackermann_steering_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ackermann_steering_controller</name>
<version>4.9.0</version>
<version>4.12.0</version>
<description>Steering controller for Ackermann kinematics. Rear fixed wheels are powering the vehicle and front wheels are steering it.</description>
<license>Apache License 2.0</license>
<maintainer email="[email protected]">Bence Magyar</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,8 @@

#include "test_ackermann_steering_controller.hpp"

#include <limits>
#include <memory>
#include <string>
#include <utility>
#include <vector>

class AckermannSteeringControllerTest
Expand Down Expand Up @@ -84,7 +82,7 @@ TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfsTIME
// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), joint_reference_interfaces_.size());
for (size_t i = 0; i < joint_reference_interfaces_.size(); ++i)
Expand Down Expand Up @@ -173,6 +171,7 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic)
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
Expand Down Expand Up @@ -211,8 +210,9 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic_chained)
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
EXPECT_NEAR(

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
controller_->command_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
EXPECT_NEAR(
Expand Down Expand Up @@ -255,12 +255,13 @@ TEST_F(AckermannSteeringControllerTest, receive_message_and_publish_updated_stat
EXPECT_EQ(msg.steering_angle_command[1], 4.4);

publish_commands();
ASSERT_TRUE(controller_->wait_for_commands(executor));
controller_->wait_for_commands(executor);

ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
Expand All @@ -276,6 +277,7 @@ TEST_F(AckermannSteeringControllerTest, receive_message_and_publish_updated_stat

subscribe_and_get_messages(msg);

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
msg.linear_velocity_command[CMD_TRACTION_RIGHT_WHEEL], 0.22222222222222224, COMMON_THRESHOLD);
EXPECT_NEAR(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,22 +15,20 @@
#ifndef TEST_ACKERMANN_STEERING_CONTROLLER_HPP_
#define TEST_ACKERMANN_STEERING_CONTROLLER_HPP_

#include <gmock/gmock.h>

#include <chrono>
#include <limits>
#include <memory>
#include <string>
#include <tuple>
#include <utility>
#include <vector>

#include "ackermann_steering_controller/ackermann_steering_controller.hpp"
#include "gmock/gmock.h"
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "rclcpp/parameter_value.hpp"
#include "rclcpp/executor.hpp"
#include "rclcpp/executors.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

using ControllerStateMsg =
Expand Down Expand Up @@ -76,14 +74,7 @@ class TestableAckermannSteeringController
controller_interface::CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state) override
{
auto ret =
ackermann_steering_controller::AckermannSteeringController::on_configure(previous_state);
// Only if on_configure is successful create subscription
if (ret == CallbackReturn::SUCCESS)
{
ref_subscriber_wait_set_.add_subscription(ref_subscriber_twist_);
}
return ret;
return ackermann_steering_controller::AckermannSteeringController::on_configure(previous_state);
}

controller_interface::CallbackReturn on_activate(
Expand All @@ -97,30 +88,25 @@ class TestableAckermannSteeringController
* @brief wait_for_command blocks until a new ControllerReferenceMsg is received.
* Requires that the executor is not spinned elsewhere between the
* message publication and the call to this function.
*
* @return true if new ControllerReferenceMsg msg was received, false if timeout.
*/
bool wait_for_command(
rclcpp::Executor & executor, rclcpp::WaitSet & subscriber_wait_set,
void wait_for_command(
rclcpp::Executor & executor,
const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500})
{
bool success = subscriber_wait_set.wait(timeout).kind() == rclcpp::WaitResultKind::Ready;
if (success)
auto until = get_node()->get_clock()->now() + timeout;
while (get_node()->get_clock()->now() < until)
{
executor.spin_some();
std::this_thread::sleep_for(std::chrono::microseconds(10));
}
return success;
}

bool wait_for_commands(
void wait_for_commands(
rclcpp::Executor & executor,
const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500})
{
return wait_for_command(executor, ref_subscriber_wait_set_, timeout);
wait_for_command(executor, timeout);
}

private:
rclcpp::WaitSet ref_subscriber_wait_set_;
};

// We are using template class here for easier reuse of Fixture in specializations of controllers
Expand Down Expand Up @@ -214,36 +200,43 @@ class AckermannSteeringControllerFixture : public ::testing::Test
void subscribe_and_get_messages(ControllerStateMsg & msg)
{
// create a new subscriber
ControllerStateMsg::SharedPtr received_msg;
rclcpp::Node test_subscription_node("test_subscription_node");
auto subs_callback = [&](const ControllerStateMsg::SharedPtr) {};
auto subs_callback = [&](const ControllerStateMsg::SharedPtr cb_msg) { received_msg = cb_msg; };
auto subscription = test_subscription_node.create_subscription<ControllerStateMsg>(
"/test_ackermann_steering_controller/controller_state", 10, subs_callback);
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(test_subscription_node.get_node_base_interface());

// call update to publish the test value
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);

// call update to publish the test value
// since update doesn't guarantee a published message, republish until received
int max_sub_check_loop_count = 5; // max number of tries for pub/sub loop
rclcpp::WaitSet wait_set; // block used to wait on message
wait_set.add_subscription(subscription);
while (max_sub_check_loop_count--)
{
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01));
const auto timeout = std::chrono::milliseconds{5};
const auto until = test_subscription_node.get_clock()->now() + timeout;
while (!received_msg && test_subscription_node.get_clock()->now() < until)
{
executor.spin_some();
std::this_thread::sleep_for(std::chrono::microseconds(10));
}
// check if message has been received
if (wait_set.wait(std::chrono::milliseconds(2)).kind() == rclcpp::WaitResultKind::Ready)
if (received_msg.get())
{
break;
}
}
ASSERT_GE(max_sub_check_loop_count, 0) << "Test was unable to publish a message through "
"controller/broadcaster update loop";
ASSERT_TRUE(received_msg);

// take message from subscription
rclcpp::MessageInfo msg_info;
ASSERT_TRUE(subscription->take(msg, msg_info));
msg = *received_msg;
}

void publish_commands(const double linear = 0.1, const double angular = 0.2)
Expand Down Expand Up @@ -302,7 +295,7 @@ class AckermannSteeringControllerFixture : public ::testing::Test

std::array<double, 4> joint_state_values_ = {0.5, 0.5, 0.0, 0.0};
std::array<double, 4> joint_command_values_ = {1.1, 3.3, 2.2, 4.4};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/position"};
std::array<std::string, 2> joint_reference_interfaces_ = {"linear/velocity", "angular/velocity"};
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,8 @@

#include "test_ackermann_steering_controller.hpp"

#include <limits>
#include <memory>
#include <string>
#include <utility>
#include <vector>

class AckermannSteeringControllerTest
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,7 @@ TEST(TestLoadAckermannSteeringController, load_controller)
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

controller_manager::ControllerManager cm(
std::make_unique<hardware_interface::ResourceManager>(
ros2_control_test_assets::minimal_robot_urdf),
executor, "test_controller_manager");
executor, ros2_control_test_assets::minimal_robot_urdf, true, "test_controller_manager");

ASSERT_NE(
cm.load_controller(
Expand Down
16 changes: 16 additions & 0 deletions admittance_controller/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,22 @@
Changelog for package admittance_controller
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.12.0 (2024-07-23)
-------------------
* Change the subscription timeout in the tests to 5ms (`#1219 <https://github.com/ros-controls/ros2_controllers/issues/1219>`_)
* Unused header cleanup (`#1199 <https://github.com/ros-controls/ros2_controllers/issues/1199>`_)
* Fix WaitSet issue in tests (`#1206 <https://github.com/ros-controls/ros2_controllers/issues/1206>`_)
* Fix parallel gripper controller CI (`#1202 <https://github.com/ros-controls/ros2_controllers/issues/1202>`_)
* Contributors: Henry Moore, Sai Kishor Kothakota

4.11.0 (2024-07-09)
-------------------
* added changes corresponding to the logger and clock propagation in ResourceManager (`#1184 <https://github.com/ros-controls/ros2_controllers/issues/1184>`_)
* Contributors: Sai Kishor Kothakota

4.10.0 (2024-07-01)
-------------------

4.9.0 (2024-06-05)
------------------

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#ifndef ADMITTANCE_CONTROLLER__ADMITTANCE_CONTROLLER_HPP_
#define ADMITTANCE_CONTROLLER__ADMITTANCE_CONTROLLER_HPP_

#include <chrono>
#include <memory>
#include <string>
#include <vector>
Expand All @@ -29,21 +28,14 @@
#include "admittance_controller/visibility_control.h"
#include "control_msgs/msg/admittance_controller_state.hpp"
#include "controller_interface/chainable_controller_interface.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/wrench_stamped.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "pluginlib/class_loader.hpp"
#include "rclcpp/duration.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_publisher.h"
#include "semantic_components/force_torque_sensor.hpp"

#include "trajectory_msgs/msg/joint_trajectory.hpp"

namespace admittance_controller
{
using ControllerStateMsg = control_msgs::msg::AdmittanceControllerState;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,23 +18,16 @@
#define ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_HPP_

#include <Eigen/Core>
#include <Eigen/Geometry>
#include <map>

#include <memory>
#include <string>
#include <vector>

#include "admittance_controller_parameters.hpp"
#include "control_msgs/msg/admittance_controller_state.hpp"
#include "control_toolbox/filters.hpp"
#include "controller_interface/controller_interface.hpp"
#include "geometry_msgs/msg/wrench_stamped.hpp"
#include "controller_interface/controller_interface_base.hpp"
#include "kinematics_interface/kinematics_interface.hpp"
#include "pluginlib/class_loader.hpp"
#include "tf2_eigen/tf2_eigen.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2_kdl/tf2_kdl.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"

namespace admittance_controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,10 @@
#include <memory>
#include <vector>

#include <control_toolbox/filters.hpp>
#include <tf2_eigen/tf2_eigen.hpp>

#include "rclcpp/duration.hpp"
#include "rclcpp/utilities.hpp"
#include "tf2_ros/transform_listener.h"

namespace admittance_controller
{
Expand Down
2 changes: 1 addition & 1 deletion admittance_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>admittance_controller</name>
<version>4.9.0</version>
<version>4.12.0</version>
<description>Implementation of admittance controllers for different input and output interface.</description>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Bence Magyar</maintainer>
Expand Down
Loading

0 comments on commit 41596c4

Please sign in to comment.