ros2_control - rolling
Loading...
Searching...
No Matches
Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
motion_primitives_controllers::MotionPrimitivesBaseController Class Reference
Inheritance diagram for motion_primitives_controllers::MotionPrimitivesBaseController:
Inheritance graph
[legend]
Collaboration diagram for motion_primitives_controllers::MotionPrimitivesBaseController:
Collaboration graph
[legend]

Public Member Functions

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 (const rclcpp::Time &time, const rclcpp::Duration &period) override
 
- Public Member Functions inherited from controller_interface::ControllerInterface
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
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
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 Types

using MotionPrimitive = control_msgs::msg::MotionPrimitive
 

Protected Member Functions

void reset_command_interfaces ()
 
bool set_command_interfaces ()
 

Protected Attributes

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_
 
- Protected Attributes inherited from controller_interface::ControllerInterfaceBase
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 
pal_statistics::RegistrationsRAII stats_registrations_
 

Member Function Documentation

◆ command_interface_configuration()

controller_interface::InterfaceConfiguration motion_primitives_controllers::MotionPrimitivesBaseController::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_init()

controller_interface::CallbackReturn motion_primitives_controllers::MotionPrimitivesBaseController::on_init ( )
overridevirtual

Extending interface with initialization method which is individual for each controller.

Implements controller_interface::ControllerInterfaceBase.

Reimplemented in motion_primitives_controllers::MotionPrimitivesForwardController.

◆ state_interface_configuration()

controller_interface::InterfaceConfiguration motion_primitives_controllers::MotionPrimitivesBaseController::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_interfaces_ member.

Returns
configuration of state interfaces.

Implements controller_interface::ControllerInterfaceBase.

◆ update()

controller_interface::return_type motion_primitives_controllers::MotionPrimitivesBaseController::update ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

Control step update. Command interfaces are updated based on on reference inputs and current states. The method called in the (real-time) control loop.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time since the last control loop iteration
Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implements controller_interface::ControllerInterfaceBase.

Reimplemented in motion_primitives_controllers::MotionPrimitivesForwardController.


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