1+ #include " HAL.hpp"
2+
3+ using namespace std ::chrono_literals;
4+
5+ std::shared_ptr<MotorsNode> HAL::motor_node_ = nullptr ;
6+ std::shared_ptr<CameraNode> HAL::camera_node_ = nullptr ;
7+ std::shared_ptr<OdometryNode> HAL::odometry_node_ = nullptr ;
8+ std::shared_ptr<LaserNode> HAL::laser_node_ = nullptr ;
9+ std::shared_ptr<OdometryNode> HAL::noisy_odometry_node_ = nullptr ;
10+
11+ HAL::HAL () : Node(" hal_node" )
12+ {
13+ motor_node_ = std::make_shared<MotorsNode>(" /turtlebot3/cmd_vel" , 4.0 , 0.3 );
14+ camera_node_ = std::make_shared<CameraNode>(" /turtlebot3/camera/image_raw" );
15+ odometry_node_ = std::make_shared<OdometryNode>(" /turtlebot3/odom" );
16+ laser_node_ = std::make_shared<LaserNode>(" /turtlebot3/laser/scan" );
17+ noisy_odometry_node_ = std::make_shared<OdometryNode>(" /turtlebot3/odom_noisy" , " noisy_odometry_node" );
18+
19+ spin_thread_ = std::thread ([]() {
20+ rclcpp::executors::MultiThreadedExecutor executor;
21+ executor.add_node (camera_node_);
22+ executor.add_node (odometry_node_);
23+ executor.add_node (laser_node_);
24+ executor.add_node (noisy_odometry_node_);
25+
26+ while (rclcpp::ok ()) {
27+ executor.spin_some ();
28+ std::this_thread::sleep_for (11ms);
29+ }
30+ });
31+ spin_thread_.detach ();
32+ }
33+
34+ Pose3d HAL::getPose3d ()
35+ {
36+ if (odometry_node_) {
37+ return odometry_node_->getPose3d ();
38+ }
39+ return Pose3d ();
40+ }
41+
42+ Pose3d HAL::getOdom ()
43+ {
44+ if (noisy_odometry_node_) {
45+ return noisy_odometry_node_->getPose3d ();
46+ }
47+ return Pose3d ();
48+ }
49+
50+ cv::Mat HAL::getImage ()
51+ {
52+ std::shared_ptr<Image> img = nullptr ;
53+ while (img == nullptr && rclcpp::ok ()) {
54+ img = camera_node_->getImage ();
55+ if (img == nullptr ) {
56+ std::this_thread::sleep_for (10ms);
57+ }
58+ }
59+ return img->data ;
60+ }
61+
62+ LaserData HAL::getLaserData ()
63+ {
64+ LaserData laser_data = laser_node_->getLaserData ();
65+ while (laser_data.values .empty () && rclcpp::ok ()) {
66+ laser_data = laser_node_->getLaserData ();
67+ if (laser_data.values .empty ()) {
68+ std::this_thread::sleep_for (10ms);
69+ }
70+ }
71+ return laser_data;
72+ }
73+
74+ void HAL::setV (float v)
75+ {
76+ if (motor_node_) {
77+ motor_node_->sendV (static_cast <double >(v));
78+ }
79+ }
80+
81+ void HAL::setW (float w)
82+ {
83+ if (motor_node_) {
84+ motor_node_->sendW (static_cast <double >(w));
85+ }
86+ }
0 commit comments