Initial commit

This commit is contained in:
2024-12-18 12:29:19 +01:00
commit fff7576e18
25 changed files with 1563 additions and 0 deletions

View File

@ -0,0 +1,57 @@
cmake_minimum_required(VERSION 3.8)
project(mg_odometry)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tf2 REQUIRED)
include(FindPkgConfig)
pkg_search_module(LIBSERIAL REQUIRED libserial)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
add_executable(mg_odom_publisher src/mg_odom_publisher.cpp)
ament_target_dependencies(
mg_odom_publisher
tf2
tf2_ros
rclcpp
)
target_include_directories(mg_odom_publisher PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>
${LIBSERIAL_INCLUDE_DIRS})
target_link_libraries(
mg_odom_publisher
${LIBSERIAL_LIBRARIES}
)
target_compile_features(mg_odom_publisher PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17
install(TARGETS mg_odom_publisher
DESTINATION lib/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

23
mg_odometry/package.xml Normal file
View File

@ -0,0 +1,23 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>mg_odometry</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="82343504+Pimpest@users.noreply.github.com">petar</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>libserial-dev</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@ -0,0 +1,91 @@
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include <libserial/SerialStream.h>
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2_ros/static_transform_broadcaster.h"
#define ENCODER_SERIAL_PATH_DEFAULT \
"/dev/serial/by-id/usb-Mg_Robotics_Magrob_Odometry_MCU_E661AC8863809024-if00"
class MgOdomPublisher : public rclcpp::Node {
public:
MgOdomPublisher()
: Node("mg_odom_publisher")
{
this->declare_parameter("odom", "odom_encoder");
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(10), 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()
{
RCLCPP_INFO(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;";
double _x,_y,_theta;
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());
sleep(1);
}
}
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();
t.transform.translation.x = x;
t.transform.translation.y = y;
t.transform.translation.z = 0.0;
tf2::Quaternion q;
q.setRPY(0.0, 0.0, theta);
t.transform.rotation.x = q.x();
t.transform.rotation.y = q.y();
t.transform.rotation.z = q.z();
t.transform.rotation.w = q.w();
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;
}