-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
3 changed files
with
124 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,50 @@ | ||
#ifndef TIRETTE_HPP | ||
#define TIRETTE_HPP | ||
|
||
#include <rclcpp/rclcpp.hpp> | ||
#include <std_msgs/msg/bool.hpp> | ||
#include <gpiod.h> | ||
|
||
|
||
class TiretteNode : public rclcpp::Node | ||
{ | ||
public: | ||
TiretteNode(); | ||
|
||
private: | ||
|
||
int gpioTirette = 11; | ||
rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr tirette_pub_; | ||
rclcpp::TimerBase::SharedPtr timer_; | ||
bool init_gpiod(void); | ||
void readGPIO(); | ||
|
||
struct gpiod_chip *gpiochip; | ||
struct gpiod_line *gpioline; | ||
}; | ||
|
||
|
||
|
||
|
||
bool TiretteNode::init_gpiod(void) | ||
{ | ||
gpiochip = gpiod_chip_open_by_name("gpiochip4"); | ||
if(gpiochip == NULL) | ||
gpiochip = gpiod_chip_open_by_name("gpiochip0"); | ||
if(gpiochip == NULL) | ||
{ | ||
printf("unable to open GPIO\n"); | ||
return false; | ||
} | ||
|
||
gpioline = gpiod_chip_get_line(gpiochip,gpioTirette); | ||
|
||
// set gpio pin INPUT PULL UP | ||
gpiod_line_request_input_flags(gpioline,"MyBlink", GPIOD_LINE_BIAS_PULL_UP); | ||
|
||
return true; | ||
|
||
} | ||
|
||
|
||
#endif // TIRETTE_HPP |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,58 @@ | ||
#include "tirette.hpp" | ||
|
||
|
||
|
||
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"); | ||
if (!chip) { | ||
// handle error | ||
} | ||
|
||
line = gpiod_chip_get_line(chip, 11); | ||
if (!line) { | ||
// handle error | ||
} | ||
|
||
if (gpiod_line_request_input(line, "tirette_node") < 0) { | ||
// handle error | ||
} | ||
|
||
value = gpiod_line_get_value(line); | ||
if (value < 0) { | ||
// handle error | ||
} | ||
|
||
message.data = value ? true : false; | ||
|
||
tirette_pub_->publish(message); | ||
|
||
gpiod_line_release(line); | ||
gpiod_chip_close(chip); | ||
} | ||
TiretteNode::TiretteNode() : Node("tirette_node") | ||
{ | ||
|
||
init_gpiod(); | ||
tirette_pub_ = this->create_publisher<std_msgs::msg::Bool>("tirette_status", 10); | ||
timer_ = this->create_wall_timer( | ||
std::chrono::seconds(1), | ||
std::bind(&TiretteNode::readGPIO, this)); | ||
|
||
|
||
} | ||
|
||
|
||
int main(int argc, char *argv[]) | ||
{ | ||
rclcpp::init(argc, argv); | ||
rclcpp::spin(std::make_shared<TiretteNode>()); | ||
rclcpp::shutdown(); | ||
return 0; | ||
} |