Class SystemROSInterface

Class Documentation

class SystemROSInterface

Class that takes care of additional ROS interface of panther system, such as publishing driver state and providing service for clearing errors.

Public Functions

SystemROSInterface(const std::string &node_name, const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())

Creates node and executor (in a separate thread), publishers, subscribers and services.

Parameters:
  • node_name

  • node_options

~SystemROSInterface()
template<class SrvT, class CallbackT>
inline void AddService(const std::string &service_name, const CallbackT &callback, const unsigned group_id = 0, rclcpp::CallbackGroupType callback_group_type = rclcpp::CallbackGroupType::MutuallyExclusive, const rclcpp::QoS &qos = rclcpp::ServicesQoS())

Registers a new service server associated with a specific service type and callback on the node.

Template Parameters:
  • SrvT – The type of ROS service for which the server is being created. This should correspond to a predefined service message type.

  • CallbackT – The type of the callback function that will be executed when the service receives a request. The function’s signature should be compatible with the expected request and response types for the given service SrvT.

Parameters:
  • service_name – A string specifying the unique name under which the service will be advertised on the ROS network.

  • callback – The callback function to be executed when the service receives a request. This function is responsible for processing the incoming request and producing an appropriate response. Currently supported callback function signatures include void() and void(bool).

  • group_id – An unsigned integer representing the unique identifier of the callback group that the service should be associated with. A value of ‘0’ indicates that the service should use the default node callback group.

  • callback_group_type – The type of the callback group to be used, expressed as an enumerated value of rclcpp::CallbackGroupType. If a new group must be created, this specifies whether it should be MutuallyExclusive or Reentrant. The default value is MutuallyExclusive.

  • qos – The QoS settings for the service. Defaults to ServicesQoS.

template<class T>
inline void AddDiagnosticTask(const std::string &name, T *task_owner, void (T::* task_fcn)(diagnostic_updater::DiagnosticStatusWrapper&))

Adds a new diagnostic task.

Parameters:
  • name – The name of the diagnostic task.

  • task_owner – A pointer to the object that posses the diagnostic task member function.

  • task_fcn – A pointer to the diagnostic task member function.

inline void BroadcastOnDiagnosticTasks(unsigned char level, const std::string &message)

Broadcasts a message with the specified level on defined diagnostic tasks.

Parameters:
  • level – The level of the diagnostic message.

  • message – The message to be broadcasted.

void UpdateMsgErrorFlags(const DriverNames name, const DriverData &data)

Updates fault flags, script flags, and runtime errors in the robot driver state msg.

Parameters:
  • name – The name of the driver to update the flags for

  • data – The data to update the flags with

void UpdateMsgDriversStates(const DriverNames name, const RoboteqDriverState &state)

Updates parameters of the driver (voltage, current and temperature) in robot driver state msg.

Parameters:
  • name – The name of the driver to update the parameters for

  • state – The data to update the parameters with

void UpdateMsgErrors(const CANErrors &can_errors)

Updates the current state of communication errors and general error state.

void PublishEStopStateMsg(const bool e_stop)
void PublishEStopStateIfChanged(const bool e_stop)
void PublishRobotDriverState()
void InitializeAndPublishIOStateMsg(const std::unordered_map<GPIOPin, bool> &io_state)
void PublishIOState(const GPIOInfo &gpio_info)

Protected Functions

bool UpdateIOStateMsg(const GPIOPin pin, const bool pin_value)

Updates the IOState message and indicates whether its state has changed.

Parameters:
  • pin – The GPIO pin whose state is to be updated.

  • pin_value – The new value to be set for the pin. True indicates a high state, and false indicates a low state.

Returns:

True if the state update caused a change in the IO state message; returns false otherwise.

rclcpp::CallbackGroup::SharedPtr GetOrCreateNodeCallbackGroup(const unsigned group_id, rclcpp::CallbackGroupType callback_group_type)

Retrieves an existing callback group from the internal map or creates a new one if it does not exist.

When the group_id is set to 0 and the callback_group_type is set to MutuallyExclusive, the method returns a nullptr, indicating the usage of the default node callback group.

Parameters:
  • group_id – The numeric identifier of the callback group. If set to 0, the default node callback group is used.

  • callback_group_type – The type of the callback group, defined by the rclcpp::CallbackGroupType enumeration.

Returns:

Shared pointer to the requested callback group, or nullptr if the default node callback group is to be used.

DriverStateNamedMsg &GetDriverStateByName(RobotDriverStateMsg &robot_driver_state, const DriverNames name)

Retrieves the driver state message associated with the specified name. If the driver state is not found, it is created.

Parameters:
  • robot_driver_state – The robot driver state message to retrieve driver state from.

  • name – The name of the driver state to be retrieved.

Returns:

Reference to the driver state message associated with the specified name.

Protected Attributes

rclcpp::Node::SharedPtr node_
std::unordered_map<unsigned, rclcpp::CallbackGroup::SharedPtr> callback_groups_
rclcpp::executors::MultiThreadedExecutor::UniquePtr executor_
std::thread executor_thread_
rclcpp::Publisher<RobotDriverStateMsg>::SharedPtr driver_state_publisher_
std::unique_ptr<realtime_tools::RealtimePublisher<RobotDriverStateMsg>> realtime_driver_state_publisher_
rclcpp::Publisher<IOStateMsg>::SharedPtr io_state_publisher_
std::unique_ptr<realtime_tools::RealtimePublisher<IOStateMsg>> realtime_io_state_publisher_
rclcpp::Publisher<BoolMsg>::SharedPtr e_stop_state_publisher_
std::unique_ptr<realtime_tools::RealtimePublisher<BoolMsg>> realtime_e_stop_state_publisher_
diagnostic_updater::Updater diagnostic_updater_
std::vector<std::any> service_wrappers_storage_