Skip to content

Commit

Permalink
changed prints to loggers
Browse files Browse the repository at this point in the history
  • Loading branch information
VincidaB committed May 9, 2024
1 parent abc8146 commit 8c2a546
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 8 deletions.
12 changes: 6 additions & 6 deletions src/ezbot_command_module/include/tirette.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/bool.hpp>
#include <gpiod.h>

#include <rclcpp/logger.hpp>

class TiretteNode : public rclcpp::Node
{
Expand Down Expand Up @@ -33,24 +33,24 @@ bool TiretteNode::init_gpiod(void)
gpiochip = gpiod_chip_open_by_name("gpiochip0");
if(gpiochip == NULL)
{
printf("unable to open GPIO\n");
RCLCPP_WARN(get_logger(), "unable to open GPIO");
return false;
}
printf("gpiochip successful = %d\n",gpiochip);
RCLCPP_INFO(get_logger(), "gpiochip successful = %d\n",gpiochip);

gpioline = gpiod_chip_get_line(gpiochip,gpioTirette);
if (gpioline == NULL)
{
printf("unable to get GPIO line\n");
RCLCPP_WARN(get_logger(), "unable to get GPIO line\n");
return false;
}
printf("gpioTirette successful = %d\n",gpioTirette);
RCLCPP_INFO(get_logger(), "gpioTirette successful = %d\n",gpioTirette);

int temp;
// temp = gpiod_line_request_input_flags(gpioline,"Tirette", GPIOD_LINE_BIAS_PULL_UP);

temp = gpiod_line_request_input(gpioline,"Tirette");
printf("gpiod_line_request_input_flags = %d\n",temp);
RCLCPP_INFO(get_logger(),"gpiod_line_request_input_flags = %d\n",temp);
return true;

}
Expand Down
2 changes: 1 addition & 1 deletion src/ezbot_command_module/src/tirette_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ void TiretteNode::readGPIO()


value = gpiod_line_get_value(gpioline);
printf("value = %d\n",value);
RCLCPP_INFO(get_logger(),"value = %d\n",value);

message.data = value ? true : false;

Expand Down
2 changes: 1 addition & 1 deletion src/listen_package/listen_package/ecoute.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ def listener_callback(self, msg):
for range_value in msg.ranges:
if min_distance < range_value < max_distance:
# If an object is detected within the specified range, publish a message
print("y a un truc")
self.get_logger().info("Object detected")
self.publisher.publish(String(data='Object detected'))
break

Expand Down

0 comments on commit 8c2a546

Please sign in to comment.