Class EStop

Inheritance Relationships

Base Type

Class Documentation

class EStop : public husarion_ugv_hardware_interfaces::EStopInterface

Implements the emergency stop interface.

Public Functions

inline EStop(std::shared_ptr<GPIOControllerInterface> gpio_controller, std::shared_ptr<RoboteqErrorFilter> roboteq_error_filter, std::shared_ptr<RobotDriverInterface> robot_driver, std::shared_ptr<std::mutex> robot_driver_write_mtx, std::function<bool()> zero_velocity_check)
virtual ~EStop() override = default
virtual bool ReadEStopState() override

Checks the emergency stop state.

  1. Check if ESTOP GPIO pin is not active. If is not it means that E-Stop is triggered by another device within the robot’s system (e.g., Roboteq controller or Safety Board), disabling the software Watchdog is necessary to prevent an uncontrolled reset.

  2. If there is a need, disable software Watchdog using GPIOControllerInterface::EStopTrigger method.

  3. Return ESTOP GPIO pin state.

virtual void TriggerEStop() override

Triggers the emergency stop.

  1. Interrupt the E-Stop resetting process if it is in progress.

  2. Attempt to trigger the E-Stop using GPIO by disabling the software-controlled watchdog.

  3. If successful, set e_stop_triggered_ to true; otherwise, throw a std::runtime_error exception.

Throws:

std::runtime_error – if triggering the E-stop using GPIO fails.

virtual void ResetEStop() override

Resets the emergency stop.

  1. Verify that the last velocity commands are zero to prevent an uncontrolled robot movement after an E-stop state change.

  2. Attempt to reset the E-Stop using GPIO by manipulating the ESTOP GPIO pin. This operation may take some time and can be interrupted by the E-Stop trigger process.

  3. Set the clear_error flag to allow for clearing of Roboteq errors.

  4. Confirm the E-Stop reset was successful with the ReadEStopState method.

Throws:
  • EStopResetInterrupted – if the E-stop reset operation was halted because the E-stop was triggered again.

  • std::runtime_error – if an error occurs when trying to reset the E-stop using GPIO.

Protected Attributes

std::shared_ptr<GPIOControllerInterface> gpio_controller_
std::shared_ptr<RoboteqErrorFilter> roboteq_error_filter_
std::shared_ptr<RobotDriverInterface> robot_driver_
std::shared_ptr<std::mutex> robot_driver_write_mtx_
std::function<bool()> ZeroVelocityCheck
std::mutex e_stop_manipulation_mtx_
std::atomic_bool e_stop_triggered_ = true