Class Cia402DeviceController

Inheritance Relationships

Base Type

Class Documentation

class Cia402DeviceController : public canopen_ros2_controllers::CanopenProxyController

Public Functions

CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC Cia402DeviceController()
CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init ()
CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const
CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const
CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state)
CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state)
CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state)
CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period)

Protected Functions

inline rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr createTriggerSrv(const std::string &service, Cia402CommandInterfaces cmd, Cia402CommandInterfaces fbk)

Protected Attributes

rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_init_service_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_halt_service_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_recover_service_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_position_service_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_torque_service_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_velocity_service_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_velocity_service_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_position_service_
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_interpolated_position_service_
rclcpp::Service<canopen_interfaces::srv::COTargetDouble>::SharedPtr handle_set_target_service_