Skip to content

Commit

Permalink
Rename Twist->TwistStamped
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 26, 2024
1 parent 9b344c7 commit 5b8df6f
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace diff_drive_controller
{
class DiffDriveController : public controller_interface::ControllerInterface
{
using Twist = geometry_msgs::msg::TwistStamped;
using TwistStamped = geometry_msgs::msg::TwistStamped;

public:
DIFF_DRIVE_CONTROLLER_PUBLIC
Expand Down Expand Up @@ -128,20 +128,20 @@ class DiffDriveController : public controller_interface::ControllerInterface
realtime_odometry_transform_publisher_ = nullptr;

bool subscriber_is_active_ = false;
rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ = nullptr;
rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;

realtime_tools::RealtimeBox<std::shared_ptr<Twist>> received_velocity_msg_ptr_{nullptr};
realtime_tools::RealtimeBox<std::shared_ptr<TwistStamped>> received_velocity_msg_ptr_{nullptr};

std::queue<Twist> previous_commands_; // last two commands
std::queue<TwistStamped> previous_commands_; // last two commands

// speed limiters
SpeedLimiter limiter_linear_;
SpeedLimiter limiter_angular_;

bool publish_limited_velocity_ = false;
std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ = nullptr;
std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
nullptr;
std::shared_ptr<rclcpp::Publisher<TwistStamped>> limited_velocity_publisher_ = nullptr;
std::shared_ptr<realtime_tools::RealtimePublisher<TwistStamped>>
realtime_limited_velocity_publisher_ = nullptr;

rclcpp::Time previous_update_timestamp_{0};

Expand Down
23 changes: 12 additions & 11 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ controller_interface::return_type DiffDriveController::update(
return controller_interface::return_type::OK;
}

std::shared_ptr<Twist> last_command_msg;
std::shared_ptr<TwistStamped> last_command_msg;
received_velocity_msg_ptr_.get(last_command_msg);

if (last_command_msg == nullptr)
Expand All @@ -130,7 +130,7 @@ controller_interface::return_type DiffDriveController::update(

// command may be limited further by SpeedLimit,
// without affecting the stored twist command
Twist command = *last_command_msg;
TwistStamped command = *last_command_msg;
double & linear_command = command.twist.linear.x;
double & angular_command = command.twist.angular.z;

Expand Down Expand Up @@ -318,23 +318,24 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(

if (publish_limited_velocity_)
{
limited_velocity_publisher_ =
get_node()->create_publisher<Twist>(DEFAULT_COMMAND_OUT_TOPIC, rclcpp::SystemDefaultsQoS());
limited_velocity_publisher_ = get_node()->create_publisher<TwistStamped>(
DEFAULT_COMMAND_OUT_TOPIC, rclcpp::SystemDefaultsQoS());
realtime_limited_velocity_publisher_ =
std::make_shared<realtime_tools::RealtimePublisher<Twist>>(limited_velocity_publisher_);
std::make_shared<realtime_tools::RealtimePublisher<TwistStamped>>(
limited_velocity_publisher_);
}

const Twist empty_twist;
received_velocity_msg_ptr_.set(std::make_shared<Twist>(empty_twist));
const TwistStamped empty_twist;
received_velocity_msg_ptr_.set(std::make_shared<TwistStamped>(empty_twist));

// Fill last two commands with default constructed commands
previous_commands_.emplace(empty_twist);
previous_commands_.emplace(empty_twist);

// initialize command subscriber
velocity_command_subscriber_ = get_node()->create_subscription<Twist>(
velocity_command_subscriber_ = get_node()->create_subscription<TwistStamped>(
DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS(),
[this](const std::shared_ptr<Twist> msg) -> void
[this](const std::shared_ptr<TwistStamped> msg) -> void
{
if (!subscriber_is_active_)
{
Expand Down Expand Up @@ -475,7 +476,7 @@ controller_interface::CallbackReturn DiffDriveController::on_cleanup(
return controller_interface::CallbackReturn::ERROR;
}

received_velocity_msg_ptr_.set(std::make_shared<Twist>());
received_velocity_msg_ptr_.set(std::make_shared<TwistStamped>());
return controller_interface::CallbackReturn::SUCCESS;
}

Expand All @@ -493,7 +494,7 @@ bool DiffDriveController::reset()
odometry_.resetOdometry();

// release the old queue
std::queue<Twist> empty;
std::queue<TwistStamped> empty;
std::swap(previous_commands_, empty);

registered_left_wheel_handles_.clear();
Expand Down

0 comments on commit 5b8df6f

Please sign in to comment.