Skip to content

Commit 5227bf4

Browse files
committed
fix backport issues
1 parent 9b82490 commit 5227bf4

File tree

1 file changed

+50
-57
lines changed

1 file changed

+50
-57
lines changed

velocity_controllers/include/velocity_controllers/integral_sliding_mode_controller.hpp

Lines changed: 50 additions & 57 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,8 @@
3333
#include "geometry_msgs/msg/twist_stamped.hpp"
3434
<<<<<<< HEAD
3535
#include "hydrodynamics/eigen.hpp"
36-
=======
36+
== == ==
37+
=
3738
>>>>>>> origin/main
3839
#include "hydrodynamics/hydrodynamics.hpp"
3940
#include "nav_msgs/msg/odometry.hpp"
@@ -49,85 +50,77 @@
4950
// auto-generated by generate_parameter_library
5051
#include <velocity_controllers/integral_sliding_mode_controller_parameters.hpp>
5152

52-
namespace velocity_controllers
53+
namespace velocity_controllers
5354
{
54-
class IntegralSlidingModeController : public controller_interface::ChainableControllerInterface
55-
{
56-
public:
57-
IntegralSlidingModeController() = default;
58-
59-
auto on_init() -> controller_interface::CallbackReturn override;
55+
class IntegralSlidingModeController : public controller_interface::ChainableControllerInterface
56+
{
57+
public:
58+
IntegralSlidingModeController() = default;
6059

61-
auto on_configure(const rclcpp_lifecycle::State & previous_state) -> controller_interface::CallbackReturn override;
60+
auto on_init() -> controller_interface::CallbackReturn override;
6261

63-
auto on_activate(const rclcpp_lifecycle::State & previous_state) -> controller_interface::CallbackReturn override;
62+
auto on_configure(const rclcpp_lifecycle::State & previous_state) -> controller_interface::CallbackReturn override;
6463

65-
auto command_interface_configuration() const -> controller_interface::InterfaceConfiguration override;
64+
auto on_activate(const rclcpp_lifecycle::State & previous_state) -> controller_interface::CallbackReturn override;
6665

67-
auto state_interface_configuration() const -> controller_interface::InterfaceConfiguration override;
66+
auto command_interface_configuration() const -> controller_interface::InterfaceConfiguration override;
6867

69-
auto update_and_write_commands(const rclcpp::Time & time, const rclcpp::Duration & period)
70-
-> controller_interface::return_type override;
68+
auto state_interface_configuration() const -> controller_interface::InterfaceConfiguration override;
7169

72-
protected:
73-
auto on_export_reference_interfaces() -> std::vector<hardware_interface::CommandInterface> override;
70+
auto update_and_write_commands(const rclcpp::Time & time, const rclcpp::Duration & period)
71+
-> controller_interface::return_type override;
7472

75-
auto update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period)
76-
-> controller_interface::return_type override;
73+
protected:
74+
auto on_export_reference_interfaces() -> std::vector<hardware_interface::CommandInterface> override;
7775

78-
auto update_system_state_values() -> controller_interface::return_type;
76+
auto update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & period)
77+
-> controller_interface::return_type override;
7978

80-
auto update_parameters() -> void;
79+
auto update_system_state_values() -> controller_interface::return_type;
8180

82-
auto configure_parameters() -> controller_interface::CallbackReturn;
81+
auto update_parameters() -> void;
8382

84-
<<<<<<< HEAD
85-
realtime_tools::RealtimeBuffer<geometry_msgs::msg::Twist> reference_;
86-
std::shared_ptr<rclcpp::Subscription<geometry_msgs::msg::Twist>> reference_sub_;
83+
auto configure_parameters() -> controller_interface::CallbackReturn;
8784

88-
realtime_tools::RealtimeBuffer<geometry_msgs::msg::Twist> system_state_;
89-
std::shared_ptr<rclcpp::Subscription<geometry_msgs::msg::TwistStamped>> system_state_sub_;
90-
=======
91-
auto update_and_validate_interfaces() -> controller_interface::return_type;
85+
auto update_and_validate_interfaces() -> controller_interface::return_type;
9286

93-
realtime_tools::RealtimeBuffer<geometry_msgs::msg::Twist> reference_;
94-
std::shared_ptr<rclcpp::Subscription<geometry_msgs::msg::Twist>> reference_sub_;
87+
realtime_tools::RealtimeBuffer<geometry_msgs::msg::Twist> reference_;
88+
std::shared_ptr<rclcpp::Subscription<geometry_msgs::msg::Twist>> reference_sub_;
9589

96-
realtime_tools::RealtimeBuffer<nav_msgs::msg::Odometry> system_state_;
97-
std::shared_ptr<rclcpp::Subscription<nav_msgs::msg::Odometry>> system_state_sub_;
98-
>>>>>>> origin/main
99-
std::vector<double> system_state_values_;
90+
realtime_tools::RealtimeBuffer<nav_msgs::msg::Odometry> system_state_;
91+
std::shared_ptr<rclcpp::Subscription<nav_msgs::msg::Odometry>> system_state_sub_;
92+
std::vector<double> system_state_values_;
10093

101-
// we need the system rotation from the inertial frame to the vehicle frame for the hydrodynamic model
102-
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
103-
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
94+
// we need the system rotation from the inertial frame to the vehicle frame for the hydrodynamic model
95+
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
96+
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
10497

105-
std::string inertial_frame_id_, vehicle_frame_id_;
106-
realtime_tools::RealtimeBuffer<Eigen::Quaterniond> system_rotation_;
98+
std::string inertial_frame_id_, vehicle_frame_id_;
99+
realtime_tools::RealtimeBuffer<Eigen::Quaterniond> system_rotation_;
107100

108-
using ControllerState = control_msgs::msg::MultiDOFStateStamped;
109-
std::shared_ptr<rclcpp::Publisher<ControllerState>> controller_state_pub_;
110-
std::unique_ptr<realtime_tools::RealtimePublisher<ControllerState>> rt_controller_state_pub_;
111-
ControllerState controller_state_;
101+
using ControllerState = control_msgs::msg::MultiDOFStateStamped;
102+
std::shared_ptr<rclcpp::Publisher<ControllerState>> controller_state_pub_;
103+
std::unique_ptr<realtime_tools::RealtimePublisher<ControllerState>> rt_controller_state_pub_;
104+
ControllerState controller_state_;
112105

113-
std::shared_ptr<integral_sliding_mode_controller::ParamListener> param_listener_;
114-
integral_sliding_mode_controller::Params params_;
106+
std::shared_ptr<integral_sliding_mode_controller::ParamListener> param_listener_;
107+
integral_sliding_mode_controller::Params params_;
115108

116-
// the dofs will always be of order six, but we make it configurable to allow for renaming
117-
std::vector<std::string> dofs_;
118-
std::size_t n_dofs_;
109+
// the dofs will always be of order six, but we make it configurable to allow for renaming
110+
std::vector<std::string> dofs_;
111+
std::size_t n_dofs_;
119112

120-
// controller gains/parameters
121-
Eigen::Matrix6d kp_, rho_;
122-
double boundary_thickness_;
113+
// controller gains/parameters
114+
Eigen::Matrix6d kp_, rho_;
115+
double boundary_thickness_;
123116

124-
// controller state
125-
bool first_update_{true};
126-
Eigen::Vector6d init_error_, total_error_;
117+
// controller state
118+
bool first_update_{true};
119+
Eigen::Vector6d init_error_, total_error_;
127120

128-
std::unique_ptr<hydrodynamics::Params> model_;
121+
std::unique_ptr<hydrodynamics::Params> model_;
129122

130-
rclcpp::Logger logger_{rclcpp::get_logger("integral_sliding_mode_controller")};
131-
};
123+
rclcpp::Logger logger_{rclcpp::get_logger("integral_sliding_mode_controller")};
124+
};
132125

133126
} // namespace velocity_controllers

0 commit comments

Comments
 (0)