Class RobotSystem
Defined in File robot_system.hpp
Inheritance Relationships
Base Type
public hardware_interface::SystemInterface
Class Documentation
-
class RobotSystem : public hardware_interface::SystemInterface
Public Functions
-
inline CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC RobotSystem()
-
CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC ~RobotSystem() = default
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_init (const hardware_interface::HardwareInfo &info) override
Initialize the hardware interface.
Fetch the hardware info stored in the urdf. Specifically these values:
bus_config
master_config
can_interface_name
master_bin
- Parameters:
info –
- Returns:
hardware_interface::CallbackReturn
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
Configure the hardware interface.
Create the device container and the executor. Start the threads for running the canopen stack.
- Parameters:
info –
- Returns:
hardware_interface::CallbackReturn
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC std::vector< hardware_interface::StateInterface > export_state_interfaces () override
Export the state interfaces for this system.
The state interface of each cia402 device contains the following:
Position
Velocity
- Returns:
std::vector<hardware_interface::StateInterface>
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC std::vector< hardware_interface::CommandInterface > export_command_interfaces () override
Export the command interfaces for this system.
The command interface of each cia402 device contains the following:
Position
Velocity
Effort
Operation Mode
Init Command
Halt Command
Recover Command
- Returns:
std::vector<hardware_interface::CommandInterface>
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
Cleanup the hardware interface.
- Parameters:
previous_state –
- Returns:
hardware_interface::CallbackReturn
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override
Shutdown the hardware interface.
- Parameters:
previous_state –
- Returns:
hardware_interface::CallbackReturn
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
Activate the hardware interface.
- Parameters:
previous_state –
- Returns:
hardware_interface::CallbackReturn
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
Deactivate the hardware interface.
- Parameters:
previous_state –
- Returns:
hardware_interface::CallbackReturn
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::return_type read (const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the state from the hardware interface.
- Returns:
hardware_interface::return_type
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::return_type write (const rclcpp::Time &time, const rclcpp::Duration &period) override
Write the command to the hardware interface.
- Returns:
hardware_interface::return_type
- CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC hardware_interface::return_type perform_command_mode_switch (const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
Protected Attributes
-
std::shared_ptr<ros2_canopen::DeviceContainer> device_container_
-
std::shared_ptr<rclcpp::executors::MultiThreadedExecutor> executor_
-
std::vector<Cia402Data> robot_motor_data_
-
std::string bus_config_
-
std::string master_config_
-
std::string master_bin_
-
std::string can_interface_
-
std::unique_ptr<std::thread> spin_thread_
-
std::unique_ptr<std::thread> init_thread_
-
rclcpp::Logger robot_system_logger = rclcpp::get_logger("robot_system")
-
inline CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC RobotSystem()