Public Member Functions | |
controller_interface::CallbackReturn | configure_odometry () override |
bool | update_odometry (const rclcpp::Duration &period) override |
void | initialize_implementation_parameter_listener () override |
![]() | |
controller_interface::CallbackReturn | on_init () override |
Extending interface with initialization method which is individual for each controller. | |
controller_interface::InterfaceConfiguration | command_interface_configuration () const override |
Get configuration for controller's required command interfaces. | |
controller_interface::InterfaceConfiguration | state_interface_configuration () const override |
Get configuration for controller's required state interfaces. | |
controller_interface::CallbackReturn | on_configure (const rclcpp_lifecycle::State &previous_state) override |
controller_interface::CallbackReturn | on_activate (const rclcpp_lifecycle::State &previous_state) override |
controller_interface::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &previous_state) override |
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. | |
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. | |
![]() | |
return_type | update (const rclcpp::Time &time, const rclcpp::Duration &period) final |
bool | is_chainable () const final |
Get information if a controller is chainable. | |
std::vector< hardware_interface::StateInterface::ConstSharedPtr > | export_state_interfaces () final |
std::vector< hardware_interface::CommandInterface::SharedPtr > | export_reference_interfaces () final |
bool | set_chained_mode (bool chained_mode) final |
bool | is_in_chained_mode () const final |
Get information if a controller is currently in chained mode. | |
![]() | |
virtual 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. | |
virtual void | release_interfaces () |
Method that releases the Loaned interfaces from the controller. | |
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) |
const rclcpp_lifecycle::State & | configure () |
Custom configure method to read additional parameters for controller-nodes. | |
ControllerUpdateStatus | trigger_update (const rclcpp::Time &time, const rclcpp::Duration &period) |
std::shared_ptr< rclcpp_lifecycle::LifecycleNode > | get_node () |
std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > | get_node () const |
const rclcpp_lifecycle::State & | get_lifecycle_state () const |
unsigned int | get_update_rate () const |
bool | is_async () const |
const std::string & | get_robot_description () const |
virtual 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. | |
void | wait_for_trigger_update_to_finish () |
void | prepare_for_deactivation () |
std::string | get_name () const |
void | enable_introspection (bool enable) |
Enable or disable introspection of the controller. | |
Protected Attributes | |
std::shared_ptr< bicycle_steering_controller::ParamListener > | bicycle_param_listener_ |
bicycle_steering_controller::Params | bicycle_params_ |
![]() | |
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< ControllerStatePublisherOdom > | rt_odom_state_publisher_ |
std::unique_ptr< ControllerStatePublisherTf > | rt_tf_odom_state_publisher_ |
steering_odometry::SteeringOdometry | odometry_ |
Odometry: | |
AckermannControllerState | published_state_ |
rclcpp::Publisher< AckermannControllerState >::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 > | traction_joints_state_names_ |
std::vector< std::string > | steering_joints_state_names_ |
![]() | |
std::vector< std::string > | exported_state_interface_names_ |
Storage of values for state interfaces. | |
std::vector< hardware_interface::StateInterface::SharedPtr > | ordered_exported_state_interfaces_ |
std::unordered_map< std::string, hardware_interface::StateInterface::SharedPtr > | exported_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_ |
std::vector< hardware_interface::CommandInterface::SharedPtr > | ordered_exported_reference_interfaces_ |
std::unordered_map< std::string, hardware_interface::CommandInterface::SharedPtr > | exported_reference_interfaces_ |
![]() | |
std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
pal_statistics::RegistrationsRAII | stats_registrations_ |
Additional Inherited Members | |
![]() | |
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 | AckermannControllerState = control_msgs::msg::SteeringControllerStatus |
![]() | |
using | ControllerStatePublisherOdom = realtime_tools::RealtimePublisher< ControllerStateMsgOdom > |
using | ControllerStatePublisherTf = realtime_tools::RealtimePublisher< ControllerStateMsgTf > |
using | ControllerStatePublisher = realtime_tools::RealtimePublisher< AckermannControllerState > |
![]() | |
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 |
Virtual method that each chainable controller should implement to switch chained mode. | |
![]() | |
virtual std::vector< hardware_interface::StateInterface > | on_export_state_interfaces () |
|
overridevirtual |
|
overridevirtual |
|
overridevirtual |