fix error
This commit is contained in:
@@ -13,7 +13,7 @@ public:
|
||||
{
|
||||
publisher_ = this->create_publisher<std_msgs::msg::String>("height_sensor", 10);
|
||||
timer_ = this->create_wall_timer(
|
||||
20ms, std::bind(&HeightSensorPublisher::timer_callback, this));
|
||||
500ms, std::bind(&HeightSensorPublisher::timer_callback, this));
|
||||
RCLCPP_INFO(this->get_logger(), "Starting height sensor publisher");
|
||||
|
||||
setup_serial_port();
|
||||
@@ -34,9 +34,11 @@ private:
|
||||
char *readdata = new char[1];
|
||||
serial_port.read(readdata, 1);
|
||||
auto message = std_msgs::msg::String();
|
||||
message.data = "Height: " + (char)readdata[0];
|
||||
if (readdata[0] == 'T') {
|
||||
RCLCPP_INFO(this->get_logger(), "got start of measurement");
|
||||
message.data = "Height: " + std::to_string((char)readdata[0]);
|
||||
|
||||
if (readdata[0] == 'T')
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "Height sensor start measurement");
|
||||
}
|
||||
RCLCPP_INFO(this->get_logger(), "Publishing: %s", message.data.c_str());
|
||||
publisher_->publish(message);
|
||||
@@ -51,7 +53,7 @@ private:
|
||||
serial_port.open("/dev/ttyACM0", std::ios::in);
|
||||
if (!serial_port.is_open())
|
||||
{
|
||||
RCLCPP_ERROR(this->get_logger(), "ERROR Could not open serial port");
|
||||
RCLCPP_ERROR(this->get_logger(), "Could not open serial port");
|
||||
return;
|
||||
}
|
||||
else
|
||||
|
||||
Reference in New Issue
Block a user