6 Commits

13 changed files with 343 additions and 1 deletions

View File

@ -37,6 +37,7 @@ set(SOURCES
add_executable(mg_bt_executor ${SOURCES})
add_executable(mg_i2cnode i2cmodule/i2cnode.cpp)
target_include_directories(
mg_bt_executor
@ -45,10 +46,14 @@ target_include_directories(
include
)
target_link_libraries(mg_i2cnode i2c)
ament_target_dependencies(mg_bt_executor ${PACKAGE_DEPS})
ament_target_dependencies(mg_i2cnode rclcpp mg_msgs)
install( TARGETS
mg_bt_executor
mg_i2cnode
DESTINATION lib/${PROJECT_NAME}
)

View File

@ -0,0 +1,47 @@
#include "rclcpp/rclcpp.hpp"
#include "mg_msgs/srv/i2c.hpp"
extern "C" {
#include <fcntl.h>
#include <linux/i2c-dev.h>
#include <sys/ioctl.h>
#include <i2c/smbus.h>
}
class MgI2c : public rclcpp::Node {
using I2cSrv = mg_msgs::srv::I2c;
public:
MgI2c(const std::string& name) : rclcpp::Node(name), i2c_fd_(open("/dev/i2c-1", O_RDWR)) { // NOLINT
auto cb
= [this](I2cSrv::Request::ConstSharedPtr req, I2cSrv::Response::SharedPtr resp) { send_req(req, resp); };
i2c_srv_ = create_service<I2cSrv>("/i2c", cb);
}
void send_req(I2cSrv::Request::ConstSharedPtr req, I2cSrv::Response::SharedPtr resp) const {
ioctl(i2c_fd_, I2C_SLAVE, req->addr); // NOLINT
i2c_smbus_write_byte(i2c_fd_, req->data);
int ch = 0;
rclcpp::Rate rate(100);
while (ch == 0 || (ch < 256 && ch > 0)) {
ch = i2c_smbus_read_byte(i2c_fd_);
rate.sleep();
}
resp->resp.push_back(ch);
RCLCPP_INFO(get_logger(), "Recieved %d", resp->resp.front());
}
private:
rclcpp::Service<mg_msgs::srv::I2c>::SharedPtr i2c_srv_;
int i2c_fd_;
};
int main(int argc, const char* const* argv) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MgI2c>("i2cu"));
rclcpp::shutdown();
return 0;
}

View File

@ -14,6 +14,7 @@
<depend>behaviortree_ros2</depend>
<depend>btcpp_ros2_interfaces</depend>
<depend>mg_msgs</depend>
<depend>libi2c-dev</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

View File

@ -2,6 +2,7 @@
#include "behaviortree_cpp/xml_parsing.h"
#include "tree_nodes/calib.hpp"
#include "tree_nodes/i2c.hpp"
#include "tree_nodes/move_point.hpp"
#include "tree_nodes/rotate.hpp"
#include "tree_nodes/zero.hpp"
@ -26,6 +27,7 @@ namespace mg {
factory.registerNodeType<mg::MovePointNode>("MovePoint", node());
factory.registerNodeType<mg::RotateNode>("RotateNode", node());
factory.registerNodeType<mg::ZeroNode>("ZeroNode", node());
factory.registerNodeType<mg::I2cNode>("I2CSignal", node());
factory.registerNodeType<mg::CalibWidthNode>("CalibWidth", node(), [this]() { return this->position(); });
}

View File

@ -0,0 +1,29 @@
#pragma once
#include "behaviortree_ros2/bt_service_node.hpp"
#include "mg_msgs/srv/i2c.hpp"
namespace mg {
class I2cNode : public BT::RosServiceNode<mg_msgs::srv::I2c> {
public:
I2cNode(const std::string& name, const BT::NodeConfig& conf, const BT::RosNodeParams& params) :
BT::RosServiceNode<mg_msgs::srv::I2c>(name, conf, params) { }
static BT::PortsList providedPorts() {
return providedBasicPorts({ BT::InputPort<int>("Address", 42, {}),
BT::InputPort<int>("Data", 0, {}),
BT::OutputPort<int>("Result") });
}
bool setRequest(typename Request::SharedPtr& req) override {
req->addr = getInput<int>("Address").value_or(42);
req->data = getInput<int>("Result").value_or(0);
return true;
}
BT::NodeStatus onResponseReceived(const typename Response::SharedPtr& resp) override {
setOutput<int>("Result", resp->resp.front());
return BT::NodeStatus::SUCCESS;
}
};
}

60
mg_lidar/CMakeLists.txt Normal file
View File

@ -0,0 +1,60 @@
cmake_minimum_required(VERSION 3.12)
project(mg_lidar)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
set(PACKAGE_DEPS
rclcpp
tf2
tf2_ros
tf2_geometry_msgs
mg_msgs
sensor_msgs
)
find_package(ament_cmake REQUIRED)
include(FindPkgConfig)
pkg_search_module(LIBGLM REQUIRED glm)
foreach(PACKAGE ${PACKAGE_DEPS})
find_package(${PACKAGE} REQUIRED)
endforeach()
set(SOURCES
src/scanner.cpp
)
add_executable(mg_scanner ${SOURCES})
target_include_directories(
mg_scanner
PRIVATE
${LIBGLM_INCLUDE_DIRS}
include
)
ament_target_dependencies(mg_scanner ${PACKAGE_DEPS})
install( TARGETS
mg_scanner
DESTINATION lib/${PROJECT_NAME}
)
install(DIRECTORY
config
launch
DESTINATION share/${PROJECT_NAME}/
)
target_compile_features(mg_scanner PUBLIC
c_std_99
cxx_std_17
) # Require C99 and C++17
ament_package()

View File

@ -0,0 +1,4 @@
rplidar_node:
ros__parameters:
scan_mode: "ppbig"
topic_name: "base-link"

28
mg_lidar/launch/launch.py Normal file
View File

@ -0,0 +1,28 @@
from launch import LaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from pathlib import Path
def generate_launch_description():
basedir = FindPackageShare("mg_lidar")
lidar_config = PathJoinSubstitution([basedir, "config/lidar.yaml"])
return LaunchDescription([
Node(
package='mg_lidar',
executable='mg_scanner',
output="screen",
parameters=[lidar_config]
),
Node(
package='rplidar_ros',
executable='rplidar_composition',
output="screen",
parameters=[lidar_config]
),
])

27
mg_lidar/package.xml Normal file
View File

@ -0,0 +1,27 @@
<?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_lidar</name>
<version>0.0.0</version>
<description>Lidar based opponent tracking</description>
<maintainer email="82343504+Pimpest@users.noreply.github.com">Pimpest</maintainer>
<license>Apache 2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>mg_msgs</depend>
<depend>std_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tf2_geometry_msgs</depend>
<depend>visualization_msgs</depend>
<depend>sensor_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

134
mg_lidar/src/scanner.cpp Normal file
View File

@ -0,0 +1,134 @@
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/laser_scan.hpp"
#include "geometry_msgs/msg/point_stamped.hpp"
#include "glm/glm.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"
#include "tf2/convert.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include <glm/gtx/norm.hpp>
class MgScanner : public rclcpp::Node {
using LaserScan = sensor_msgs::msg::LaserScan;
using PointStamped = geometry_msgs::msg::PointStamped;
public:
MgScanner() : rclcpp::Node("EnemyScanner") {
gen_rotations();
scan_sup_ = create_subscription<LaserScan>(
"scan", rclcpp::QoS(1), [this](LaserScan::ConstSharedPtr msg) { process_scan(msg); });
enemy_pub_ = create_publisher<PointStamped>("/dynamicObstacle", rclcpp::QoS(1));
tf_buf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buf_);
}
private:
rclcpp::Subscription<LaserScan>::SharedPtr scan_sup_;
rclcpp::Publisher<PointStamped>::SharedPtr enemy_pub_;
std::shared_ptr<tf2_ros::Buffer> tf_buf_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
std::vector<glm::dmat2> rotations;
void gen_rotations() {
constexpr double min_angle = -3.1241393089294434;
constexpr double max_angle = 3.1415927410125732;
constexpr double angle_increment = 0.008714509196579456;
double curr = min_angle;
while (curr <= max_angle) {
rotations.emplace_back(glm::cos(curr), glm::sin(curr), -glm::sin(curr), glm::cos(curr));
curr += angle_increment;
}
rotations.emplace_back(glm::cos(curr), glm::sin(curr), -glm::sin(curr), glm::cos(curr));
}
glm::dvec3 pos_query() {
RCLCPP_ERROR(get_logger(), "Works to here");
try {
double x = NAN;
double y = NAN;
double rot = NAN;
auto tmsg = tf_buf_->lookupTransform("odom", "base-link", tf2::TimePointZero);
tf2::Transform t;
tf2::convert(tmsg.transform, t);
t.getBasis().getRPY(x, y, rot);
auto vec3 = tmsg.transform.translation;
return { vec3.x, vec3.y, rot };
} catch (const tf2::TransformException& e) {
RCLCPP_ERROR(get_logger(), "Got following error when looking up transform:\n\t%s", e.what());
}
return { 0, 0, 0 };
}
static bool part_of_clump(const glm::dvec2 prev, glm::dvec2 curr) {
return glm::length2(prev - curr) < 0.05 * 0.05;
}
void process_scan(LaserScan::ConstSharedPtr msg) {
// TODO: finish processing
const glm::dvec3 v = pos_query();
const glm::dvec2 pos = { v.x, v.y };
const glm::dmat2 rot = { glm::cos(v.z), glm::sin(v.z), -glm::sin(v.z), glm::cos(v.z) };
double mini = INFINITY;
glm::dvec2 mini_pos = { 0, 0 };
glm::dvec2 prev = { -1, -1 };
glm::dvec2 clump = { -1, -1 };
int clump_size = 0;
bool good_clump = false;
if (msg->ranges.size() != rotations.size()) {
RCLCPP_ERROR(get_logger(),
"The amount of rotations differs from amount of ranges(%lu != %lu)",
msg->ranges.size(),
rotations.size());
}
for (uint i = 0; i < msg->ranges.size(); i++) {
if (msg->intensities.at(i) < 35.0) {
continue;
}
const glm::dvec2 potential_pos = rot * rotations.at(i) * glm::dvec2{ msg->ranges.at(i), 0 } + pos;
if (0.1 < potential_pos.x && potential_pos.x < 2.9 && 0.1 < potential_pos.y && potential_pos.y < 1.9) {
if (!part_of_clump(prev, potential_pos)) {
clump_size = 0;
clump = { 0, 0 };
}
good_clump |= mini > msg->ranges.at(i);
clump += potential_pos;
clump_size++;
if (good_clump) {
mini = msg->ranges.at(i);
mini_pos = clump / (double)clump_size;
}
}
prev = potential_pos;
}
if (mini < INFINITY) {
PointStamped m;
m.header.frame_id = "odom";
m.point.x = mini_pos.x;
m.point.y = mini_pos.y;
enemy_pub_->publish(m);
}
}
};
int main(const int argc, const char** argv) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MgScanner>());
rclcpp::shutdown();
}

View File

@ -19,6 +19,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"action/Rotate.action"
"srv/CalcPath.srv"
"srv/SendDouble.srv"
"srv/I2c.srv"
)
ament_package()

4
mg_msgs/srv/I2c.srv Normal file
View File

@ -0,0 +1,4 @@
uint8 addr
uint8 data
---
uint8[] resp

View File

@ -153,7 +153,7 @@ namespace mg {
double ObstacleManager::dist_to_bounds(glm::dvec2 pos, glm::dvec2 size, double rot) {
// Find me
const glm::dmat2 rot_mat{ { glm::cos(rot), -glm::sin(rot) }, { glm::sin(rot), glm::cos(rot) } };
const glm::dmat2 rot_mat{ { glm::cos(rot), glm::sin(rot) }, { -glm::sin(rot), glm::cos(rot) } };
return ObstacleManager::dist_to_bounds(pos, size, rot_mat);
}