Class SteeringControllersLibrary
Defined in File steering_controllers_library.hpp
Inheritance Relationships
Base Type
public controller_interface::ChainableControllerInterface
Class Documentation
-
class SteeringControllersLibrary : public controller_interface::ChainableControllerInterface
Public Types
-
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
Public Functions
-
STEERING_CONTROLLERS__VISIBILITY_PUBLIC SteeringControllersLibrary()
- virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC void initialize_implementation_parameter_listener ()=0
- STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init () override
- STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
- STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
- virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn configure_odometry ()=0
- virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC bool update_odometry (const rclcpp::Duration &period)=0
- STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
- STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
- STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
- STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type update_reference_from_subscribers () override
- STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type update_and_write_commands (const rclcpp::Time &time, const rclcpp::Duration &period) override
Protected Types
-
using ControllerStatePublisherOdom = realtime_tools::RealtimePublisher<ControllerStateMsgOdom>
-
using ControllerStatePublisherTf = realtime_tools::RealtimePublisher<ControllerStateMsgTf>
-
using ControllerStatePublisher = realtime_tools::RealtimePublisher<AckermanControllerState>
Protected Functions
-
controller_interface::CallbackReturn set_interface_numbers(size_t nr_state_itfs, size_t nr_cmd_itfs, size_t nr_ref_itfs)
-
std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override
-
bool on_set_chained_mode(bool chained_mode) override
Protected Attributes
-
std::shared_ptr<steering_controllers_library::ParamListener> param_listener_
-
steering_controllers_library::Params params_
-
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)
-
rclcpp::Publisher<ControllerStateMsgOdom>::SharedPtr odom_s_publisher_
-
rclcpp::Publisher<ControllerStateMsgTf>::SharedPtr tf_odom_s_publisher_
-
std::unique_ptr<ControllerStatePublisherOdom> rt_odom_state_publisher_
-
std::unique_ptr<ControllerStatePublisherTf> rt_tf_odom_state_publisher_
-
steering_odometry::SteeringOdometry odometry_
Odometry:
-
AckermanControllerState published_state_
-
rclcpp::Publisher<AckermanControllerState>::SharedPtr controller_s_publisher_
-
std::unique_ptr<ControllerStatePublisher> controller_state_publisher_
-
size_t nr_state_itfs_
-
size_t nr_cmd_itfs_
-
size_t nr_ref_itfs_
-
double last_linear_velocity_ = 0.0
-
double last_angular_velocity_ = 0.0
-
std::vector<std::string> rear_wheels_state_names_
-
std::vector<std::string> front_wheels_state_names_
-
using ControllerAckermannReferenceMsg = ackermann_msgs::msg::AckermannDriveStamped