ros2_control - rolling
Public Member Functions | Protected Attributes | List of all members
ros2_control_demo_example_7::RobotController Class Reference
Inheritance diagram for ros2_control_demo_example_7::RobotController:
Inheritance graph
[legend]
Collaboration diagram for ros2_control_demo_example_7::RobotController:
Collaboration graph
[legend]

Public Member Functions

CONTROLLER_INTERFACE_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
 Get configuration for controller's required command interfaces. More...
 
CONTROLLER_INTERFACE_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
 Get configuration for controller's required state interfaces. More...
 
CONTROLLER_INTERFACE_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
 
CONTROLLER_INTERFACE_PUBLIC controller_interface::CallbackReturn on_init () override
 Extending interface with initialization method which is individual for each controller.
 
CONTROLLER_INTERFACE_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 
CONTROLLER_INTERFACE_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 
CONTROLLER_INTERFACE_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 
CONTROLLER_INTERFACE_PUBLIC controller_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
 
CONTROLLER_INTERFACE_PUBLIC controller_interface::CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
 
CONTROLLER_INTERFACE_PUBLIC controller_interface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override
 
- Public Member Functions inherited from controller_interface::ControllerInterface
CONTROLLER_INTERFACE_PUBLIC bool is_chainable () const final
 
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
 
- 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 Attributes

std::vector< std::string > joint_names_
 
std::vector< std::string > command_interface_types_
 
std::vector< std::string > state_interface_types_
 
rclcpp::Subscription< trajectory_msgs::msg::JointTrajectory >::SharedPtr joint_command_subscriber_
 
realtime_tools::RealtimeBuffer< std::shared_ptr< trajectory_msgs::msg::JointTrajectory > > traj_msg_external_point_ptr_
 
bool new_msg_ = false
 
rclcpp::Time start_time_
 
std::shared_ptr< trajectory_msgs::msg::JointTrajectory > trajectory_msg_
 
trajectory_msgs::msg::JointTrajectoryPoint point_interp_
 
std::vector< std::reference_wrapper< hardware_interface::LoanedCommandInterface > > joint_position_command_interface_
 
std::vector< std::reference_wrapper< hardware_interface::LoanedCommandInterface > > joint_velocity_command_interface_
 
std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > joint_position_state_interface_
 
std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > joint_velocity_state_interface_
 
std::unordered_map< std::string, std::vector< std::reference_wrapper< hardware_interface::LoanedCommandInterface > > * > command_interface_map_
 
std::unordered_map< std::string, std::vector< std::reference_wrapper< hardware_interface::LoanedStateInterface > > * > state_interface_map_
 
- 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 ros2_control_demo_example_7::RobotController::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.

◆ state_interface_configuration()

controller_interface::InterfaceConfiguration ros2_control_demo_example_7::RobotController::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()

controller_interface::return_type ros2_control_demo_example_7::RobotController::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 taken by the last control loop iteration
Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implements controller_interface::ControllerInterfaceBase.

Member Data Documentation

◆ command_interface_map_

std::unordered_map< std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface> > *> ros2_control_demo_example_7::RobotController::command_interface_map_
protected
Initial value:
= {
{"position", &joint_position_command_interface_},
{"velocity", &joint_velocity_command_interface_}}

◆ state_interface_map_

std::unordered_map< std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface> > *> ros2_control_demo_example_7::RobotController::state_interface_map_
protected
Initial value:
= {
{"position", &joint_position_state_interface_},
{"velocity", &joint_velocity_state_interface_}}

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