Skip to content

Commit

Permalink
removed unnecessary code
Browse files Browse the repository at this point in the history
  • Loading branch information
VincidaB committed May 8, 2024
1 parent c731273 commit 00737ca
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 22 deletions.
2 changes: 1 addition & 1 deletion src/ezbot_command_module/include/tirette.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ bool TiretteNode::init_gpiod(void)
}

gpioline = gpiod_chip_get_line(gpiochip,gpioTirette);

printf("gpioTirette successful = %d\n",gpioTirette);
// set gpio pin INPUT PULL UP
gpiod_line_request_input_flags(gpioline,"MyBlink", GPIOD_LINE_BIAS_PULL_UP);

Expand Down
23 changes: 2 additions & 21 deletions src/ezbot_command_module/src/tirette_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,30 +6,11 @@ void TiretteNode::readGPIO()
{
auto message = std_msgs::msg::Bool();

struct gpiod_chip *chip;
struct gpiod_line *line;
int value;

chip = gpiod_chip_open("/dev/gpiochip0");
printf("chip : %p\n", chip);

if (!chip) {
printf("unable to open GPIO\n")
}

line = gpiod_chip_get_line(chip, 11);
if (!line) {
printf("unable to get line\n")
}

if (gpiod_line_request_input(line, "tirette_node") < 0) {
printf("unable to request line\n")
}

value = gpiod_line_get_value(line);
if (value < 0) {
printf("unable to get value\n")
}
value = gpiod_line_get_value(gpioline);
printf("value = %d\n",value);

message.data = value ? true : false;

Expand Down

0 comments on commit 00737ca

Please sign in to comment.