Skip to content

Commit

Permalink
Generic controller state msg instead of Ackermann msg.
Browse files Browse the repository at this point in the history
  • Loading branch information
mbharatheesha committed Nov 10, 2023
1 parent dc5b3b4 commit 8923c5f
Show file tree
Hide file tree
Showing 8 changed files with 9 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

using ControllerStateMsg =
steering_controllers_library::SteeringControllersLibrary::AckermanControllerState;
steering_controllers_library::SteeringControllersLibrary::SteeringControllerStateMsg;
using ControllerReferenceMsg =
steering_controllers_library::SteeringControllersLibrary::ControllerTwistReferenceMsg;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

using ControllerStateMsg =
steering_controllers_library::SteeringControllersLibrary::AckermanControllerState;
steering_controllers_library::SteeringControllersLibrary::SteeringControllerStateMsg;
using ControllerReferenceMsg =
steering_controllers_library::SteeringControllersLibrary::ControllerTwistReferenceMsg;

Expand Down
1 change: 0 additions & 1 deletion steering_controllers_library/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
tf2
tf2_msgs
tf2_geometry_msgs
ackermann_msgs
)

find_package(ament_cmake REQUIRED)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@
#include "steering_controllers_library_parameters.hpp"

// TODO(anyone): Replace with controller specific messages
#include "ackermann_msgs/msg/ackermann_drive_stamped.hpp"
#include "control_msgs/msg/steering_controller_status.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
Expand Down Expand Up @@ -81,11 +80,10 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type
update_and_write_commands(const rclcpp::Time & time, const rclcpp::Duration & period) override;

using ControllerAckermannReferenceMsg = ackermann_msgs::msg::AckermannDriveStamped;
using ControllerTwistReferenceMsg = geometry_msgs::msg::TwistStamped;
using ControllerStateMsgOdom = nav_msgs::msg::Odometry;
using ControllerStateMsgTf = tf2_msgs::msg::TFMessage;
using AckermanControllerState = control_msgs::msg::SteeringControllerStatus;
using SteeringControllerStateMsg = control_msgs::msg::SteeringControllerStatus;

protected:
controller_interface::CallbackReturn set_interface_numbers(
Expand All @@ -96,7 +94,6 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl

// Command subscribers and Controller State publisher
rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_twist_ = nullptr;
rclcpp::Subscription<ControllerTwistReferenceMsg>::SharedPtr ref_subscriber_ackermann_ = nullptr;
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr ref_subscriber_unstamped_ = nullptr;
realtime_tools::RealtimeBuffer<std::shared_ptr<ControllerTwistReferenceMsg>> input_ref_;
rclcpp::Duration ref_timeout_ = rclcpp::Duration::from_seconds(0.0); // 0ms
Expand All @@ -118,10 +115,10 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl
/// Odometry:
steering_odometry::SteeringOdometry odometry_;

AckermanControllerState published_state_;
SteeringControllerStateMsg published_state_;

using ControllerStatePublisher = realtime_tools::RealtimePublisher<AckermanControllerState>;
rclcpp::Publisher<AckermanControllerState>::SharedPtr controller_s_publisher_;
using ControllerStatePublisher = realtime_tools::RealtimePublisher<SteeringControllerStateMsg>;
rclcpp::Publisher<SteeringControllerStateMsg>::SharedPtr controller_s_publisher_;
std::unique_ptr<ControllerStatePublisher> controller_state_publisher_;

// name constants for state interfaces
Expand Down
1 change: 0 additions & 1 deletion steering_controllers_library/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
<depend>tf2</depend>
<depend>tf2_msgs</depend>
<depend>tf2_geometry_msgs</depend>
<depend>ackermann_msgs</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>controller_manager</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure(
try
{
// State publisher
controller_s_publisher_ = get_node()->create_publisher<AckermanControllerState>(
controller_s_publisher_ = get_node()->create_publisher<SteeringControllerStateMsg>(
"~/controller_state", rclcpp::SystemDefaultsQoS());
controller_state_publisher_ =
std::make_unique<ControllerStatePublisher>(controller_s_publisher_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include "steering_controllers_library/steering_controllers_library.hpp"

using ControllerStateMsg =
steering_controllers_library::SteeringControllersLibrary::AckermanControllerState;
steering_controllers_library::SteeringControllersLibrary::SteeringControllerStateMsg;
using ControllerReferenceMsg =
steering_controllers_library::SteeringControllersLibrary::ControllerTwistReferenceMsg;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include "tricycle_steering_controller/tricycle_steering_controller.hpp"

using ControllerStateMsg =
steering_controllers_library::SteeringControllersLibrary::AckermanControllerState;
steering_controllers_library::SteeringControllersLibrary::SteeringControllerStateMsg;
using ControllerReferenceMsg =
steering_controllers_library::SteeringControllersLibrary::ControllerTwistReferenceMsg;

Expand Down

0 comments on commit 8923c5f

Please sign in to comment.