Changed service to wait for proper response from i2c
This commit is contained in:
@ -8,7 +8,6 @@ extern "C" {
|
||||
#include <sys/ioctl.h>
|
||||
#include <i2c/smbus.h>
|
||||
}
|
||||
|
||||
class MgI2c : public rclcpp::Node {
|
||||
using I2cSrv = mg_msgs::srv::I2c;
|
||||
|
||||
@ -21,7 +20,15 @@ class MgI2c : public rclcpp::Node {
|
||||
|
||||
void send_req(I2cSrv::Request::ConstSharedPtr req, I2cSrv::Response::SharedPtr resp) const {
|
||||
ioctl(i2c_fd_, I2C_SLAVE, req->addr); // NOLINT
|
||||
int ch = i2c_smbus_read_byte_data(i2c_fd_, req->data);
|
||||
i2c_smbus_write_byte(i2c_fd_, req->data);
|
||||
int ch = 0;
|
||||
|
||||
rclcpp::Rate rate(100);
|
||||
|
||||
while (ch == 0 || (ch < 256 && ch > 0)) {
|
||||
ch = i2c_smbus_read_byte(i2c_fd_);
|
||||
rate.sleep();
|
||||
}
|
||||
resp->resp.push_back(ch);
|
||||
RCLCPP_INFO(get_logger(), "Recieved %d", resp->resp.front());
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user