Skip to content

Commit

Permalink
Fix even more API changes
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jun 6, 2024
1 parent 239bf3c commit 30f6030
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 10 deletions.
6 changes: 2 additions & 4 deletions pid_controller/include/pid_controller/pid_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,10 +80,6 @@ class PidController : public controller_interface::ChainableControllerInterface
controller_interface::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state) override;

PID_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::return_type update_reference_from_subscribers(
const rclcpp::Time & time, const rclcpp::Duration & period) override;

PID_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::return_type update_and_write_commands(
const rclcpp::Time & time, const rclcpp::Duration & period) override;
Expand All @@ -94,6 +90,8 @@ class PidController : public controller_interface::ChainableControllerInterface
using ControllerStateMsg = control_msgs::msg::MultiDOFStateStamped;

protected:
controller_interface::return_type update_reference_from_subscribers() override;

std::shared_ptr<pid_controller::ParamListener> param_listener_;
pid_controller::Params params_;

Expand Down
17 changes: 11 additions & 6 deletions pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,16 @@ namespace
{ // utility

// Changed services history QoS to keep all so we don't lose any client service calls
rclcpp::QoS qos_services =
rclcpp::QoS(rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 1))
.reliable()
.durability_volatile();
static const rmw_qos_profile_t qos_services = {
RMW_QOS_POLICY_HISTORY_KEEP_ALL,
1, // message queue depth
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
RMW_QOS_POLICY_DURABILITY_VOLATILE,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
false};

using ControllerCommandMsg = pid_controller::PidController::ControllerReferenceMsg;

Expand Down Expand Up @@ -377,8 +383,7 @@ controller_interface::CallbackReturn PidController::on_deactivate(
return controller_interface::CallbackReturn::SUCCESS;
}

controller_interface::return_type PidController::update_reference_from_subscribers(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
controller_interface::return_type PidController::update_reference_from_subscribers()
{
auto current_ref = input_ref_.readFromRT();

Expand Down

0 comments on commit 30f6030

Please sign in to comment.