|
| controller_interface::CallbackReturn | on_init () override |
| | Extending interface with initialization method which is individual for each controller.
|
| |
|
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 (const rclcpp::Time &time, const rclcpp::Duration &period) override |
| |
| 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 |
| |
| bool | is_chainable () const final |
| |
| 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 |
| |
| 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) |
| |
|
return_type | init (const controller_interface::ControllerInterfaceParams ¶ms) |
| |
|
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 |
| |
| const std::unordered_map< std::string, joint_limits::JointLimits > & | get_hard_joint_limits () const |
| |
| const std::unordered_map< std::string, joint_limits::SoftJointLimits > & | get_soft_joint_limits () 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.
|
| |
|
|
std::shared_ptr< motion_primitives_forward_controller::ParamListener > | param_listener_ |
| |
|
motion_primitives_forward_controller::Params | params_ |
| |
|
rclcpp_action::Server< ExecuteMotionAction >::SharedPtr | action_server_ |
| |
|
realtime_tools::RealtimeThreadSafeBox< std::shared_ptr< RealtimeGoalHandle > > | rt_goal_handle_ |
| |
|
std::string | tf_prefix_ |
| |
|
realtime_tools::LockFreeSPSCQueue< MotionPrimitive, 1024 > | moprim_queue_ |
| |
|
std::atomic< bool > | has_active_goal_ = false |
| |
|
rclcpp::TimerBase::SharedPtr | goal_handle_timer_ |
| |
|
rclcpp::Duration | action_monitor_period_ = rclcpp::Duration(std::chrono::milliseconds(20)) |
| |
|
bool | print_error_once_ = true |
| |
|
std::atomic< bool > | cancel_requested_ = false |
| |
|
std::atomic< bool > | robot_stop_requested_ = false |
| |
|
bool | was_executing_ = false |
| |
|
ExecutionState | execution_status_ |
| |
|
ReadyForNewPrimitive | ready_for_new_primitive_ |
| |
|
MotionPrimitive | current_moprim_ |
| |
| std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
| |
| std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
| |
|
pal_statistics::RegistrationsRAII | stats_registrations_ |
| |