ros2_control - rolling
Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
steering_controllers_library::SteeringControllersLibrary Class Referenceabstract
Inheritance diagram for steering_controllers_library::SteeringControllersLibrary:
Inheritance graph
[legend]
Collaboration diagram for steering_controllers_library::SteeringControllersLibrary:
Collaboration graph
[legend]

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 Member Functions

virtual STEERING_CONTROLLERS__VISIBILITY_PUBLIC void initialize_implementation_parameter_listener ()=0
 
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init () override
 Extending interface with initialization method which is individual for each controller.
 
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
 Get configuration for controller's required command interfaces. More...
 
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
 Get configuration for controller's required state interfaces. More...
 
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 (const rclcpp::Time &time, const rclcpp::Duration &period) override
 Update reference from input topics when not in chained mode. More...
 
STEERING_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type update_and_write_commands (const rclcpp::Time &time, const rclcpp::Duration &period) override
 Execute calculations of the controller and update command interfaces. More...
 
- Public Member Functions inherited from controller_interface::ChainableControllerInterface
CONTROLLER_INTERFACE_PUBLIC return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) final
 
CONTROLLER_INTERFACE_PUBLIC bool is_chainable () const final
 Get information if a controller is chainable. More...
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::StateInterfaceexport_state_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterfaceexport_reference_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode (bool chained_mode) final
 
CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode () const final
 Get information if a controller is currently in chained mode. More...
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
virtual CONTROLLER_INTERFACE_PUBLIC void assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces)
 Method that assigns the Loaned interfaces to the controller. More...
 
virtual CONTROLLER_INTERFACE_PUBLIC void release_interfaces ()
 Method that releases the Loaned interfaces from the controller. More...
 
CONTROLLER_INTERFACE_PUBLIC return_type init (const std::string &controller_name, const std::string &urdf, unsigned int cm_update_rate, const std::string &node_namespace, const rclcpp::NodeOptions &node_options)
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure ()
 Custom configure method to read additional parameters for controller-nodes.
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node ()
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > get_node () const
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state () const
 
CONTROLLER_INTERFACE_PUBLIC unsigned int get_update_rate () const
 
CONTROLLER_INTERFACE_PUBLIC bool is_async () const
 
CONTROLLER_INTERFACE_PUBLIC const std::string & get_robot_description () const
 
virtual CONTROLLER_INTERFACE_PUBLIC rclcpp::NodeOptions define_custom_node_options () const
 
template<typename ParameterT >
auto auto_declare (const std::string &name, const ParameterT &default_value)
 Declare and initialize a parameter with a type. More...
 

Protected Types

using ControllerStatePublisherOdom = realtime_tools::RealtimePublisher< ControllerStateMsgOdom >
 
using ControllerStatePublisherTf = realtime_tools::RealtimePublisher< ControllerStateMsgTf >
 
using ControllerStatePublisher = realtime_tools::RealtimePublisher< AckermanControllerState >
 

Protected Member 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::CommandInterfaceon_export_reference_interfaces () override
 
bool on_set_chained_mode (bool chained_mode) override
 Virtual method that each chainable controller should implement to switch chained mode. More...
 
- Protected Member Functions inherited from controller_interface::ChainableControllerInterface
virtual std::vector< hardware_interface::StateInterfaceon_export_state_interfaces ()
 

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
 
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< ControllerStatePublisherOdomrt_odom_state_publisher_
 
std::unique_ptr< ControllerStatePublisherTfrt_tf_odom_state_publisher_
 
steering_odometry::SteeringOdometry odometry_
 Odometry:
 
AckermanControllerState published_state_
 
rclcpp::Publisher< AckermanControllerState >::SharedPtr controller_s_publisher_
 
std::unique_ptr< ControllerStatePublishercontroller_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_
 
- Protected Attributes inherited from controller_interface::ChainableControllerInterface
std::vector< std::string > exported_state_interface_names_
 Storage of values for state interfaces.
 
std::vector< double > state_interfaces_values_
 
std::vector< std::string > exported_reference_interface_names_
 Storage of values for reference interfaces.
 
std::vector< double > reference_interfaces_
 
- Protected Attributes inherited from controller_interface::ControllerInterfaceBase
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 

Member Function Documentation

◆ command_interface_configuration()

controller_interface::InterfaceConfiguration steering_controllers_library::SteeringControllersLibrary::command_interface_configuration ( ) const
overridevirtual

Get configuration for controller's required command interfaces.

Method used by the controller_manager to get the set of command interfaces used by the controller. Each controller can use individual method to determine interface names that in simples case have the following format: <joint>/<interface>. The method is called only in inactive or active state, i.e., on_configure has to be called first. The configuration is used to check if controller can be activated and to claim interfaces from hardware. The claimed interfaces are populated in the command_interfaces_ member.

Returns
configuration of command interfaces.

Implements controller_interface::ControllerInterfaceBase.

◆ on_export_reference_interfaces()

std::vector< hardware_interface::CommandInterface > steering_controllers_library::SteeringControllersLibrary::on_export_reference_interfaces ( )
overrideprotectedvirtual

Virtual method that each chainable controller should implement to export its read/write chainable interfaces. Each chainable controller implements this methods where all input (command) interfaces are exported. The method has the same meaning as export_command_interface method from hardware_interface::SystemInterface or hardware_interface::ActuatorInterface.

Returns
list of CommandInterfaces that other controller can use as their outputs.

Reimplemented from controller_interface::ChainableControllerInterface.

◆ on_set_chained_mode()

bool steering_controllers_library::SteeringControllersLibrary::on_set_chained_mode ( bool  chained_mode)
overrideprotectedvirtual

Virtual method that each chainable controller should implement to switch chained mode.

Each chainable controller implements this methods to switch between "chained" and "external" mode. In "chained" mode all external interfaces like subscriber and service servers are disabled to avoid potential concurrency in input commands.

Parameters
[in]flagmarking a switch to or from chained mode.
Returns
true if controller successfully switched between "chained" and "external" mode. \default returns true so the method don't have to be overridden if controller can always switch chained mode.

Reimplemented from controller_interface::ChainableControllerInterface.

◆ state_interface_configuration()

controller_interface::InterfaceConfiguration steering_controllers_library::SteeringControllersLibrary::state_interface_configuration ( ) const
overridevirtual

Get configuration for controller's required state interfaces.

Method used by the controller_manager to get the set of state interface used by the controller. Each controller can use individual method to determine interface names that in simples case have the following format: <joint>/<interface>. The method is called only in inactive or active state, i.e., on_configure has to be called first. The configuration is used to check if controller can be activated and to claim interfaces from hardware. The claimed interfaces are populated in the state_interface_ member.

Returns
configuration of state interfaces.

Implements controller_interface::ControllerInterfaceBase.

◆ update_and_write_commands()

controller_interface::return_type steering_controllers_library::SteeringControllersLibrary::update_and_write_commands ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

Execute calculations of the controller and update command interfaces.

Update method for chainable controllers. In this method is valid to assume that \reference_interfaces_ hold the values for calculation of the commands in the current control step. This means that this method is called after \update_reference_from_subscribers if controller is not in chained mode.

Returns
return_type::OK if calculation and writing of interface is successfully, otherwise return_type::ERROR.

Implements controller_interface::ChainableControllerInterface.

◆ update_reference_from_subscribers()

controller_interface::return_type steering_controllers_library::SteeringControllersLibrary::update_reference_from_subscribers ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

Update reference from input topics when not in chained mode.

Each chainable controller implements this method to update reference from subscribers when not in chained mode.

Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implements controller_interface::ChainableControllerInterface.


The documentation for this class was generated from the following files: