Skip to content

Boolean data type signals are not supported by GPIO Controller #1970

@JavierIntermodalicsKion

Description

Describe the bug

After upgrading my ros2_control version from v 4.37.0 to this commit hash where boolean data types are handle, I noticed that gpio controller is triggering the following error:

[ros2_control_node-2] Exception thrown during reading the state of: GeneralSafetyIn/RunOk
[ros2_control_node-2] Exception thrown during reading the state of: PhysDigitalInputs/TruckOnState
[ros2_control_node-2] Exception thrown during reading the state of: PhysDigitalInputs/LoadFlap

That error comes from here where it didn't consider between different data types:

How do I fixed?

apply_command function

    auto data_type = command_interface.get_data_type();
    bool success;
    if (data_type == hardware_interface::HandleDataType::DOUBLE) {
      success = command_interface.set_value<double>(
        gpio_commands.interface_values[gpio_index].values[command_interface_index]);
    } else if (data_type == hardware_interface::HandleDataType::BOOL) {
      // To be discussed with Jonas
      success = command_interface.set_value<bool>(
        gpio_commands.interface_values[gpio_index].values[command_interface_index]);
    } else {
      RCLCPP_ERROR(
        get_node()->get_logger(), "Unsupported data type for interface %s",
        full_command_interface_name.c_str());
      return;
    }
    (void)success;
  } catch (const std::exception & e) {
    fprintf(
      stderr, "Exception thrown during applying command stage of %s with message: %s \n",
      full_command_interface_name.c_str(), e.what());
  }

apply_command

    auto & command_interface = command_interfaces_map_.at(full_command_interface_name).get();
    auto data_type = command_interface.get_data_type();
    bool success;
    if (data_type == hardware_interface::HandleDataType::DOUBLE) {
      success = command_interface.set_value<double>(
        gpio_commands.interface_values[gpio_index].values[command_interface_index]);
    } else if (data_type == hardware_interface::HandleDataType::BOOL) {
      // To be discussed with Jonas
      success = command_interface.set_value<bool>(
        gpio_commands.interface_values[gpio_index].values[command_interface_index] < 0.5 ? false : true);
    } else {
      RCLCPP_ERROR(
        get_node()->get_logger(), "Unsupported data type for interface %s",
        full_command_interface_name.c_str());
      return;
    }

ros2_control.config.yaml

gpio_controller:
  ros__parameters:
    type: gpio_controllers/GpioCommandController
    gpios:
      - PhysDigitalOutputs
      - GeneralSafetyIn
      - PhysDigitalInputs
      - PushThrResp
    command_interfaces:
      PhysDigitalOutputs:
        - interfaces:
          - TruckOn
    state_interfaces:
      GeneralSafetyIn:
        - interfaces:
          - RunOK
      PhysDigitalInputs:
        - interfaces:
          - TruckOnState
          - LoadFlap
      PushThrResp:
        - interfaces:
          - PushThroughDist

urdf example

<gpio name="GeneralSafetyIn">
      <state_interface name="RunOK" data_type="bool"></state_interface>
</gpio>

Expected behavior
No error thrown when a bool signal arrives

Screenshots
If applicable, add screenshots to help explain your problem.

Environment (please complete the following information):

  • OS: 24.04
  • Version Jazzy
  • Anything that may be unusual about your environment

Additional context
Add any other context about the problem here, especially include any modifications to ros2_control that relate to this issue.

Metadata

Metadata

Assignees

Labels

bugpersistentIssue won't get marked as stale

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions