Skip to content
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

Fix RealtimeBox API changes #1385

Merged
merged 8 commits into from
Dec 4, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,7 @@ class DiffDriveController : public controller_interface::ControllerInterface
rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;

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

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

Expand Down
29 changes: 15 additions & 14 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,26 +111,27 @@ controller_interface::return_type DiffDriveController::update(
return controller_interface::return_type::OK;
}

std::shared_ptr<TwistStamped> last_command_msg;
received_velocity_msg_ptr_.get(last_command_msg);
// if the mutex is unable to lock, last_command_msg_ won't be updated
received_velocity_msg_ptr_.try_get([this](const std::shared_ptr<TwistStamped> & msg)
{ last_command_msg_ = msg; });

if (last_command_msg == nullptr)
if (last_command_msg_ == nullptr)
{
RCLCPP_WARN(logger, "Velocity message received was a nullptr.");
return controller_interface::return_type::ERROR;
}

const auto age_of_last_command = time - last_command_msg->header.stamp;
const auto age_of_last_command = time - last_command_msg_->header.stamp;
// Brake if cmd_vel has timeout, override the stored command
if (age_of_last_command > cmd_vel_timeout_)
{
last_command_msg->twist.linear.x = 0.0;
last_command_msg->twist.angular.z = 0.0;
last_command_msg_->twist.linear.x = 0.0;
last_command_msg_->twist.angular.z = 0.0;
}

// command may be limited further by SpeedLimit,
// without affecting the stored twist command
TwistStamped 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 @@ -325,12 +326,12 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
limited_velocity_publisher_);
}

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

last_command_msg_ = std::make_shared<TwistStamped>();
received_velocity_msg_ptr_.set([this](std::shared_ptr<TwistStamped> & stored_value)
{ stored_value = last_command_msg_; });
// Fill last two commands with default constructed commands
previous_commands_.emplace(empty_twist);
previous_commands_.emplace(empty_twist);
previous_commands_.emplace(*last_command_msg_);
previous_commands_.emplace(*last_command_msg_);

// initialize command subscriber
velocity_command_subscriber_ = get_node()->create_subscription<TwistStamped>(
Expand All @@ -350,7 +351,8 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
"time, this message will only be shown once");
msg->header.stamp = get_node()->get_clock()->now();
}
received_velocity_msg_ptr_.set(std::move(msg));
received_velocity_msg_ptr_.set([msg](std::shared_ptr<TwistStamped> & stored_value)
{ stored_value = std::move(msg); });
});

// initialize odometry publisher and message
Expand Down Expand Up @@ -476,7 +478,6 @@ controller_interface::CallbackReturn DiffDriveController::on_cleanup(
return controller_interface::CallbackReturn::ERROR;
}

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

Expand Down
3 changes: 2 additions & 1 deletion diff_drive_controller/test/test_diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,8 @@ class TestableDiffDriveController : public diff_drive_controller::DiffDriveContr
std::shared_ptr<geometry_msgs::msg::TwistStamped> getLastReceivedTwist()
{
std::shared_ptr<geometry_msgs::msg::TwistStamped> ret;
received_velocity_msg_ptr_.get(ret);
received_velocity_msg_ptr_.get(
[&ret](const std::shared_ptr<geometry_msgs::msg::TwistStamped> & msg) { ret = msg; });
return ret;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,7 @@ class TricycleController : public controller_interface::ControllerInterface
rclcpp::Subscription<TwistStamped>::SharedPtr velocity_command_subscriber_ = nullptr;

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

rclcpp::Service<std_srvs::srv::Empty>::SharedPtr reset_odom_service_;

Expand Down
26 changes: 14 additions & 12 deletions tricycle_controller/src/tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,25 +95,27 @@ controller_interface::return_type TricycleController::update(
}
return controller_interface::return_type::OK;
}
std::shared_ptr<TwistStamped> last_command_msg;
received_velocity_msg_ptr_.get(last_command_msg);
if (last_command_msg == nullptr)

// if the mutex is unable to lock, last_command_msg_ won't be updated
received_velocity_msg_ptr_.try_get([this](const std::shared_ptr<TwistStamped> & msg)
{ last_command_msg_ = msg; });
if (last_command_msg_ == nullptr)
{
RCLCPP_WARN(get_node()->get_logger(), "Velocity message received was a nullptr.");
return controller_interface::return_type::ERROR;
}

const auto age_of_last_command = time - last_command_msg->header.stamp;
const auto age_of_last_command = time - last_command_msg_->header.stamp;
// Brake if cmd_vel has timeout, override the stored command
if (age_of_last_command > cmd_vel_timeout_)
{
last_command_msg->twist.linear.x = 0.0;
last_command_msg->twist.angular.z = 0.0;
last_command_msg_->twist.linear.x = 0.0;
last_command_msg_->twist.angular.z = 0.0;
}

// command may be limited further by Limiters,
// without affecting the stored twist command
TwistStamped command = *last_command_msg;
TwistStamped command = *last_command_msg_;
double & linear_command = command.twist.linear.x;
double & angular_command = command.twist.angular.z;
double Ws_read = traction_joint_[0].velocity_state.get().get_value(); // in radians/s
Expand Down Expand Up @@ -271,9 +273,9 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
return CallbackReturn::ERROR;
}

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

last_command_msg_ = std::make_shared<TwistStamped>();
received_velocity_msg_ptr_.set([this](std::shared_ptr<TwistStamped> & stored_value)
{ stored_value = last_command_msg_; });
// Fill last two commands with default constructed commands
const AckermannDrive empty_ackermann_drive;
previous_commands_.emplace(empty_ackermann_drive);
Expand Down Expand Up @@ -307,7 +309,8 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
"time, this message will only be shown once");
msg->header.stamp = get_node()->get_clock()->now();
}
received_velocity_msg_ptr_.set(std::move(msg));
received_velocity_msg_ptr_.set([msg](std::shared_ptr<TwistStamped> & stored_value)
{ stored_value = std::move(msg); });
});

// initialize odometry publisher and message
Expand Down Expand Up @@ -397,7 +400,6 @@ CallbackReturn TricycleController::on_cleanup(const rclcpp_lifecycle::State &)
return CallbackReturn::ERROR;
}

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

Expand Down
3 changes: 2 additions & 1 deletion tricycle_controller/test/test_tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,8 @@ class TestableTricycleController : public tricycle_controller::TricycleControlle
std::shared_ptr<geometry_msgs::msg::TwistStamped> getLastReceivedTwist()
{
std::shared_ptr<geometry_msgs::msg::TwistStamped> ret;
received_velocity_msg_ptr_.get(ret);
received_velocity_msg_ptr_.get(
[&ret](const std::shared_ptr<geometry_msgs::msg::TwistStamped> & msg) { ret = msg; });
return ret;
}

Expand Down
Loading