Class UGVSystem
Defined in File ugv_system.hpp
Inheritance Relationships
Base Type
public hardware_interface::SystemInterface
Derived Types
public husarion_ugv_hardware_interfaces::LynxSystem(Class LynxSystem)public husarion_ugv_hardware_interfaces::PantherSystem(Class PantherSystem)
Class Documentation
-
class UGVSystem : public hardware_interface::SystemInterface
Class that implements SystemInterface from ros2_control for Husarion UGV.
Subclassed by husarion_ugv_hardware_interfaces::LynxSystem, husarion_ugv_hardware_interfaces::PantherSystem
Public Functions
-
inline UGVSystem(const std::vector<std::string> &joint_order)
-
virtual ~UGVSystem() = default
-
CallbackReturn on_init(const hardware_interface::HardwareInfo &hardware_info) override
-
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
-
CallbackReturn on_cleanup(const rclcpp_lifecycle::State &previous_state) override
-
CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override
-
CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override
-
CallbackReturn on_shutdown(const rclcpp_lifecycle::State &previous_state) override
-
CallbackReturn on_error(const rclcpp_lifecycle::State &previous_state) override
-
std::vector<StateInterface> export_state_interfaces() override
-
std::vector<CommandInterface> export_command_interfaces() override
-
return_type read(const rclcpp::Time &time, const rclcpp::Duration&) override
-
return_type write(const rclcpp::Time&, const rclcpp::Duration&) override
Protected Functions
-
void CheckJointSize() const
-
void SortAndCheckJointNames()
-
void SetInitialValues()
-
void CheckInterfaces() const
-
void ReadDrivetrainSettings()
-
void ReadCANopenSettings()
-
virtual void ReadCANopenSettingsDriverCANIDs() = 0
-
void ReadInitializationActivationAttempts()
-
void ReadParametersAndCreateRoboteqErrorFilter()
-
void ReadDriverStatesUpdateFrequency()
-
virtual void ConfigureGPIOController()
-
void ConfigureRobotDriver()
-
virtual void DefineRobotDriver() = 0
-
virtual void ConfigureEStop()
-
void UpdateMotorsState()
-
void UpdateDriverState()
-
void UpdateEStopState()
-
virtual void UpdateHwStates() = 0
-
virtual void UpdateMotorsStateDataTimedOut() = 0
-
bool AreVelocityCommandsNearZero()
-
virtual void UpdateDriverStateMsg() = 0
-
virtual void UpdateFlagErrors() = 0
-
virtual void UpdateDriverStateDataTimedOut() = 0
-
void HandleRobotDriverWriteOperation(std::function<void()> write_operation)
-
virtual std::vector<float> GetSpeedCommands() const = 0
-
void MotorTorqueEnable(const bool enable)
-
virtual void DiagnoseErrors(diagnostic_updater::DiagnosticStatusWrapper &status) = 0
-
virtual void DiagnoseStatus(diagnostic_updater::DiagnosticStatusWrapper &status) = 0
Protected Attributes
-
const size_t joint_size_
-
std::vector<double> hw_commands_velocities_
-
std::vector<double> hw_states_positions_
-
std::vector<double> hw_states_velocities_
-
std::vector<double> hw_states_efforts_
-
const std::vector<std::string> joint_order_
-
std::vector<std::string> joints_names_sorted_
-
std::shared_ptr<GPIOControllerInterface> gpio_controller_
-
std::shared_ptr<RobotDriverInterface> robot_driver_
-
std::shared_ptr<EStopInterface> e_stop_
-
DrivetrainSettings drivetrain_settings_
-
CANopenSettings canopen_settings_
-
std::unique_ptr<SystemROSInterface> system_ros_interface_
-
unsigned max_roboteq_initialization_attempts_
-
unsigned max_roboteq_activation_attempts_
-
rclcpp::Logger logger_ = {rclcpp::get_logger("UGVSystem")}
-
std::shared_ptr<RoboteqErrorFilter> roboteq_error_filter_
-
std::shared_ptr<std::mutex> robot_driver_write_mtx_
-
inline UGVSystem(const std::vector<std::string> &joint_order)