Merged mg odometry with magrob
This commit is contained in:
86
mg_odometry/src/mg_odom_publisher.cpp
Normal file
86
mg_odometry/src/mg_odom_publisher.cpp
Normal file
@ -0,0 +1,86 @@
|
||||
#include <chrono>
|
||||
#include <functional>
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <libserial/SerialStream.h>
|
||||
|
||||
#include "geometry_msgs/msg/transform_stamped.hpp"
|
||||
#include "tf2_ros/static_transform_broadcaster.h"
|
||||
|
||||
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
|
||||
#include "tf2/LinearMath/Transform.hpp"
|
||||
#include "tf2/LinearMath/Quaternion.hpp"
|
||||
#include "tf2/convert.hpp"
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
#define TIMEOUT 10u
|
||||
|
||||
constexpr const char* ENCODER_SERIAL_PATH_DEFAULT = "/dev/ttyACM1";
|
||||
|
||||
class MgOdomPublisher : public rclcpp::Node {
|
||||
public:
|
||||
MgOdomPublisher() : Node("mg_odom_publisher") {
|
||||
this->declare_parameter("odom", "odom");
|
||||
this->declare_parameter("target", "base-link");
|
||||
this->declare_parameter("serial_path", ENCODER_SERIAL_PATH_DEFAULT);
|
||||
|
||||
tf_static_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);
|
||||
|
||||
timer_ = this->create_wall_timer(std::chrono::milliseconds(TIMEOUT),
|
||||
std::bind(&MgOdomPublisher::timer_callback, this));
|
||||
}
|
||||
|
||||
private:
|
||||
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> tf_static_broadcaster_;
|
||||
rclcpp::TimerBase::SharedPtr timer_;
|
||||
LibSerial::SerialStream enc_serial_port_;
|
||||
|
||||
void timer_callback() {
|
||||
double _x = NAN;
|
||||
double _y = NAN;
|
||||
double _theta = NAN;
|
||||
|
||||
RCLCPP_DEBUG(this->get_logger(), "Callback called");
|
||||
|
||||
try {
|
||||
if (!enc_serial_port_.IsOpen()) {
|
||||
enc_serial_port_.Open(this->get_parameter("serial_path").as_string());
|
||||
}
|
||||
|
||||
enc_serial_port_ << "g;";
|
||||
|
||||
if (!(enc_serial_port_ >> _x >> _y >> _theta)) {
|
||||
RCLCPP_INFO(this->get_logger(), "Reading Serial Port failed. Closing...");
|
||||
throw "Unfortunately bug with libserial";
|
||||
}
|
||||
|
||||
RCLCPP_DEBUG(this->get_logger(), "Got following from rpi:{ x: %lf, y: %lf, z: %lf}\n", _x, _y, _theta);
|
||||
|
||||
make_transform(_x, _y, _theta);
|
||||
} catch (const std::exception& e) { RCLCPP_ERROR(this->get_logger(), "%s\n", e.what()); }
|
||||
}
|
||||
|
||||
void make_transform(double x, double y, double theta) {
|
||||
geometry_msgs::msg::TransformStamped t;
|
||||
|
||||
t.header.stamp = this->get_clock()->now();
|
||||
t.header.frame_id = this->get_parameter("odom").as_string();
|
||||
t.child_frame_id = this->get_parameter("target").as_string();
|
||||
|
||||
tf2::Quaternion q;
|
||||
q.setRPY(0, 0, theta);
|
||||
const tf2::Transform tf(tf2::Transform(q, tf2::Vector3(x, y, 0)));
|
||||
tf2::convert(tf, t.transform);
|
||||
|
||||
tf_static_broadcaster_->sendTransform(t);
|
||||
}
|
||||
};
|
||||
|
||||
int main(const int argc, const char** argv) {
|
||||
rclcpp::init(argc, argv);
|
||||
rclcpp::spin(std::make_shared<MgOdomPublisher>());
|
||||
rclcpp::shutdown();
|
||||
|
||||
return 0;
|
||||
}
|
||||
Reference in New Issue
Block a user