add example reading of multiflex data

This commit is contained in:
Sem van der Hoeven
2023-04-24 11:57:13 +02:00
parent 32d73ba229
commit de9510c096

View File

@@ -5,35 +5,69 @@
#include <iostream> #include <iostream>
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "object_detection/msg/lidar_reading.hpp"
#include <terabee/ITerarangerFactory.hpp> #include <terabee/ITerarangerFactory.hpp>
#include <terabee/ITerarangerTowerEvo.hpp> #include <terabee/ITerarangerMultiflex.hpp>
#include <terabee/TowerDistanceData.hpp> #include <terabee/DistanceData.hpp>
#include <terabee/ImuData.hpp>
using terabee::ImuData; using terabee::DistanceData;
using terabee::ITerarangerTowerEvo;
using terabee::TowerDistanceData;
using namespace std::chrono_literals; using namespace std::chrono_literals;
std::ostream &operator<<(std::ostream &os, const DistanceData &d)
{
os << "[";
for (size_t i = 0; i < d.distance.size(); i++)
{
os << d.distance[i] << ", ";
}
os << "\b\b"
<< " ]";
return os;
}
class MultiflexReader : public rclcpp::Node class MultiflexReader : public rclcpp::Node
{ {
public: public:
MultiflexReader() MultiflexReader()
: Node("multiflex_reader") : Node("multiflex_reader")
{ {
//publisher_ = this->create_publisher<object_detection::msg::LidarReading>("drone/object_detection", 10); factory = terabee::ITerarangerFactory::getFactory();
//timer_ = this->create_wall_timer(500ms, std::bind(&MultiflexReader::read_multiflex_data, this)); multiflex = factory->createTerarangerMultiflex("/dev/ttyACM0");
if (!multiflex)
{
RCLCPP_ERROR(this->get_logger(), "Failed to create multiflex");
return;
}
if (!multiflex->initialize())
{
RCLCPP_ERROR(this->get_logger(), "Failed to initialize multiflex");
return;
}
if (!multiflex->configureNumberOfSensors(0x3f))
{
RCLCPP_ERROR(this->get_logger(), "Failed to set the number of sensors to 6!");
return;
}
RCLCPP_INFO(this->get_logger(), "Multiflex initialized");
timer_ = this->create_wall_timer(500ms, std::bind(&MultiflexReader::read_multiflex_data, this));
} }
private: private:
void read_multiflex_data() void read_multiflex_data()
{ {
std::cout << "Distance = " << multiflex->getDistance() << std::endl;
} }
std::unique_ptr<terabee::ITerarangerFactory> factory;
std::unique_ptr<terabee::ITerarangerMultiflex> multiflex;
rclcpp::TimerBase::SharedPtr timer_;
}; };
int main(int argc, char *argv[]) int main(int argc, char *argv[])