Class RoboteqRobotDriver
Defined in File roboteq_robot_driver.hpp
Inheritance Relationships
Base Type
public husarion_ugv_hardware_interfaces::RobotDriverInterface(Class RobotDriverInterface)
Derived Types
public husarion_ugv_hardware_interfaces::LynxRobotDriver(Class LynxRobotDriver)public husarion_ugv_hardware_interfaces::PantherRobotDriver(Class PantherRobotDriver)
Class Documentation
-
class RoboteqRobotDriver : public husarion_ugv_hardware_interfaces::RobotDriverInterface
Abstract class implementing RobotDriver for robots using Roboteq drivers. It uses canopen_manager for communication with Roboteq controllers. This class implements the activation procedure for controllers, which involves resetting the script and sending an initial 0 command. It also provides methods to get data feedback and send commands. Data is converted between raw Roboteq formats and SI units using roboteq_data_converters.
Subclassed by husarion_ugv_hardware_interfaces::LynxRobotDriver, husarion_ugv_hardware_interfaces::PantherRobotDriver
Public Functions
-
RoboteqRobotDriver(const CANopenSettings &canopen_settings, const DrivetrainSettings &drivetrain_settings, const std::chrono::milliseconds activate_wait_time = std::chrono::milliseconds(1000))
-
inline ~RoboteqRobotDriver()
-
virtual void Initialize() override
Starts CAN communication and waits for boot to finish.
- Throws:
std::runtime_error – if boot fails
-
virtual void Deinitialize() override
Deinitialize can communication.
-
virtual void Activate() override
Activate procedure for Roboteq drivers - reset scripts and send 0 commands on both channels. Blocking function, takes around 2 seconds to finish.
- Throws:
std::runtime_error – if any procedure step fails
-
virtual void UpdateCommunicationState() override
Updates current communication state with Roboteq drivers.
- Throws:
std::runtime_error – if CAN error was detected
-
virtual void UpdateMotorsState() override
Updates current motors’ state (position, velocity, current).
- Throws:
std::runtime_error – if CAN error was detected
-
virtual void UpdateDriversState() override
Updates current Roboteq driver state (flags, temperatures, voltage, battery current)
- Throws:
std::runtime_error – if CAN error was detected
-
virtual void TurnOnEStop() override
Turns on Roboteq E-stop.
- Throws:
std::runtime_error – if any operation returns error
-
virtual void TurnOffEStop() override
Turns off Roboteq E-stop.
- Throws:
std::runtime_error – if any operation returns error
-
virtual const DriverData &GetData(const DriverNames name) override
Get data feedback from the driver.
- Parameters:
name – name of the data to get
- Throws:
std::runtime_error – if data with the given name does not exist
- Returns:
data feedback
-
virtual bool CommunicationError() override
Check if communication with drivers is working properly.
- Returns:
true if communication error occurred
Protected Functions
-
virtual void DefineDrivers() = 0
This method defines driver objects and adds motor drivers for them.
-
inline RoboteqVelocityCommandConverter &GetCmdVelConverter()
-
inline CANopenSettings &GetCANopenSettings()
-
inline CANopenManager &GetCANopenManager()
Protected Attributes
-
CANopenSettings canopen_settings_
-
DrivetrainSettings drivetrain_settings_
-
CANopenManager canopen_manager_
-
std::unordered_map<DriverNames, std::shared_ptr<DriverInterface>> drivers_
-
RoboteqRobotDriver(const CANopenSettings &canopen_settings, const DrivetrainSettings &drivetrain_settings, const std::chrono::milliseconds activate_wait_time = std::chrono::milliseconds(1000))