Class Cia402System

Inheritance Relationships

Base Type

Class Documentation

class Cia402System : public canopen_ros2_control::CanopenSystem

Public Functions

CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC Cia402System()
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC ~Cia402System() = default
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_init (const hardware_interface::HardwareInfo &info)
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state)
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC std::vector< hardware_interface::StateInterface > export_state_interfaces ()
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC std::vector< hardware_interface::CommandInterface > export_command_interfaces ()
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state)
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state)
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::return_type read (const rclcpp::Time &time, const rclcpp::Duration &period)
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::return_type write (const rclcpp::Time &time, const rclcpp::Duration &period)

Protected Attributes

std::map<uint, MotorNodeData> motor_data_